WPILibC++ 2025.2.1
|
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::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 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 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. | |
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.
|
constexprdefault |
Constructs a Translation2d with X and Y components equal to zero.
|
inlineconstexpr |
Constructs a Translation2d with the X and Y components equal to the provided values.
x | The x component of the translation. |
y | The y component of the translation. |
|
inlineconstexpr |
Constructs a Translation2d with the provided distance and angle.
This is essentially converting from polar coordinates to Cartesian coordinates.
distance | The distance from the origin to the end of the translation. |
angle | The angle between the x-axis and the translation vector. |
|
inlineexplicitconstexpr |
Constructs a Translation2d from a 2D translation vector.
The values are assumed to be in meters.
vector | The translation vector. |
|
inlineconstexpr |
Returns the angle this translation forms with the positive X axis.
|
inlineconstexpr |
Calculates the distance between two translations in 2D space.
The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
other | The translation to compute the distance to. |
|
inlineconstexpr |
Returns the nearest Translation2d from a collection of translations.
translations | The collection of translations. |
|
inlineconstexpr |
Returns the nearest Translation2d from a collection of translations.
translations | The collection of translations. |
|
inlineconstexpr |
Returns the norm, or distance from the origin to the translation.
|
inlineconstexpr |
Returns the translation multiplied by a scalar.
For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}.
scalar | The scalar to multiply by. |
|
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}.
other | The translation to add. |
|
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.
|
inlineconstexpr |
Returns the difference between two translations.
For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} = Translation2d{4.0, 2.0}.
other | The translation to subtract. |
|
inlineconstexpr |
Returns the translation divided by a scalar.
For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}.
scalar | The scalar to divide by. |
|
inlineconstexpr |
Checks equality between this Translation2d and another object.
other | The other object. |
|
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]
other | The other translation to rotate around. |
rot | The rotation to rotate the translation by. |
|
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>.
other | The rotation to rotate the translation by. |
|
inlineconstexpr |
Returns a 2D translation vector representation of this translation.
|
inlineconstexpr |
Returns the X component of the translation.
|
inlineconstexpr |
Returns the Y component of the translation.