Robot Core Documentation
|
Public Member Functions | |
Twist2d () | |
Twist2d (double dx, double dy, double dtheta) | |
boolean | equals (Object obj) |
Public Attributes | |
double | dx |
double | dy |
double | dtheta |
Static Public Attributes | |
static final Twist2dProto | proto = new Twist2dProto() |
static final Twist2dStruct | struct = new Twist2dStruct() |
A change in distance along a 2D arc since the last pose update. We can use ideas from differential calculus to create new Pose2d objects from a Twist2d and vice versa.
A Twist can be used to represent a difference between two poses.
edu.wpi.first.math.geometry.Twist2d.Twist2d | ( | ) |
Default constructor.
edu.wpi.first.math.geometry.Twist2d.Twist2d | ( | double | dx, |
double | dy, | ||
double | dtheta ) |
Constructs a Twist2d with the given values.
dx | Change in x direction relative to robot. |
dy | Change in y direction relative to robot. |
dtheta | Change in angle relative to robot. |
boolean edu.wpi.first.math.geometry.Twist2d.equals | ( | Object | obj | ) |
Checks equality between this Twist2d and another object.
obj | The other object. |
double edu.wpi.first.math.geometry.Twist2d.dtheta |
Angular "dtheta" component (radians).
double edu.wpi.first.math.geometry.Twist2d.dx |
Linear "dx" component.
double edu.wpi.first.math.geometry.Twist2d.dy |
Linear "dy" component.
|
static |
Twist2d protobuf for serialization.
|
static |
Twist2d struct for serialization.