WPILibC++ 2024.3.2
frc::Translation3d Class Reference

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

#include <frc/geometry/Translation3d.h>

Public Member Functions

constexpr Translation3d ()=default
 Constructs a Translation3d with X, Y, and Z components equal to zero. More...
 
constexpr Translation3d (units::meter_t x, units::meter_t y, units::meter_t z)
 Constructs a Translation3d with the X, Y, and Z components equal to the provided values. More...
 
 Translation3d (units::meter_t distance, const Rotation3d &angle)
 Constructs a Translation3d with the provided distance and angle. More...
 
 Translation3d (const Eigen::Vector3d &vector)
 Constructs a Translation3d from the provided translation vector's X, Y, and Z components. More...
 
units::meter_t Distance (const Translation3d &other) const
 Calculates the distance between two translations in 3D 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...
 
constexpr units::meter_t Z () const
 Returns the Z component of the translation. More...
 
constexpr Eigen::Vector3d ToVector () const
 Returns a vector representation of this translation. More...
 
units::meter_t Norm () const
 Returns the norm, or distance from the origin to the translation. More...
 
Translation3d RotateBy (const Rotation3d &other) const
 Applies a rotation to the translation in 3D space. More...
 
constexpr Translation2d ToTranslation2d () const
 Returns a Translation2d representing this Translation3d projected into the X-Y plane. More...
 
constexpr Translation3d operator+ (const Translation3d &other) const
 Returns the sum of two translations in 3D space. More...
 
constexpr Translation3d operator- (const Translation3d &other) const
 Returns the difference between two translations. More...
 
constexpr Translation3d operator- () const
 Returns the inverse of the current translation. More...
 
constexpr Translation3d operator* (double scalar) const
 Returns the translation multiplied by a scalar. More...
 
constexpr Translation3d operator/ (double scalar) const
 Returns the translation divided by a scalar. More...
 
bool operator== (const Translation3d &other) const
 Checks equality between this Translation3d and another object. More...
 

Detailed Description

Represents a translation in 3D 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, left is positive Y, and up is positive Z.

Constructor & Destructor Documentation

◆ Translation3d() [1/4]

constexpr frc::Translation3d::Translation3d ( )
constexprdefault

Constructs a Translation3d with X, Y, and Z components equal to zero.

◆ Translation3d() [2/4]

constexpr frc::Translation3d::Translation3d ( units::meter_t  x,
units::meter_t  y,
units::meter_t  z 
)
constexpr

Constructs a Translation3d with the X, Y, and Z components equal to the provided values.

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

◆ Translation3d() [3/4]

frc::Translation3d::Translation3d ( units::meter_t  distance,
const Rotation3d angle 
)

Constructs a Translation3d 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.

◆ Translation3d() [4/4]

frc::Translation3d::Translation3d ( const Eigen::Vector3d &  vector)
explicit

Constructs a Translation3d from the provided translation vector's X, Y, and Z components.

The values are assumed to be in meters.

Parameters
vectorThe translation vector to represent.

Member Function Documentation

◆ Distance()

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

Calculates the distance between two translations in 3D space.

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

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

◆ Norm()

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

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

Returns
The norm of the translation.

◆ operator*()

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

Returns the translation multiplied by a scalar.

For example, Translation3d{2.0, 2.5, 4.5} * 2 = Translation3d{4.0, 5.0, 9.0}.

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

◆ operator+()

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

Returns the sum of two translations in 3D space.

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

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

◆ operator-() [1/2]

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

Returns the inverse of the current translation.

This is equivalent to negating all components of the translation.

Returns
The inverse of the current translation.

◆ operator-() [2/2]

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

Returns the difference between two translations.

For example, Translation3d{5.0, 4.0, 3.0} - Translation3d{1.0, 2.0, 3.0} = Translation3d{4.0, 2.0, 0.0}.

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

◆ operator/()

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

Returns the translation divided by a scalar.

For example, Translation3d{2.0, 2.5, 4.5} / 2 = Translation3d{1.0, 1.25, 2.25}.

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

◆ operator==()

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

Checks equality between this Translation3d and another object.

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

◆ RotateBy()

Translation3d frc::Translation3d::RotateBy ( const Rotation3d other) const

Applies a rotation to the translation in 3D space.

For example, rotating a Translation3d of <2, 0, 0> by 90 degrees around the Z axis will return a Translation3d of <0, 2, 0>.

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

◆ ToTranslation2d()

constexpr Translation2d frc::Translation3d::ToTranslation2d ( ) const
constexpr

Returns a Translation2d representing this Translation3d projected into the X-Y plane.

◆ ToVector()

constexpr Eigen::Vector3d frc::Translation3d::ToVector ( ) const
constexpr

Returns a vector representation of this translation.

Returns
A Vector representation of this translation.

◆ X()

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

Returns the X component of the translation.

Returns
The Z component of the translation.

◆ Y()

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

Returns the Y component of the translation.

Returns
The Y component of the translation.

◆ Z()

constexpr units::meter_t frc::Translation3d::Z ( ) const
inlineconstexpr

Returns the Z component of the translation.

Returns
The Z component of the translation.

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