WPILibC++  2020.3.2-60-g3011ebe
frc::Transform2d Class Reference

Represents a transformation for a Pose2d. More...

#include <Transform2d.h>

Public Member Functions

 Transform2d (Pose2d initial, Pose2d final)
 Constructs the transform that maps the initial pose to the final pose. More...
 
 Transform2d (Translation2d translation, Rotation2d rotation)
 Constructs a transform with the given translation and rotation components. More...
 
constexpr Transform2d ()=default
 Constructs the identity transform – maps an initial pose to itself.
 
const Translation2dTranslation () const
 Returns the translation component of the transformation. More...
 
const Rotation2dRotation () const
 Returns the rotational component of the transformation. More...
 
Transform2d Inverse () const
 Invert the transformation. More...
 
Transform2d operator* (double scalar) const
 Scales the transform by the scalar. More...
 
bool operator== (const Transform2d &other) const
 Checks equality between this Transform2d and another object. More...
 
bool operator!= (const Transform2d &other) const
 Checks inequality between this Transform2d and another object. More...
 

Detailed Description

Represents a transformation for a Pose2d.

Constructor & Destructor Documentation

◆ Transform2d() [1/2]

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

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

Constructs a transform with the given translation and rotation components.

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

Member Function Documentation

◆ Inverse()

Transform2d frc::Transform2d::Inverse ( ) const

Invert the transformation.

This is useful for undoing a transformation.

Returns
The inverted transformation.

◆ operator!=()

bool frc::Transform2d::operator!= ( const Transform2d other) const

Checks inequality between this Transform2d and another object.

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

◆ operator*()

Transform2d frc::Transform2d::operator* ( double  scalar) const
inline

Scales the transform by the scalar.

Parameters
scalarThe scalar.
Returns
The scaled Transform2d.

◆ operator==()

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

Checks equality between this Transform2d and another object.

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

◆ Rotation()

const Rotation2d& frc::Transform2d::Rotation ( ) const
inline

Returns the rotational component of the transformation.

Returns
Reference to the rotational component of the transform.

◆ Translation()

const Translation2d& frc::Transform2d::Translation ( ) const
inline

Returns the translation component of the transformation.

Returns
Reference to the translational component of the transform.

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