|
constexpr | Pose3d ()=default |
| Constructs a pose at the origin facing toward the positive X axis.
|
|
constexpr | Pose3d (Translation3d translation, Rotation3d rotation) |
| Constructs a pose with the specified translation and rotation.
|
|
constexpr | Pose3d (units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation) |
| Constructs a pose with x, y, and z translations instead of a separate Translation3d.
|
|
constexpr | Pose3d (const Eigen::Matrix4d &matrix) |
| Constructs a pose with the specified affine transformation matrix.
|
|
constexpr | Pose3d (const Pose2d &pose) |
| Constructs a 3D pose from a 2D pose in the X-Y plane.
|
|
constexpr Pose3d | operator+ (const Transform3d &other) const |
| Transforms the pose by the given transformation and returns the new transformed pose.
|
|
constexpr Transform3d | operator- (const Pose3d &other) const |
| Returns the Transform3d that maps the one pose to another.
|
|
constexpr bool | operator== (const Pose3d &) const =default |
| Checks equality between this Pose3d and another object.
|
|
constexpr const Translation3d & | Translation () const |
| Returns the underlying translation.
|
|
constexpr units::meter_t | X () const |
| Returns the X component of the pose's translation.
|
|
constexpr units::meter_t | Y () const |
| Returns the Y component of the pose's translation.
|
|
constexpr units::meter_t | Z () const |
| Returns the Z component of the pose's translation.
|
|
constexpr const Rotation3d & | Rotation () const |
| Returns the underlying rotation.
|
|
constexpr Pose3d | operator* (double scalar) const |
| Multiplies the current pose by a scalar.
|
|
constexpr Pose3d | operator/ (double scalar) const |
| Divides the current pose by a scalar.
|
|
constexpr Pose3d | RotateBy (const Rotation3d &other) const |
| Rotates the pose around the origin and returns the new pose.
|
|
constexpr Pose3d | TransformBy (const Transform3d &other) const |
| Transforms the pose by the given transformation and returns the new transformed pose.
|
|
constexpr Pose3d | RelativeTo (const Pose3d &other) const |
| Returns the current pose relative to the given pose.
|
|
constexpr Pose3d | Exp (const Twist3d &twist) const |
| Obtain a new Pose3d from a (constant curvature) velocity.
|
|
constexpr Twist3d | Log (const Pose3d &end) const |
| Returns a Twist3d that maps this pose to the end pose.
|
|
constexpr Eigen::Matrix4d | ToMatrix () const |
| Returns an affine transformation matrix representation of this pose.
|
|
constexpr Pose2d | ToPose2d () const |
| Returns a Pose2d representing this Pose3d projected into the X-Y plane.
|
|
Represents a 3D pose containing translational and rotational elements.
Obtain a new Pose3d from a (constant curvature) velocity.
The twist is a change in pose in the robot's coordinate frame since the previous pose update. When the user runs exp() on the previous known field-relative pose with the argument being the twist, the user will receive the new field-relative pose.
"Exp" represents the pose exponential, which is solving a differential equation moving the pose forward in time.
- Parameters
-
twist | The change in pose in the robot's coordinate frame since the previous pose update. For example, if a non-holonomic robot moves forward 0.01 meters and changes angle by 0.5 degrees since the previous pose update, the twist would be Twist3d{0.01_m, 0_m, 0_m, Rotation3d{0.0, 0.0, 0.5_deg}}. |
- Returns
- The new pose of the robot.