8#include <initializer_list>
14#include "wpi/units/area.hpp"
15#include "wpi/units/length.hpp"
16#include "wpi/units/math.hpp"
58 : m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {}
67 : m_x{
wpi::units::meter_t{vector.x()}},
68 m_y{
wpi::units::meter_t{vector.y()}} {}
80 return wpi::units::math::hypot(other.m_x - m_x, other.m_y - m_y);
96 return wpi::units::math::pow<2>(other.m_x - m_x) +
97 wpi::units::math::pow<2>(other.m_y - m_y);
105 constexpr wpi::units::meter_t
X()
const {
return m_x; }
112 constexpr wpi::units::meter_t
Y()
const {
return m_y; }
120 return Eigen::Vector2d{{m_x.value(), m_y.value()}};
128 constexpr wpi::units::meter_t
Norm()
const {
129 return wpi::units::math::hypot(m_x, m_y);
140 return wpi::units::math::pow<2>(m_x) + wpi::units::math::pow<2>(m_y);
171 return {m_x * other.
Cos() - m_y * other.
Sin(),
172 m_x * other.
Sin() + m_y * other.
Cos()};
189 return {(m_x - other.
X()) * rot.
Cos() - (m_y - other.
Y()) * rot.
Sin() +
191 (m_x - other.
X()) * rot.
Sin() + (m_y - other.
Y()) * rot.
Cos() +
205 return m_x * other.
X() + m_y * other.
Y();
218 return m_x * other.
Y() - m_y * other.
X();
232 return {
X() + other.
X(),
Y() + other.
Y()};
246 return *
this + -other;
268 return {scalar * m_x, scalar * m_y};
291 return wpi::units::math::abs(m_x - other.m_x) < 1E-9_m &&
292 wpi::units::math::abs(m_y - other.m_y) < 1E-9_m;
301 std::span<const Translation2d> translations)
const {
302 return *std::min_element(
303 translations.begin(), translations.end(),
305 return this->Distance(a) < this->Distance(b);
315 std::initializer_list<Translation2d> translations)
const {
316 return *std::min_element(
317 translations.begin(), translations.end(),
319 return this->Distance(a) < this->Distance(b);
324 wpi::units::meter_t m_x = 0_m;
325 wpi::units::meter_t m_y = 0_m;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:29
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.hpp:238
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.hpp:245
Represents a translation in 2D space.
Definition Translation2d.hpp:33
constexpr Rotation2d Angle() const
Returns the angle this translation forms with the positive X axis.
Definition Translation2d.hpp:148
constexpr Translation2d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation2d.hpp:280
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.hpp:170
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition Translation2d.hpp:187
constexpr wpi::units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.hpp:112
constexpr bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Definition Translation2d.hpp:290
constexpr Translation2d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation2d.hpp:267
constexpr wpi::units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.hpp:105
constexpr Translation2d operator-() const
Returns the inverse of the current translation.
Definition Translation2d.hpp:256
constexpr Translation2d Nearest(std::initializer_list< Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.hpp:314
constexpr wpi::units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation2d.hpp:128
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
constexpr wpi::units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.hpp:79
constexpr Translation2d(wpi::units::meter_t distance, const Rotation2d &angle)
Constructs a Translation2d with the provided distance and angle.
Definition Translation2d.hpp:57
constexpr Eigen::Vector2d ToVector() const
Returns a 2D translation vector representation of this translation.
Definition Translation2d.hpp:119
constexpr Translation2d operator+(const Translation2d &other) const
Returns the sum of two translations in 2D space.
Definition Translation2d.hpp:231
constexpr wpi::units::square_meter_t Cross(const Translation2d &other) const
Computes the cross product between this translation and another translation in 2D space.
Definition Translation2d.hpp:217
constexpr Translation2d(const Eigen::Vector2d &vector)
Constructs a Translation2d from a 2D translation vector.
Definition Translation2d.hpp:66
constexpr wpi::units::square_meter_t Dot(const Translation2d &other) const
Computes the dot product between this translation and another translation in 2D space.
Definition Translation2d.hpp:204
constexpr Translation2d Nearest(std::span< const Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.hpp:300
constexpr wpi::units::square_meter_t SquaredNorm() const
Returns the squared norm, or squared distance from the origin to the translation.
Definition Translation2d.hpp:139
constexpr wpi::units::square_meter_t SquaredDistance(const Translation2d &other) const
Calculates the square of the distance between two translations in 2D space.
Definition Translation2d.hpp:94
constexpr Translation2d operator-(const Translation2d &other) const
Returns the difference between two translations.
Definition Translation2d.hpp:245
constexpr Translation2d(wpi::units::meter_t x, wpi::units::meter_t y)
Constructs a Translation2d with the X and Y components equal to the provided values.
Definition Translation2d.hpp:47
Definition LinearSystem.hpp:20
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
Definition raw_os_ostream.hpp:19
Definition CvSource.hpp:15