8#include <initializer_list>
45 constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z)
46 : m_x{x}, m_y{y}, m_z{z} {}
57 m_x = rectangular.
X();
58 m_y = rectangular.Y();
59 m_z = rectangular.Z();
69 : m_x{
units::meter_t{vector.x()}},
70 m_y{
units::meter_t{vector.y()}},
71 m_z{
units::meter_t{vector.z()}} {}
104 constexpr units::meter_t
X()
const {
return m_x; }
111 constexpr units::meter_t
Y()
const {
return m_y; }
118 constexpr units::meter_t
Z()
const {
return m_z; }
126 return Eigen::Vector3d{{m_x.value(), m_y.value(), m_z.value()}};
134 constexpr units::meter_t
Norm()
const {
149 Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()};
150 auto qprime = other.GetQuaternion() * p * other.GetQuaternion().
Inverse();
151 return Translation3d{units::meter_t{qprime.X()}, units::meter_t{qprime.Y()},
152 units::meter_t{qprime.Z()}};
164 return (*
this - other).
RotateBy(rot) + other;
186 return {X() + other.X(), Y() + other.Y(), Z() + other.Z()};
200 return operator+(-other);
236 return operator*(1.0 /
scalar);
257 std::span<const Translation3d> translations)
const {
258 return *std::min_element(
259 translations.begin(), translations.end(),
261 return this->Distance(a) < this->Distance(b);
271 std::initializer_list<Translation3d> translations)
const {
272 return *std::min_element(
273 translations.begin(), translations.end(),
275 return this->Distance(a) < this->Distance(b);
280 units::meter_t m_x = 0_m;
281 units::meter_t m_y = 0_m;
282 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
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.h:130
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Represents a translation in 2D space.
Definition Translation2d.h:29
Represents a translation in 3D space.
Definition Translation3d.h:30
constexpr Translation3d Nearest(std::initializer_list< Translation3d > translations) const
Returns the nearest Translation3d from a collection of translations.
Definition Translation3d.h:270
constexpr Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
Definition Translation3d.h:148
constexpr Translation3d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation3d.h:235
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation3d.h:111
constexpr Translation3d RotateAround(const Translation3d &other, const Rotation3d &rot) const
Rotates this translation around another translation in 3D space.
Definition Translation3d.h:162
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:45
constexpr bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Definition Translation3d.h:245
constexpr Translation3d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation3d.h:221
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation3d.h:104
constexpr units::meter_t Z() const
Returns the Z component of the translation.
Definition Translation3d.h:118
constexpr Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from a 3D translation vector.
Definition Translation3d.h:68
constexpr Translation3d(const Translation2d &translation)
Constructs a 3D translation from a 2D translation in the X-Y plane.
Definition Translation3d.h:80
constexpr Translation3d operator-() const
Returns the inverse of the current translation.
Definition Translation3d.h:209
constexpr Translation3d operator+(const Translation3d &other) const
Returns the sum of two translations in 3D space.
Definition Translation3d.h:185
constexpr units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation3d.h:134
constexpr Translation3d operator-(const Translation3d &other) const
Returns the difference between two translations.
Definition Translation3d.h:199
constexpr units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
Definition Translation3d.h:93
constexpr Translation2d ToTranslation2d() const
Returns a Translation2d representing this Translation3d projected into the X-Y plane.
Definition Translation3d.h:171
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:256
constexpr Translation3d(units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
Definition Translation3d.h:55
constexpr Eigen::Vector3d ToVector() const
Returns a 3D translation vector representation of this translation.
Definition Translation3d.h:125
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition math.h:485
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)
constexpr auto pow(const UnitType &value) noexcept -> unit_t< typename units::detail::power_of_unit< power, typename units::traits::unit_t_traits< UnitType >::unit_type >::type, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the value of value raised to the power
Definition base.h:2810
Unit Conversion Library namespace.
Definition acceleration.h:33
Type representing an arbitrary unit.
Definition base.h:888