8#include <initializer_list>
15#include "wpi/units/area.hpp"
16#include "wpi/units/length.hpp"
17#include "wpi/units/math.hpp"
47 wpi::units::meter_t z)
48 : m_x{x}, m_y{y}, m_z{z} {}
59 auto rectangular =
Translation3d{distance, 0_m, 0_m}.RotateBy(angle);
60 m_x = rectangular.X();
61 m_y = rectangular.Y();
62 m_z = rectangular.Z();
72 : m_x{
wpi::units::meter_t{vector.x()}},
73 m_y{
wpi::units::meter_t{vector.y()}},
74 m_z{
wpi::units::meter_t{vector.z()}} {}
97 return wpi::units::math::sqrt(wpi::units::math::pow<2>(other.m_x - m_x) +
98 wpi::units::math::pow<2>(other.m_y - m_y) +
99 wpi::units::math::pow<2>(other.m_z - m_z));
115 return wpi::units::math::pow<2>(other.m_x - m_x) +
116 wpi::units::math::pow<2>(other.m_y - m_y) +
117 wpi::units::math::pow<2>(other.m_z - m_z);
125 constexpr wpi::units::meter_t
X()
const {
return m_x; }
132 constexpr wpi::units::meter_t
Y()
const {
return m_y; }
139 constexpr wpi::units::meter_t
Z()
const {
return m_z; }
147 return Eigen::Vector3d{{m_x.value(), m_y.value(), m_z.value()}};
155 constexpr wpi::units::meter_t
Norm()
const {
156 return wpi::units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
167 return m_x * m_x + m_y * m_y + m_z * m_z;
181 Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()};
184 wpi::units::meter_t{qprime.Y()},
185 wpi::units::meter_t{qprime.Z()}};
197 return (*
this - other).
RotateBy(rot) + other;
210 return m_x * other.
X() + m_y * other.
Y() + m_z * other.
Z();
224 constexpr Eigen::Vector<wpi::units::square_meter_t, 3>
Cross(
226 return Eigen::Vector<wpi::units::square_meter_t, 3>{
227 {m_y * other.
Z() - other.
Y() * m_z},
228 {m_z * other.
X() - other.
Z() * m_x},
229 {m_x * other.
Y() - other.
X() * m_y}};
251 return {
X() + other.
X(),
Y() + other.
Y(),
Z() + other.
Z()};
287 return {scalar * m_x, scalar * m_y, scalar * m_z};
311 return wpi::units::math::abs(m_x - other.m_x) < 1E-9_m &&
312 wpi::units::math::abs(m_y - other.m_y) < 1E-9_m &&
313 wpi::units::math::abs(m_z - other.m_z) < 1E-9_m;
322 std::span<const Translation3d> translations)
const {
323 return *std::min_element(
324 translations.begin(), translations.end(),
326 return this->Distance(a) < this->Distance(b);
336 std::initializer_list<Translation3d> translations)
const {
337 return *std::min_element(
338 translations.begin(), translations.end(),
340 return this->Distance(a) < this->Distance(b);
345 wpi::units::meter_t m_x = 0_m;
346 wpi::units::meter_t m_y = 0_m;
347 wpi::units::meter_t m_z = 0_m;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a quaternion.
Definition Quaternion.hpp:20
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.hpp:131
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
constexpr const Quaternion & GetQuaternion() const
Returns the quaternion representation of the Rotation3d.
Definition Rotation3d.hpp:385
Represents a translation in 2D space.
Definition Translation2d.hpp:30
Represents a translation in 3D space.
Definition Translation3d.hpp:31
constexpr Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
Definition Translation3d.hpp:180
constexpr wpi::units::square_meter_t Dot(const Translation3d &other) const
Computes the dot product between this translation and another translation in 3D space.
Definition Translation3d.hpp:209
constexpr Translation3d(wpi::units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
Definition Translation3d.hpp:57
constexpr Translation3d operator-() const
Returns the inverse of the current translation.
Definition Translation3d.hpp:274
constexpr Translation3d RotateAround(const Translation3d &other, const Rotation3d &rot) const
Rotates this translation around another translation in 3D space.
Definition Translation3d.hpp:195
constexpr Translation3d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation3d.hpp:286
constexpr Translation3d operator+(const Translation3d &other) const
Returns the sum of two translations in 3D space.
Definition Translation3d.hpp:250
constexpr Eigen::Vector< wpi::units::square_meter_t, 3 > Cross(const Translation3d &other) const
Computes the cross product between this translation and another translation in 3D space.
Definition Translation3d.hpp:224
constexpr wpi::units::square_meter_t SquaredDistance(const Translation3d &other) const
Calculates the squared distance between two translations in 3D space.
Definition Translation3d.hpp:113
constexpr Eigen::Vector3d ToVector() const
Returns a 3D translation vector representation of this translation.
Definition Translation3d.hpp:146
constexpr Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from a 3D translation vector.
Definition Translation3d.hpp:71
constexpr Translation3d Nearest(std::span< const Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.hpp:321
constexpr wpi::units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
Definition Translation3d.hpp:96
constexpr wpi::units::square_meter_t SquaredNorm() const
Returns the squared norm, or squared distance from the origin to the translation.
Definition Translation3d.hpp:166
constexpr Translation2d ToTranslation2d() const
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
Definition Translation3d.hpp:236
constexpr Translation3d()=default
Constructs a Translation3d with X, Y, and Z components equal to zero.
constexpr Translation3d Nearest(std::initializer_list< Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.hpp:335
constexpr Translation3d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation3d.hpp:300
constexpr wpi::units::meter_t Z() const
Returns the Z component of the translation.
Definition Translation3d.hpp:139
constexpr Translation3d(const Translation2d &translation)
Constructs a 3D translation from a 2D translation in the X-Y plane.
Definition Translation3d.hpp:83
constexpr wpi::units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation3d.hpp:132
constexpr wpi::units::meter_t X() const
Returns the X component of the translation.
Definition Translation3d.hpp:125
constexpr Translation3d operator-(const Translation3d &other) const
Returns the difference between two translations.
Definition Translation3d.hpp:264
constexpr Translation3d(wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::meter_t z)
Constructs a Translation3d with the X, Y, and Z components equal to the provided values.
Definition Translation3d.hpp:46
constexpr wpi::units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation3d.hpp:155
constexpr bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Definition Translation3d.hpp:310
basic_json<> json
default specialization
Definition json_fwd.hpp:62
Definition LinearSystem.hpp:20
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
Definition CvSource.hpp:15