WPILibC++ 2024.3.2
frc::Transform2d Class Reference

Represents a transformation for a Pose2d in the pose's frame. More...

#include <frc/geometry/Transform2d.h>

Public Member Functions

 Transform2d (Pose2d initial, Pose2d final)
 Constructs the transform that maps the initial pose to the final pose. More...
 
constexpr Transform2d (Translation2d translation, Rotation2d rotation)
 Constructs a transform with the given translation and rotation components. More...
 
constexpr Transform2d (units::meter_t x, units::meter_t y, Rotation2d rotation)
 Constructs a transform with x and y translations instead of a separate Translation2d. More...
 
constexpr Transform2d ()=default
 Constructs the identity transform – maps an initial pose to itself. More...
 
constexpr const Translation2dTranslation () const
 Returns the translation component of the transformation. More...
 
constexpr units::meter_t X () const
 Returns the X component of the transformation's translation. More...
 
constexpr units::meter_t Y () const
 Returns the Y component of the transformation's translation. More...
 
constexpr const Rotation2dRotation () const
 Returns the rotational component of the transformation. More...
 
constexpr Transform2d Inverse () const
 Invert the transformation. More...
 
constexpr Transform2d operator* (double scalar) const
 Multiplies the transform by the scalar. More...
 
constexpr Transform2d operator/ (double scalar) const
 Divides the transform by the scalar. More...
 
Transform2d operator+ (const Transform2d &other) const
 Composes two transformations. More...
 
bool operator== (const Transform2d &) const =default
 Checks equality between this Transform2d and another object. More...
 

Detailed Description

Represents a transformation for a Pose2d in the pose's frame.

Constructor & Destructor Documentation

◆ Transform2d() [1/4]

frc::Transform2d::Transform2d ( Pose2d  initial,
Pose2d  final 
)

Constructs the transform that maps the initial pose to the final pose.

Parameters
initialThe initial pose for the transformation.
finalThe final pose for the transformation.

◆ Transform2d() [2/4]

constexpr frc::Transform2d::Transform2d ( Translation2d  translation,
Rotation2d  rotation 
)
constexpr

Constructs a transform with the given translation and rotation components.

Parameters
translationTranslational component of the transform.
rotationRotational component of the transform.

◆ Transform2d() [3/4]

constexpr frc::Transform2d::Transform2d ( units::meter_t  x,
units::meter_t  y,
Rotation2d  rotation 
)
constexpr

Constructs a transform with x and y translations instead of a separate Translation2d.

Parameters
xThe x component of the translational component of the transform.
yThe y component of the translational component of the transform.
rotationThe rotational component of the transform.

◆ Transform2d() [4/4]

constexpr frc::Transform2d::Transform2d ( )
constexprdefault

Constructs the identity transform – maps an initial pose to itself.

Member Function Documentation

◆ Inverse()

constexpr Transform2d frc::Transform2d::Inverse ( ) const
constexpr

Invert the transformation.

This is useful for undoing a transformation.

Returns
The inverted transformation.

◆ operator*()

constexpr Transform2d frc::Transform2d::operator* ( double  scalar) const
inlineconstexpr

Multiplies the transform by the scalar.

Parameters
scalarThe scalar.
Returns
The scaled Transform2d.

◆ operator+()

Transform2d frc::Transform2d::operator+ ( const Transform2d other) const

Composes two transformations.

The second transform is applied relative to the orientation of the first.

Parameters
otherThe transform to compose with this one.
Returns
The composition of the two transformations.

◆ operator/()

constexpr Transform2d frc::Transform2d::operator/ ( double  scalar) const
inlineconstexpr

Divides the transform by the scalar.

Parameters
scalarThe scalar.
Returns
The scaled Transform2d.

◆ operator==()

bool frc::Transform2d::operator== ( const Transform2d ) const
default

Checks equality between this Transform2d and another object.

◆ Rotation()

constexpr const Rotation2d & frc::Transform2d::Rotation ( ) const
inlineconstexpr

Returns the rotational component of the transformation.

Returns
Reference to the rotational component of the transform.

◆ Translation()

constexpr const Translation2d & frc::Transform2d::Translation ( ) const
inlineconstexpr

Returns the translation component of the transformation.

Returns
Reference to the translational component of the transform.

◆ X()

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

Returns the X component of the transformation's translation.

Returns
The x component of the transformation's translation.

◆ Y()

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

Returns the Y component of the transformation's translation.

Returns
The y component of the transformation's translation.

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