8#include <initializer_list>
15#include "wpi/units/area.hpp"
16#include "wpi/units/length.hpp"
17#include "wpi/units/math.hpp"
50 wpi::units::meter_t z)
51 : m_x{x}, m_y{y}, m_z{z} {}
62 auto rectangular =
Translation3d{distance, 0_m, 0_m}.RotateBy(angle);
63 m_x = rectangular.X();
64 m_y = rectangular.Y();
65 m_z = rectangular.Z();
75 : m_x{
wpi::units::meter_t{vector.x()}},
76 m_y{
wpi::units::meter_t{vector.y()}},
77 m_z{
wpi::units::meter_t{vector.z()}} {}
100 return wpi::units::math::sqrt(wpi::units::math::pow<2>(other.m_x - m_x) +
101 wpi::units::math::pow<2>(other.m_y - m_y) +
102 wpi::units::math::pow<2>(other.m_z - m_z));
118 return wpi::units::math::pow<2>(other.m_x - m_x) +
119 wpi::units::math::pow<2>(other.m_y - m_y) +
120 wpi::units::math::pow<2>(other.m_z - m_z);
128 constexpr wpi::units::meter_t
X()
const {
return m_x; }
135 constexpr wpi::units::meter_t
Y()
const {
return m_y; }
142 constexpr wpi::units::meter_t
Z()
const {
return m_z; }
150 return Eigen::Vector3d{{m_x.value(), m_y.value(), m_z.value()}};
158 constexpr wpi::units::meter_t
Norm()
const {
159 return wpi::units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z);
170 return m_x * m_x + m_y * m_y + m_z * m_z;
184 Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()};
187 wpi::units::meter_t{qprime.Y()},
188 wpi::units::meter_t{qprime.Z()}};
200 return (*
this - other).
RotateBy(rot) + other;
213 return m_x * other.
X() + m_y * other.
Y() + m_z * other.
Z();
227 constexpr Eigen::Vector<wpi::units::square_meter_t, 3>
Cross(
229 return Eigen::Vector<wpi::units::square_meter_t, 3>{
230 {m_y * other.
Z() - other.
Y() * m_z},
231 {m_z * other.
X() - other.
Z() * m_x},
232 {m_x * other.
Y() - other.
X() * m_y}};
254 return {
X() + other.
X(),
Y() + other.
Y(),
Z() + other.
Z()};
290 return {scalar * m_x, scalar * m_y, scalar * m_z};
314 return wpi::units::math::abs(m_x - other.m_x) < 1E-9_m &&
315 wpi::units::math::abs(m_y - other.m_y) < 1E-9_m &&
316 wpi::units::math::abs(m_z - other.m_z) < 1E-9_m;
325 std::span<const Translation3d> translations)
const {
326 return *std::min_element(
327 translations.begin(), translations.end(),
329 return this->Distance(a) < this->Distance(b);
339 std::initializer_list<Translation3d> translations)
const {
340 return *std::min_element(
341 translations.begin(), translations.end(),
343 return this->Distance(a) < this->Distance(b);
348 wpi::units::meter_t m_x = 0_m;
349 wpi::units::meter_t m_y = 0_m;
350 wpi::units::meter_t m_z = 0_m;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a quaternion.
Definition Quaternion.hpp:23
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.hpp:134
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:72
constexpr const Quaternion & GetQuaternion() const
Returns the quaternion representation of the Rotation3d.
Definition Rotation3d.hpp:388
Represents a translation in 2D space.
Definition Translation2d.hpp:33
Represents a translation in 3D space.
Definition Translation3d.hpp:34
constexpr Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
Definition Translation3d.hpp:183
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:212
constexpr Translation3d(wpi::units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
Definition Translation3d.hpp:60
constexpr Translation3d operator-() const
Returns the inverse of the current translation.
Definition Translation3d.hpp:277
constexpr Translation3d RotateAround(const Translation3d &other, const Rotation3d &rot) const
Rotates this translation around another translation in 3D space.
Definition Translation3d.hpp:198
constexpr Translation3d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation3d.hpp:289
constexpr Translation3d operator+(const Translation3d &other) const
Returns the sum of two translations in 3D space.
Definition Translation3d.hpp:253
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:227
constexpr wpi::units::square_meter_t SquaredDistance(const Translation3d &other) const
Calculates the squared distance between two translations in 3D space.
Definition Translation3d.hpp:116
constexpr Eigen::Vector3d ToVector() const
Returns a 3D translation vector representation of this translation.
Definition Translation3d.hpp:149
constexpr Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from a 3D translation vector.
Definition Translation3d.hpp:74
constexpr Translation3d Nearest(std::span< const Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.hpp:324
constexpr wpi::units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
Definition Translation3d.hpp:99
constexpr wpi::units::square_meter_t SquaredNorm() const
Returns the squared norm, or squared distance from the origin to the translation.
Definition Translation3d.hpp:169
constexpr Translation2d ToTranslation2d() const
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
Definition Translation3d.hpp:239
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:338
constexpr Translation3d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation3d.hpp:303
constexpr wpi::units::meter_t Z() const
Returns the Z component of the translation.
Definition Translation3d.hpp:142
constexpr Translation3d(const Translation2d &translation)
Constructs a 3D translation from a 2D translation in the X-Y plane.
Definition Translation3d.hpp:86
constexpr wpi::units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation3d.hpp:135
constexpr wpi::units::meter_t X() const
Returns the X component of the translation.
Definition Translation3d.hpp:128
constexpr Translation3d operator-(const Translation3d &other) const
Returns the difference between two translations.
Definition Translation3d.hpp:267
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:49
constexpr wpi::units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation3d.hpp:158
constexpr bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Definition Translation3d.hpp:313
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 raw_os_ostream.hpp:19
Definition CvSource.hpp:15