40 constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z);
76 constexpr units::meter_t
X()
const {
return m_x; }
83 constexpr units::meter_t
Y()
const {
return m_y; }
90 constexpr units::meter_t
Z()
const {
return m_z; }
97 constexpr Eigen::Vector3d ToVector()
const;
189 units::meter_t m_x = 0_m;
190 units::meter_t m_y = 0_m;
191 units::meter_t m_z = 0_m;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
A rotation in a 3D coordinate frame represented by a quaternion.
Definition: Rotation3d.h:20
Represents a translation in 2D space.
Definition: Translation2d.h:27
Represents a translation in 3D space.
Definition: Translation3d.h:25
bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from the provided translation vector's X, Y, and Z components.
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation3d.h:83
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation3d.h:76
Translation3d(units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
constexpr units::meter_t Z() const
Returns the Z component of the translation.
Definition: Translation3d.h:90
units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
constexpr Translation3d()=default
Constructs a Translation3d with X, Y, and Z components equal to zero.
Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
state
Definition: core.h:2271
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr dimensionless::scalar_t operator/(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept
Division for convertible unit_t types with a linear scale.
Definition: base.h:2644
constexpr unit_t< Units, T, NonLinearScale > operator-(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2352
constexpr unit_t< Units, T, NonLinearScale > operator+(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2328
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588