Represents a transformation for a Pose3d in the pose's frame.
More...
#include <frc/geometry/Transform3d.h>
Represents a transformation for a Pose3d in the pose's frame.
◆ Transform3d() [1/4]
frc::Transform3d::Transform3d |
( |
Pose3d |
initial, |
|
|
Pose3d |
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. |
◆ Transform3d() [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. |
◆ Transform3d() [3/4]
frc::Transform3d::Transform3d |
( |
units::meter_t |
x, |
|
|
units::meter_t |
y, |
|
|
units::meter_t |
z, |
|
|
Rotation3d |
rotation |
|
) |
| |
Constructs a transform with x, y, and z translations instead of a separate Translation3d.
- Parameters
-
x | The x component of the translational component of the transform. |
y | The y component of the translational component of the transform. |
z | The z component of the translational component of the transform. |
rotation | The rotational component of the transform. |
◆ Transform3d() [4/4]
constexpr frc::Transform3d::Transform3d |
( |
| ) |
|
|
constexprdefault |
Constructs the identity transform – maps an initial pose to itself.
◆ Inverse()
Invert the transformation.
This is useful for undoing a transformation.
- Returns
- The inverted transformation.
◆ operator*()
Transform3d frc::Transform3d::operator* |
( |
double |
scalar | ) |
const |
|
inline |
Multiplies the transform by the scalar.
- Parameters
-
- Returns
- The scaled Transform3d.
◆ 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/()
Transform3d frc::Transform3d::operator/ |
( |
double |
scalar | ) |
const |
|
inline |
Divides the transform by the scalar.
- Parameters
-
- Returns
- The scaled Transform3d.
◆ operator==()
bool frc::Transform3d::operator== |
( |
const Transform3d & |
| ) |
const |
|
default |
Checks equality between this Transform3d and another object.
◆ Rotation()
const Rotation3d & frc::Transform3d::Rotation |
( |
| ) |
const |
|
inline |
Returns the rotational component of the transformation.
- Returns
- Reference to the rotational component of the transform.
◆ Translation()
Returns the translation component of the transformation.
- Returns
- Reference to the translational component of the transform.
◆ X()
units::meter_t frc::Transform3d::X |
( |
| ) |
const |
|
inline |
Returns the X component of the transformation's translation.
- Returns
- The x component of the transformation's translation.
◆ Y()
units::meter_t frc::Transform3d::Y |
( |
| ) |
const |
|
inline |
Returns the Y component of the transformation's translation.
- Returns
- The y component of the transformation's translation.
◆ Z()
units::meter_t frc::Transform3d::Z |
( |
| ) |
const |
|
inline |
Returns the Z component of the transformation's translation.
- Returns
- The z component of the transformation's translation.
The documentation for this class was generated from the following file: