7#include <initializer_list>
76 constexpr units::meter_t
X()
const {
return m_x; }
83 constexpr units::meter_t
Y()
const {
return m_y; }
90 constexpr Eigen::Vector2d ToVector()
const;
97 units::meter_t
Norm()
const;
202 std::initializer_list<Translation2d> translations)
const;
205 units::meter_t m_x = 0_m;
206 units::meter_t m_y = 0_m;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a translation in 2D space.
Definition: Translation2d.h:27
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Translation2d Nearest(std::span< const Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:76
Translation2d Nearest(std::initializer_list< Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:83
units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Translation2d(const Eigen::Vector2d &vector)
Constructs a Translation2d from the provided translation vector's X and Y components.
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