Represents a transformation for a Pose2d in the pose's frame.
More...
#include <frc/geometry/Transform2d.h>
Represents a transformation for a Pose2d in the pose's frame.
◆ Transform2d() [1/4]
frc::Transform2d::Transform2d |
( |
Pose2d |
initial, |
|
|
Pose2d |
final |
|
) |
| |
Constructs the transform that maps the initial pose to the final pose.
- Parameters
-
initial | The initial pose for the transformation. |
final | The final pose for the transformation. |
◆ Transform2d() [2/4]
Constructs a transform with the given translation and rotation components.
- Parameters
-
translation | Translational component of the transform. |
rotation | Rotational 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
-
x | The x component of the translational component of the transform. |
y | The y component of the translational component of the transform. |
rotation | The rotational component of the transform. |
◆ Transform2d() [4/4]
constexpr frc::Transform2d::Transform2d |
( |
| ) |
|
|
constexprdefault |
Constructs the identity transform – maps an initial pose to itself.
◆ 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
-
- Returns
- The scaled Transform2d.
◆ operator+()
Composes two transformations.
The second transform is applied relative to the orientation of the first.
- Parameters
-
other | The 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
-
- 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: