10 #include <units/units.h>
12 #include "Rotation2d.h"
61 units::meter_t
X()
const {
return m_x; }
68 units::meter_t
Y()
const {
return m_y; }
75 units::meter_t
Norm()
const;
215 units::meter_t m_x = 0_m;
216 units::meter_t m_y = 0_m;
219 void to_json(
wpi::json& json,
const Translation2d& state);
221 void from_json(
const wpi::json& json, Translation2d& state);
a class to store JSON values
Definition: json.h:2655
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
units::meter_t X() const
Returns the X component of the translation.
Definition: Translation2d.h:61
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:22
bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Represents a translation in 2d space.
Definition: Translation2d.h:28
WPILib C++ utilities (wpiutil) namespace.
Definition: EventLoopRunner.h:17
Translation2d operator/(double scalar) const
Divides the translation by a scalar and returns the new translation.
units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2d space.
bool operator!=(const Translation2d &other) const
Checks inequality between this Translation2d and another object.
Translation2d operator-() const
Returns the inverse of the current translation.
Translation2d operator*(double scalar) const
Multiplies the translation by a scalar and returns the new translation.
Translation2d operator+(const Translation2d &other) const
Adds two translations in 2d space and returns the sum.
A class that enforces constraints on the differential drive kinematics.
Definition: SPIAccelerometerSim.h:16
Translation2d & operator-=(const Translation2d &other)
Subtracts the new translation from the current translation.
units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation2d.h:68
Translation2d & operator+=(const Translation2d &other)
Adds the new translation to the current translation.
Translation2d & operator*=(double scalar)
Multiplies the current translation by a scalar.
Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2d space.