8#include <initializer_list>
16#include "units/area.h"
17#include "units/length.h"
18#include "units/math.h"
55 : m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {}
64 : m_x{units::meter_t{vector.x()}}, m_y{units::meter_t{vector.y()}} {}
76 return units::math::hypot(other.m_x - m_x, other.m_y - m_y);
92 return units::math::pow<2>(other.m_x - m_x) +
93 units::math::pow<2>(other.m_y - m_y);
101 constexpr units::meter_t
X()
const {
return m_x; }
108 constexpr units::meter_t
Y()
const {
return m_y; }
116 return Eigen::Vector2d{{m_x.value(), m_y.value()}};
124 constexpr units::meter_t
Norm()
const {
return units::math::hypot(m_x, m_y); }
134 return units::math::pow<2>(m_x) + units::math::pow<2>(m_y);
165 return {m_x * other.Cos() - m_y * other.Sin(),
166 m_x * other.Sin() + m_y * other.Cos()};
183 return {(m_x - other.X()) * rot.
Cos() - (m_y - other.Y()) * rot.
Sin() +
185 (m_x - other.X()) * rot.
Sin() + (m_y - other.Y()) * rot.
Cos() +
199 return m_x * other.X() + m_y * other.Y();
212 return m_x * other.Y() - m_y * other.X();
226 return {X() + other.X(), Y() + other.Y()};
240 return *
this + -other;
262 return {scalar * m_x, scalar * m_y};
275 return operator*(1.0 / scalar);
285 return units::math::abs(m_x - other.m_x) < 1E-9_m &&
286 units::math::abs(m_y - other.m_y) < 1E-9_m;
295 std::span<const Translation2d> translations)
const {
296 return *std::min_element(
297 translations.begin(), translations.end(),
299 return this->Distance(a) < this->Distance(b);
309 std::initializer_list<Translation2d> translations)
const {
310 return *std::min_element(
311 translations.begin(), translations.end(),
313 return this->Distance(a) < this->Distance(b);
318 units::meter_t m_x = 0_m;
319 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:26
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:222
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:229
Represents a translation in 2D space.
Definition Translation2d.h:30
constexpr Translation2d(const Eigen::Vector2d &vector)
Constructs a Translation2d from a 2D translation vector.
Definition Translation2d.h:63
constexpr units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation2d.h:124
constexpr Translation2d Nearest(std::initializer_list< Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.h:308
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:181
constexpr Translation2d operator-() const
Returns the inverse of the current translation.
Definition Translation2d.h:250
constexpr Translation2d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation2d.h:274
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:101
constexpr units::square_meter_t SquaredDistance(const Translation2d &other) const
Calculates the square of the distance between two translations in 2D space.
Definition Translation2d.h:90
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.h:164
constexpr Translation2d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation2d.h:261
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:108
constexpr units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.h:75
constexpr Translation2d operator-(const Translation2d &other) const
Returns the difference between two translations.
Definition Translation2d.h:239
constexpr Rotation2d Angle() const
Returns the angle this translation forms with the positive X axis.
Definition Translation2d.h:142
constexpr units::square_meter_t SquaredNorm() const
Returns the squared norm, or squared distance from the origin to the translation.
Definition Translation2d.h:133
constexpr Eigen::Vector2d ToVector() const
Returns a 2D translation vector representation of this translation.
Definition Translation2d.h:115
constexpr bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Definition Translation2d.h:284
constexpr units::square_meter_t Dot(const Translation2d &other) const
Computes the dot product between this translation and another translation in 2D space.
Definition Translation2d.h:198
constexpr Translation2d operator+(const Translation2d &other) const
Returns the sum of two translations in 2D space.
Definition Translation2d.h:225
constexpr Translation2d(units::meter_t distance, const Rotation2d &angle)
Constructs a Translation2d with the provided distance and angle.
Definition Translation2d.h:54
constexpr Translation2d Nearest(std::span< const Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.h:294
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:44
constexpr units::square_meter_t Cross(const Translation2d &other) const
Computes the cross product between this translation and another translation in 2D space.
Definition Translation2d.h:211
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)