7#include <initializer_list>
70 constexpr units::meter_t
X()
const {
return m_x; }
77 constexpr units::meter_t
Y()
const {
return m_y; }
84 units::meter_t
Norm()
const;
189 std::initializer_list<Translation2d> translations)
const;
192 units::meter_t m_x = 0_m;
193 units::meter_t m_y = 0_m;
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseBinaryOp< internal::scalar_quotient_op< Scalar, typename OtherDerived::Scalar >, const Derived, const OtherDerived > operator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
Definition: ArrayCwiseBinaryOps.h:21
EIGEN_DEVICE_FUNC const NegativeReturnType operator-() const
Definition: CommonCwiseUnaryOps.h:45
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Represents a translation in 2D space.
Definition: Translation2d.h:29
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:70
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:77
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.
a class to store JSON values
Definition: json.h:2655
const Scalar & y
Definition: MathFunctions.h:821
Definition: AprilTagFieldLayout.h:22
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 unit_t< Units, T, NonLinearScale > operator+(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2328
/file This file defines the SmallVector class.
Definition: AprilTagFieldLayout.h:18