8#include <initializer_list>
17#include "units/area.h"
18#include "units/length.h"
19#include "units/math.h"
46 constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z)
47 : m_x{x}, m_y{y}, m_z{z} {}
58 m_x = rectangular.
X();
59 m_y = rectangular.Y();
60 m_z = rectangular.Z();
70 : m_x{units::meter_t{vector.x()}},
71 m_y{units::meter_t{vector.y()}},
72 m_z{units::meter_t{vector.z()}} {}
95 return units::math::sqrt(units::math::pow<2>(other.m_x - m_x) +
96 units::math::pow<2>(other.m_y - m_y) +
97 units::math::pow<2>(other.m_z - m_z));
113 return units::math::pow<2>(other.m_x - m_x) +
114 units::math::pow<2>(other.m_y - m_y) +
115 units::math::pow<2>(other.m_z - m_z);
123 constexpr units::meter_t
X()
const {
return m_x; }
130 constexpr units::meter_t
Y()
const {
return m_y; }
137 constexpr units::meter_t
Z()
const {
return m_z; }
145 return Eigen::Vector3d{{m_x.value(), m_y.value(), m_z.value()}};
153 constexpr units::meter_t
Norm()
const {
154 return units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
165 return m_x * m_x + m_y * m_y + m_z * m_z;
179 Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()};
180 auto qprime = other.GetQuaternion() *
p * other.GetQuaternion().Inverse();
181 return Translation3d{units::meter_t{qprime.X()}, units::meter_t{qprime.Y()},
182 units::meter_t{qprime.Z()}};
194 return (*
this - other).
RotateBy(rot) + other;
207 return m_x * other.X() + m_y * other.Y() + m_z * other.Z();
221 constexpr Eigen::Vector<units::square_meter_t, 3>
Cross(
223 return Eigen::Vector<units::square_meter_t, 3>{
224 {m_y * other.Z() - other.Y() * m_z},
225 {m_z * other.X() - other.Z() * m_x},
226 {m_x * other.Y() - other.X() * m_y}};
248 return {X() + other.X(), Y() + other.Y(), Z() + other.Z()};
262 return operator+(-other);
284 return {scalar * m_x, scalar * m_y, scalar * m_z};
298 return operator*(1.0 / scalar);
308 return units::math::abs(m_x - other.m_x) < 1E-9_m &&
309 units::math::abs(m_y - other.m_y) < 1E-9_m &&
310 units::math::abs(m_z - other.m_z) < 1E-9_m;
319 std::span<const Translation3d> translations)
const {
320 return *std::min_element(
321 translations.begin(), translations.end(),
323 return this->Distance(a) < this->Distance(b);
333 std::initializer_list<Translation3d> translations)
const {
334 return *std::min_element(
335 translations.begin(), translations.end(),
337 return this->Distance(a) < this->Distance(b);
342 units::meter_t m_x = 0_m;
343 units::meter_t m_y = 0_m;
344 units::meter_t m_z = 0_m;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
Represents a quaternion.
Definition Quaternion.h:19
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Represents a translation in 2D space.
Definition Translation2d.h:30
Represents a translation in 3D space.
Definition Translation3d.h:31
constexpr Translation3d Nearest(std::initializer_list< Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.h:332
constexpr Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
Definition Translation3d.h:178
constexpr Translation3d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation3d.h:297
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation3d.h:130
constexpr Translation3d RotateAround(const Translation3d &other, const Rotation3d &rot) const
Rotates this translation around another translation in 3D space.
Definition Translation3d.h:192
constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z)
Constructs a Translation3d with the X, Y, and Z components equal to the provided values.
Definition Translation3d.h:46
constexpr Eigen::Vector< 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.h:221
constexpr bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Definition Translation3d.h:307
constexpr Translation3d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation3d.h:283
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation3d.h:123
constexpr units::square_meter_t SquaredDistance(const Translation3d &other) const
Calculates the squared distance between two translations in 3D space.
Definition Translation3d.h:111
constexpr units::meter_t Z() const
Returns the Z component of the translation.
Definition Translation3d.h:137
constexpr units::square_meter_t SquaredNorm() const
Returns the squared norm, or squared distance from the origin to the translation.
Definition Translation3d.h:164
constexpr Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from a 3D translation vector.
Definition Translation3d.h:69
constexpr Translation3d(const Translation2d &translation)
Constructs a 3D translation from a 2D translation in the X-Y plane.
Definition Translation3d.h:81
constexpr Translation3d operator-() const
Returns the inverse of the current translation.
Definition Translation3d.h:271
constexpr Translation3d operator+(const Translation3d &other) const
Returns the sum of two translations in 3D space.
Definition Translation3d.h:247
constexpr units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation3d.h:153
constexpr Translation3d operator-(const Translation3d &other) const
Returns the difference between two translations.
Definition Translation3d.h:261
constexpr units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
Definition Translation3d.h:94
constexpr Translation2d ToTranslation2d() const
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
Definition Translation3d.h:233
constexpr Translation3d()=default
Constructs a Translation3d with X, Y, and Z components equal to zero.
constexpr Translation3d Nearest(std::span< const Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.h:318
constexpr units::square_meter_t Dot(const Translation3d &other) const
Computes the dot product between this translation and another translation in 3D space.
Definition Translation3d.h:206
constexpr Translation3d(units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
Definition Translation3d.h:56
constexpr Eigen::Vector3d ToVector() const
Returns a 3D translation vector representation of this translation.
Definition Translation3d.h:144
Definition SystemServer.h:9
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)