![]() |
WPILibC++ 2027.0.0-alpha-4
|
Represents a transformation for a Pose3d in the pose's frame. More...
#include <wpi/math/geometry/Transform3d.hpp>
Public Member Functions | |
| 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 (wpi::units::meter_t x, wpi::units::meter_t y, wpi::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 wpi::math::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 wpi::units::meter_t | X () const |
| Returns the X component of the transformation's translation. | |
| constexpr wpi::units::meter_t | Y () const |
| Returns the Y component of the transformation's translation. | |
| constexpr wpi::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 Twist3d | Log () const |
| Returns a Twist3d of the current transform (pose delta). | |
| 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.
Translation is applied before rotation. (The translation is applied in the pose's original frame, not the transformed frame.)
Constructs the transform that maps the initial pose to the final pose.
| initial | The initial pose for the transformation. |
| final | The final pose for the transformation. |
|
inlineconstexpr |
Constructs a transform with the given translation and rotation components.
| translation | Translational component of the transform. |
| rotation | Rotational component of the transform. |
|
inlineconstexpr |
Constructs a transform with x, y, and z translations instead of a separate Translation3d.
| 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. |
|
inlineexplicitconstexpr |
Constructs a transform with the specified affine transformation matrix.
| matrix | The affine transformation matrix. |
|
constexprdefault |
Constructs the identity transform – maps an initial pose to itself.
|
inlineexplicitconstexpr |
Constructs a 3D transform from a 2D transform in the X-Y plane.
| transform | The 2D transform. |
|
inlineconstexpr |
Invert the transformation.
This is useful for undoing a transformation.
|
constexpr |
Returns a Twist3d of the current transform (pose delta).
If b is the output of a.Log(), then b.Exp() would yield a.
|
inlineconstexpr |
|
constexpr |
Composes two transformations.
The second transform is applied relative to the orientation of the first.
| other | The transform to compose with this one. |
|
inlineconstexpr |
|
constexprdefault |
Checks equality between this Transform3d and another object.
|
inlineconstexpr |
Returns the rotational component of the transformation.
|
inlineconstexpr |
Returns an affine transformation matrix representation of this transformation.
|
inlineconstexpr |
Returns the translation component of the transformation.
|
inlineconstexpr |
Returns the X component of the transformation's translation.
|
inlineconstexpr |
Returns the Y component of the transformation's translation.
|
inlineconstexpr |
Returns the Z component of the transformation's translation.