|
| constexpr | Pose2d ()=default |
| | Constructs a pose at the origin facing toward the positive X axis.
|
| |
| constexpr | Pose2d (Translation2d translation, Rotation2d rotation) |
| | Constructs a pose with the specified translation and rotation.
|
| |
| constexpr | Pose2d (units::meter_t x, units::meter_t y, Rotation2d rotation) |
| | Constructs a pose with x and y translations instead of a separate Translation2d.
|
| |
| constexpr | Pose2d (const Eigen::Matrix3d &matrix) |
| | Constructs a pose with the specified affine transformation matrix.
|
| |
| constexpr Pose2d | operator+ (const Transform2d &other) const |
| | Transforms the pose by the given transformation and returns the new transformed pose.
|
| |
| constexpr Transform2d | operator- (const Pose2d &other) const |
| | Returns the Transform2d that maps the one pose to another.
|
| |
| constexpr bool | operator== (const Pose2d &) const =default |
| | Checks equality between this Pose2d and another object.
|
| |
| constexpr const Translation2d & | 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 const Rotation2d & | Rotation () const |
| | Returns the underlying rotation.
|
| |
| constexpr Pose2d | operator* (double scalar) const |
| | Multiplies the current pose by a scalar.
|
| |
| constexpr Pose2d | operator/ (double scalar) const |
| | Divides the current pose by a scalar.
|
| |
| constexpr Pose2d | RotateBy (const Rotation2d &other) const |
| | Rotates the pose around the origin and returns the new pose.
|
| |
| constexpr Pose2d | TransformBy (const Transform2d &other) const |
| | Transforms the pose by the given transformation and returns the new pose.
|
| |
| constexpr Pose2d | RelativeTo (const Pose2d &other) const |
| | Returns the current pose relative to the given pose.
|
| |
| constexpr Pose2d | RotateAround (const Translation2d &point, const Rotation2d &rot) const |
| | Rotates the current pose around a point in 2D space.
|
| |
| constexpr Eigen::Matrix3d | ToMatrix () const |
| | Returns an affine transformation matrix representation of this pose.
|
| |
| constexpr Pose2d | Nearest (std::span< const Pose2d > poses) const |
| | Returns the nearest Pose2d from a collection of poses.
|
| |
| constexpr Pose2d | Nearest (std::initializer_list< Pose2d > poses) const |
| | Returns the nearest Pose2d from a collection of poses.
|
| |
Represents a 2D pose containing translational and rotational elements.
Transforms the pose by the given transformation and returns the new transformed pose.
[x_new] [cos, -sin, 0][transform.x]
[y_new] += [sin, cos, 0][transform.y]
[t_new] [ 0, 0, 1][transform.t]
- Parameters
-
| other | The transform to transform the pose by. |
- Returns
- The transformed pose.