WPILibC++ 2027.0.0-alpha-3
Loading...
Searching...
No Matches
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.
 
constexpr Translation2d (units::meter_t x, units::meter_t y)
 Constructs a Translation2d with the X and Y components equal to the provided values.
 
constexpr Translation2d (units::meter_t distance, const Rotation2d &angle)
 Constructs a Translation2d with the provided distance and angle.
 
constexpr Translation2d (const Eigen::Vector2d &vector)
 Constructs a Translation2d from a 2D translation vector.
 
constexpr units::meter_t Distance (const Translation2d &other) const
 Calculates the distance between two translations in 2D space.
 
constexpr units::square_meter_t SquaredDistance (const Translation2d &other) const
 Calculates the square of the distance between two translations in 2D space.
 
constexpr units::meter_t X () const
 Returns the X component of the translation.
 
constexpr units::meter_t Y () const
 Returns the Y component of the translation.
 
constexpr Eigen::Vector2d ToVector () const
 Returns a 2D translation vector representation of this translation.
 
constexpr units::meter_t Norm () const
 Returns the norm, or distance from the origin to the translation.
 
constexpr units::square_meter_t SquaredNorm () const
 Returns the squared norm, or squared distance from the origin to the translation.
 
constexpr Rotation2d Angle () const
 Returns the angle this translation forms with the positive X axis.
 
constexpr Translation2d RotateBy (const Rotation2d &other) const
 Applies a rotation to the translation in 2D space.
 
constexpr Translation2d RotateAround (const Translation2d &other, const Rotation2d &rot) const
 Rotates this translation around another translation in 2D space.
 
constexpr units::square_meter_t Dot (const Translation2d &other) const
 Computes the dot product between this translation and another translation in 2D space.
 
constexpr units::square_meter_t Cross (const Translation2d &other) const
 Computes the cross product between this translation and another translation in 2D space.
 
constexpr Translation2d operator+ (const Translation2d &other) const
 Returns the sum of two translations in 2D space.
 
constexpr Translation2d operator- (const Translation2d &other) const
 Returns the difference between two translations.
 
constexpr Translation2d operator- () const
 Returns the inverse of the current translation.
 
constexpr Translation2d operator* (double scalar) const
 Returns the translation multiplied by a scalar.
 
constexpr Translation2d operator/ (double scalar) const
 Returns the translation divided by a scalar.
 
constexpr bool operator== (const Translation2d &other) const
 Checks equality between this Translation2d and another object.
 
constexpr Translation2d Nearest (std::span< const Translation2d > translations) const
 Returns the nearest Translation2d from a collection of translations.
 
constexpr Translation2d Nearest (std::initializer_list< Translation2d > translations) const
 Returns the nearest Translation2d from a collection of translations.
 

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/4]

frc::Translation2d::Translation2d ( )
constexprdefault

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

◆ Translation2d() [2/4]

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

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/4]

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

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.

◆ Translation2d() [4/4]

frc::Translation2d::Translation2d ( const Eigen::Vector2d & vector)
inlineexplicitconstexpr

Constructs a Translation2d from a 2D translation vector.

The values are assumed to be in meters.

Parameters
vectorThe translation vector.

Member Function Documentation

◆ Angle()

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

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

Returns
The angle of the translation

◆ Cross()

units::square_meter_t frc::Translation2d::Cross ( const Translation2d & other) const
inlineconstexpr

Computes the cross product between this translation and another translation in 2D space.

The 2D cross product between two translations is defined as x₁y₂-x₂y₁.

Parameters
otherThe translation to compute the cross product with.
Returns
The cross product between the two translations.

◆ Distance()

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

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.

◆ Dot()

units::square_meter_t frc::Translation2d::Dot ( const Translation2d & other) const
inlineconstexpr

Computes the dot product between this translation and another translation in 2D space.

The dot product between two translations is defined as x₁x₂+y₁y₂.

Parameters
otherThe translation to compute the dot product with.
Returns
The dot product between the two translations.

◆ Nearest() [1/2]

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

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
inlineconstexpr

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
inlineconstexpr

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

Returns
The norm of the translation.

◆ operator*()

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

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+()

Translation2d frc::Translation2d::operator+ ( const Translation2d & other) const
inlineconstexpr

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]

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

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]

Translation2d frc::Translation2d::operator- ( const Translation2d & other) const
inlineconstexpr

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/()

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

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
inlineconstexpr

Checks equality between this Translation2d and another object.

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

◆ RotateAround()

Translation2d frc::Translation2d::RotateAround ( const Translation2d & other,
const Rotation2d & rot ) const
inlineconstexpr

Rotates this translation around another translation in 2D space.

[x_new]   [rot.cos, -rot.sin][x - other.x]   [other.x]
[y_new] = [rot.sin,  rot.cos][y - other.y] + [other.y]
Parameters
otherThe other translation to rotate around.
rotThe rotation to rotate the translation by.
Returns
The new rotated translation.

◆ RotateBy()

Translation2d frc::Translation2d::RotateBy ( const Rotation2d & other) const
inlineconstexpr

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.

◆ SquaredDistance()

units::square_meter_t frc::Translation2d::SquaredDistance ( const Translation2d & other) const
inlineconstexpr

Calculates the square of the distance between two translations in 2D space.

This is equivalent to squaring the result of Distance(Translation2d), but avoids computing a square root.

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

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

◆ SquaredNorm()

units::square_meter_t frc::Translation2d::SquaredNorm ( ) const
inlineconstexpr

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

This is equivalent to squaring the result of Norm(), but avoids computing a square root.

Returns
The squared norm of the translation.

◆ ToVector()

Eigen::Vector2d frc::Translation2d::ToVector ( ) const
inlineconstexpr

Returns a 2D translation vector representation of this translation.

Returns
A 2D translation vector representation of this translation.

◆ X()

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

Returns the X component of the translation.

Returns
The X component of the translation.

◆ Y()

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 file: