WPILibC++ 2023.4.3
frc::Translation2d Class Reference

Represents a translation in 2D space. More...

#include <frc/geometry/Translation2d.h>

Public Member Functions

constexpr Translation2d ()=default
 Constructs a Translation2d with X and Y components equal to zero. More...
 
constexpr Translation2d (units::meter_t x, units::meter_t y)
 Constructs a Translation2d with the X and Y components equal to the provided values. More...
 
constexpr Translation2d (units::meter_t distance, const Rotation2d &angle)
 Constructs a Translation2d with the provided distance and angle. More...
 
units::meter_t Distance (const Translation2d &other) const
 Calculates the distance between two translations in 2D space. More...
 
constexpr units::meter_t X () const
 Returns the X component of the translation. More...
 
constexpr units::meter_t Y () const
 Returns the Y component of the translation. More...
 
units::meter_t Norm () const
 Returns the norm, or distance from the origin to the translation. More...
 
constexpr Rotation2d Angle () const
 Returns the angle this translation forms with the positive X axis. More...
 
constexpr Translation2d RotateBy (const Rotation2d &other) const
 Applies a rotation to the translation in 2D space. More...
 
constexpr Translation2d operator+ (const Translation2d &other) const
 Returns the sum of two translations in 2D space. More...
 
constexpr Translation2d operator- (const Translation2d &other) const
 Returns the difference between two translations. More...
 
constexpr Translation2d operator- () const
 Returns the inverse of the current translation. More...
 
constexpr Translation2d operator* (double scalar) const
 Returns the translation multiplied by a scalar. More...
 
constexpr Translation2d operator/ (double scalar) const
 Returns the translation divided by a scalar. More...
 
bool operator== (const Translation2d &other) const
 Checks equality between this Translation2d and another object. More...
 
Translation2d Nearest (std::span< const Translation2d > translations) const
 Returns the nearest Translation2d from a collection of translations. More...
 
Translation2d Nearest (std::initializer_list< Translation2d > translations) const
 Returns the nearest Translation2d from a collection of translations. More...
 

Detailed Description

Represents a translation in 2D space.

This object can be used to represent a point or a vector.

This assumes that you are using conventional mathematical axes. When the robot is at the origin facing in the positive X direction, forward is positive X and left is positive Y.

Constructor & Destructor Documentation

◆ Translation2d() [1/3]

constexpr frc::Translation2d::Translation2d ( )
constexprdefault

Constructs a Translation2d with X and Y components equal to zero.

◆ Translation2d() [2/3]

constexpr frc::Translation2d::Translation2d ( units::meter_t  x,
units::meter_t  y 
)
constexpr

Constructs a Translation2d with the X and Y components equal to the provided values.

Parameters
xThe x component of the translation.
yThe y component of the translation.

◆ Translation2d() [3/3]

constexpr frc::Translation2d::Translation2d ( units::meter_t  distance,
const Rotation2d angle 
)
constexpr

Constructs a Translation2d with the provided distance and angle.

This is essentially converting from polar coordinates to Cartesian coordinates.

Parameters
distanceThe distance from the origin to the end of the translation.
angleThe angle between the x-axis and the translation vector.

Member Function Documentation

◆ Angle()

constexpr Rotation2d frc::Translation2d::Angle ( ) const
constexpr

Returns the angle this translation forms with the positive X axis.

Returns
The angle of the translation

◆ Distance()

units::meter_t frc::Translation2d::Distance ( const Translation2d other) const

Calculates the distance between two translations in 2D space.

The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).

Parameters
otherThe translation to compute the distance to.
Returns
The distance between the two translations.

◆ Nearest() [1/2]

Translation2d frc::Translation2d::Nearest ( std::initializer_list< Translation2d translations) const

Returns the nearest Translation2d from a collection of translations.

Parameters
translationsThe collection of translations.
Returns
The nearest Translation2d from the collection.

◆ Nearest() [2/2]

Translation2d frc::Translation2d::Nearest ( std::span< const Translation2d translations) const

Returns the nearest Translation2d from a collection of translations.

Parameters
translationsThe collection of translations.
Returns
The nearest Translation2d from the collection.

◆ Norm()

units::meter_t frc::Translation2d::Norm ( ) const

Returns the norm, or distance from the origin to the translation.

Returns
The norm of the translation.

◆ operator*()

constexpr Translation2d frc::Translation2d::operator* ( double  scalar) const
constexpr

Returns the translation multiplied by a scalar.

For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}.

Parameters
scalarThe scalar to multiply by.
Returns
The scaled translation.

◆ operator+()

constexpr Translation2d frc::Translation2d::operator+ ( const Translation2d other) const
constexpr

Returns the sum of two translations in 2D space.

For example, Translation3d{1.0, 2.5} + Translation3d{2.0, 5.5} = Translation3d{3.0, 8.0}.

Parameters
otherThe translation to add.
Returns
The sum of the translations.

◆ operator-() [1/2]

constexpr Translation2d frc::Translation2d::operator- ( ) const
constexpr

Returns the inverse of the current translation.

This is equivalent to rotating by 180 degrees, flipping the point over both axes, or negating all components of the translation.

Returns
The inverse of the current translation.

◆ operator-() [2/2]

constexpr Translation2d frc::Translation2d::operator- ( const Translation2d other) const
constexpr

Returns the difference between two translations.

For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} = Translation2d{4.0, 2.0}.

Parameters
otherThe translation to subtract.
Returns
The difference between the two translations.

◆ operator/()

constexpr Translation2d frc::Translation2d::operator/ ( double  scalar) const
constexpr

Returns the translation divided by a scalar.

For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}.

Parameters
scalarThe scalar to divide by.
Returns
The scaled translation.

◆ operator==()

bool frc::Translation2d::operator== ( const Translation2d other) const

Checks equality between this Translation2d and another object.

Parameters
otherThe other object.
Returns
Whether the two objects are equal.

◆ RotateBy()

constexpr Translation2d frc::Translation2d::RotateBy ( const Rotation2d other) const
constexpr

Applies a rotation to the translation in 2D space.

This multiplies the translation vector by a counterclockwise rotation matrix of the given angle.

[x_new]   [other.cos, -other.sin][x]
[y_new] = [other.sin,  other.cos][y]

For example, rotating a Translation2d of <2, 0> by 90 degrees will return a Translation2d of <0, 2>.

Parameters
otherThe rotation to rotate the translation by.
Returns
The new rotated translation.

◆ X()

constexpr units::meter_t frc::Translation2d::X ( ) const
inlineconstexpr

Returns the X component of the translation.

Returns
The X component of the translation.

◆ Y()

constexpr units::meter_t frc::Translation2d::Y ( ) const
inlineconstexpr

Returns the Y component of the translation.

Returns
The Y component of the translation.

The documentation for this class was generated from the following files: