Robot Core Documentation
|
Public Member Functions | |
Pose2d () | |
Pose2d ( @JsonProperty(required=true, value="translation") Translation2d translation, @JsonProperty(required=true, value="rotation") Rotation2d rotation) | |
Pose2d (double x, double y, Rotation2d rotation) | |
Pose2d (Measure< Distance > x, Measure< Distance > y, Rotation2d rotation) | |
Pose2d | plus (Transform2d other) |
Transform2d | minus (Pose2d other) |
Translation2d | getTranslation () |
double | getX () |
double | getY () |
Rotation2d | getRotation () |
Pose2d | times (double scalar) |
Pose2d | div (double scalar) |
Pose2d | rotateBy (Rotation2d other) |
Pose2d | transformBy (Transform2d other) |
Pose2d | relativeTo (Pose2d other) |
Pose2d | exp (Twist2d twist) |
Twist2d | log (Pose2d end) |
Pose2d | nearest (List< Pose2d > poses) |
boolean | equals (Object obj) |
![]() | |
T | interpolate (T endValue, double t) |
Static Public Attributes | |
static final Pose2dProto | proto = new Pose2dProto() |
static final Pose2dStruct | struct = new Pose2dStruct() |
Represents a 2D pose containing translational and rotational elements.
edu.wpi.first.math.geometry.Pose2d.Pose2d | ( | ) |
Constructs a pose at the origin facing toward the positive X axis.
edu.wpi.first.math.geometry.Pose2d.Pose2d | ( | @JsonProperty(required=true, value="translation") Translation2d | translation, |
@JsonProperty(required=true, value="rotation") Rotation2d | rotation ) |
Constructs a pose with the specified translation and rotation.
translation | The translational component of the pose. |
rotation | The rotational component of the pose. |
edu.wpi.first.math.geometry.Pose2d.Pose2d | ( | double | x, |
double | y, | ||
Rotation2d | rotation ) |
Constructs a pose with x and y translations instead of a separate Translation2d.
x | The x component of the translational component of the pose. |
y | The y component of the translational component of the pose. |
rotation | The rotational component of the pose. |
edu.wpi.first.math.geometry.Pose2d.Pose2d | ( | Measure< Distance > | x, |
Measure< Distance > | y, | ||
Rotation2d | rotation ) |
Constructs a pose with x and y translations instead of a separate Translation2d. The X and Y translations will be converted to and tracked as meters.
x | The x component of the translational component of the pose. |
y | The y component of the translational component of the pose. |
rotation | The rotational component of the pose. |
Pose2d edu.wpi.first.math.geometry.Pose2d.div | ( | double | scalar | ) |
boolean edu.wpi.first.math.geometry.Pose2d.equals | ( | Object | obj | ) |
Checks equality between this Pose2d and another object.
obj | The other object. |
Obtain a new Pose2d from a (constant curvature) velocity.
See Controls Engineering in the FIRST Robotics Competition 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.
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, 0.0, Units.degreesToRadians(0.5)). |
Rotation2d edu.wpi.first.math.geometry.Pose2d.getRotation | ( | ) |
Returns the rotational component of the transformation.
Translation2d edu.wpi.first.math.geometry.Pose2d.getTranslation | ( | ) |
Returns the translation component of the transformation.
double edu.wpi.first.math.geometry.Pose2d.getX | ( | ) |
Returns the X component of the pose's translation.
double edu.wpi.first.math.geometry.Pose2d.getY | ( | ) |
Returns the Y component of the pose's translation.
Returns a Twist2d that maps this pose to the end pose. If c is the output of a.Log(b)
, then a.Exp(c)
would yield b.
end | The end pose for the transformation. |
Transform2d edu.wpi.first.math.geometry.Pose2d.minus | ( | Pose2d | other | ) |
Returns the Transform2d that maps the one pose to another.
other | The initial pose of the transformation. |
Pose2d edu.wpi.first.math.geometry.Pose2d.plus | ( | Transform2d | other | ) |
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]
other | The transform to transform the pose by. |
Returns the current pose relative to the given pose.
This function can often be used for trajectory tracking or pose stabilization algorithms to get the error between the reference and the current pose.
other | The pose that is the origin of the new coordinate frame that the current pose will be converted into. |
Pose2d edu.wpi.first.math.geometry.Pose2d.rotateBy | ( | Rotation2d | other | ) |
Rotates the pose around the origin and returns the new pose.
other | The rotation to transform the pose by. |
Pose2d edu.wpi.first.math.geometry.Pose2d.times | ( | double | scalar | ) |
Pose2d edu.wpi.first.math.geometry.Pose2d.transformBy | ( | Transform2d | other | ) |
Transforms the pose by the given transformation and returns the new pose. See + operator for the matrix multiplication performed.
other | The transform to transform the pose by. |
|
static |
Pose2d protobuf for serialization.
|
static |
Pose2d struct for serialization.