Represents a transformation for a Pose3d in the pose's frame.
More...
#include <frc/geometry/Transform3d.h>
|
constexpr | Transform3d (const Pose3d &initial, const Pose3d &final) |
| Constructs the transform that maps the initial pose to the final pose.
|
|
constexpr | Transform3d (Translation3d translation, Rotation3d rotation) |
| Constructs a transform with the given translation and rotation components.
|
|
constexpr | 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.
|
|
constexpr | Transform3d (const Eigen::Matrix4d &matrix) |
| Constructs a transform with the specified affine transformation matrix.
|
|
constexpr | Transform3d ()=default |
| Constructs the identity transform – maps an initial pose to itself.
|
|
constexpr | Transform3d (const frc::Transform2d &transform) |
| Constructs a 3D transform from a 2D transform in the X-Y plane.
|
|
constexpr const Translation3d & | Translation () const |
| Returns the translation component of the transformation.
|
|
constexpr units::meter_t | X () const |
| Returns the X component of the transformation's translation.
|
|
constexpr units::meter_t | Y () const |
| Returns the Y component of the transformation's translation.
|
|
constexpr units::meter_t | Z () const |
| Returns the Z component of the transformation's translation.
|
|
constexpr Eigen::Matrix4d | ToMatrix () const |
| Returns an affine transformation matrix representation of this transformation.
|
|
constexpr const Rotation3d & | Rotation () const |
| Returns the rotational component of the transformation.
|
|
constexpr Transform3d | Inverse () const |
| Invert the transformation.
|
|
constexpr Transform3d | operator* (double scalar) const |
| Multiplies the transform by the scalar.
|
|
constexpr Transform3d | operator/ (double scalar) const |
| Divides the transform by the scalar.
|
|
constexpr Transform3d | operator+ (const Transform3d &other) const |
| Composes two transformations.
|
|
constexpr bool | operator== (const Transform3d &) const =default |
| Checks equality between this Transform3d and another object.
|
|
Represents a transformation for a Pose3d in the pose's frame.
◆ Transform3d() [1/6]
frc::Transform3d::Transform3d |
( |
const Pose3d & | initial, |
|
|
const Pose3d & | final ) |
|
constexpr |
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/6]
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/6]
frc::Transform3d::Transform3d |
( |
units::meter_t | x, |
|
|
units::meter_t | y, |
|
|
units::meter_t | z, |
|
|
Rotation3d | rotation ) |
|
inlineconstexpr |
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/6]
frc::Transform3d::Transform3d |
( |
const Eigen::Matrix4d & | matrix | ) |
|
|
inlineexplicitconstexpr |
Constructs a transform with the specified affine transformation matrix.
- Parameters
-
matrix | The affine transformation matrix. |
- Throws:
- std::domain_error if the affine transformation matrix is invalid.
◆ Transform3d() [5/6]
frc::Transform3d::Transform3d |
( |
| ) |
|
|
constexprdefault |
Constructs the identity transform – maps an initial pose to itself.
◆ Transform3d() [6/6]
Constructs a 3D transform from a 2D transform in the X-Y plane.
- Parameters
-
transform | The 2D transform. |
- See also
- Rotation3d(Rotation2d)
-
Translation3d(Translation2d)
◆ Inverse()
Invert the transformation.
This is useful for undoing a transformation.
- Returns
- The inverted transformation.
◆ operator*()
Transform3d frc::Transform3d::operator* |
( |
double | scalar | ) |
const |
|
inlineconstexpr |
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 |
|
inlineconstexpr |
Divides the transform by the scalar.
- Parameters
-
- Returns
- The scaled Transform3d.
◆ operator==()
bool frc::Transform3d::operator== |
( |
const Transform3d & | | ) |
const |
|
constexprdefault |
Checks equality between this Transform3d and another object.
◆ Rotation()
const Rotation3d & frc::Transform3d::Rotation |
( |
| ) |
const |
|
inlineconstexpr |
Returns the rotational component of the transformation.
- Returns
- Reference to the rotational component of the transform.
◆ ToMatrix()
Eigen::Matrix4d frc::Transform3d::ToMatrix |
( |
| ) |
const |
|
inlineconstexpr |
Returns an affine transformation matrix representation of this transformation.
◆ 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 |
|
inlineconstexpr |
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 |
|
inlineconstexpr |
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 |
|
inlineconstexpr |
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: