8#include <initializer_list>
54 : m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {}
63 : m_x{
units::meter_t{vector.x()}}, m_y{
units::meter_t{vector.y()}} {}
83 constexpr units::meter_t
X()
const {
return m_x; }
90 constexpr units::meter_t
Y()
const {
return m_y; }
98 return Eigen::Vector2d{{m_x.value(), m_y.value()}};
136 return {m_x * other.Cos() - m_y * other.Sin(),
137 m_x * other.Sin() + m_y * other.Cos()};
154 return {(m_x - other.X()) * rot.
Cos() - (m_y - other.Y()) * rot.
Sin() +
156 (m_x - other.X()) * rot.
Sin() + (m_y - other.Y()) * rot.
Cos() +
171 return {X() + other.X(), Y() + other.Y()};
185 return *
this + -other;
220 return operator*(1.0 /
scalar);
240 std::span<const Translation2d> translations)
const {
241 return *std::min_element(translations.begin(), translations.end(),
243 return this->Distance(a) < this->Distance(b);
253 std::initializer_list<Translation2d> translations)
const {
254 return *std::min_element(translations.begin(), translations.end(),
256 return this->Distance(a) < this->Distance(b);
261 units::meter_t m_x = 0_m;
262 units::meter_t m_y = 0_m;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:231
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:238
Represents a translation in 2D space.
Definition Translation2d.h:29
constexpr Translation2d(const Eigen::Vector2d &vector)
Constructs a Translation2d from a 2D translation vector.
Definition Translation2d.h:62
constexpr units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation2d.h:106
constexpr Translation2d Nearest(std::initializer_list< Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.h:252
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition Translation2d.h:152
constexpr Translation2d operator-() const
Returns the inverse of the current translation.
Definition Translation2d.h:195
constexpr Translation2d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation2d.h:219
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.h:135
constexpr Translation2d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation2d.h:206
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:90
constexpr units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.h:74
constexpr Translation2d operator-(const Translation2d &other) const
Returns the difference between two translations.
Definition Translation2d.h:184
constexpr Rotation2d Angle() const
Returns the angle this translation forms with the positive X axis.
Definition Translation2d.h:113
constexpr Eigen::Vector2d ToVector() const
Returns a 2D translation vector representation of this translation.
Definition Translation2d.h:97
constexpr bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Definition Translation2d.h:229
constexpr Translation2d operator+(const Translation2d &other) const
Returns the sum of two translations in 2D space.
Definition Translation2d.h:170
constexpr Translation2d(units::meter_t distance, const Rotation2d &angle)
Constructs a Translation2d with the provided distance and angle.
Definition Translation2d.h:53
constexpr Translation2d Nearest(std::span< const Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.h:239
constexpr Translation2d(units::meter_t x, units::meter_t y)
Constructs a Translation2d with the X and Y components equal to the provided values.
Definition Translation2d.h:43
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr UnitTypeLhs hypot(const UnitTypeLhs &x, const UnitTypeRhs &y)
Computes the square root of the sum-of-squares of x and y.
Definition math.h:508
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
Unit Conversion Library namespace.
Definition acceleration.h:33
Type representing an arbitrary unit.
Definition base.h:888