|
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 | Exp (const Twist2d &twist) const |
| Obtain a new Pose2d from a (constant curvature) velocity.
|
|
constexpr Twist2d | Log (const Pose2d &end) const |
| Returns a Twist2d that maps this pose to the end pose.
|
|
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.
Obtain a new Pose2d from a (constant curvature) velocity.
See https://file.tavsys.net/control/controls-engineering-in-frc.pdf section 10.2 "Pose exponential" for a derivation.
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 Twist2d{0.01_m, 0_m, 0.5_deg}. |
- Returns
- The new pose of the robot.
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.