Robot Core Documentation
|
Public Member Functions | |
Rotation2d () | |
Rotation2d (@JsonProperty(required=true, value="radians") double value) | |
Rotation2d (double x, double y) | |
Rotation2d (Measure< Angle > angle) | |
Rotation2d | plus (Rotation2d other) |
Rotation2d | minus (Rotation2d other) |
Rotation2d | unaryMinus () |
Rotation2d | times (double scalar) |
Rotation2d | div (double scalar) |
Rotation2d | rotateBy (Rotation2d other) |
double | getRadians () |
double | getDegrees () |
double | getRotations () |
double | getCos () |
double | getSin () |
double | getTan () |
boolean | equals (Object obj) |
![]() | |
T | interpolate (T endValue, double t) |
Static Public Member Functions | |
static Rotation2d | fromRadians (double radians) |
static Rotation2d | fromDegrees (double degrees) |
static Rotation2d | fromRotations (double rotations) |
Static Public Attributes | |
static final Rotation2dProto | proto = new Rotation2dProto() |
static final Rotation2dStruct | struct = new Rotation2dStruct() |
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
The angle is continuous, that is if a Rotation2d is constructed with 361 degrees, it will return 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the rotations as it sweeps past from 360 to 0 on the second time around.
edu.wpi.first.math.geometry.Rotation2d.Rotation2d | ( | ) |
Constructs a Rotation2d with a default angle of 0 degrees.
edu.wpi.first.math.geometry.Rotation2d.Rotation2d | ( | @JsonProperty(required=true, value="radians") double | value | ) |
Constructs a Rotation2d with the given radian value.
value | The value of the angle in radians. |
edu.wpi.first.math.geometry.Rotation2d.Rotation2d | ( | double | x, |
double | y ) |
Constructs a Rotation2d with the given x and y (cosine and sine) components.
x | The x component or cosine of the rotation. |
y | The y component or sine of the rotation. |
edu.wpi.first.math.geometry.Rotation2d.Rotation2d | ( | Measure< Angle > | angle | ) |
Constructs a Rotation2d with the given angle.
angle | The angle of the rotation. |
Rotation2d edu.wpi.first.math.geometry.Rotation2d.div | ( | double | scalar | ) |
Divides the current rotation by a scalar.
scalar | The scalar. |
boolean edu.wpi.first.math.geometry.Rotation2d.equals | ( | Object | obj | ) |
Checks equality between this Rotation2d and another object.
obj | The other object. |
|
static |
Constructs and returns a Rotation2d with the given degree value.
degrees | The value of the angle in degrees. |
|
static |
Constructs and returns a Rotation2d with the given radian value.
radians | The value of the angle in radians. |
|
static |
Constructs and returns a Rotation2d with the given number of rotations.
rotations | The value of the angle in rotations. |
double edu.wpi.first.math.geometry.Rotation2d.getCos | ( | ) |
Returns the cosine of the Rotation2d.
double edu.wpi.first.math.geometry.Rotation2d.getDegrees | ( | ) |
Returns the degree value of the Rotation2d.
double edu.wpi.first.math.geometry.Rotation2d.getRadians | ( | ) |
Returns the radian value of the Rotation2d.
double edu.wpi.first.math.geometry.Rotation2d.getRotations | ( | ) |
Returns the number of rotations of the Rotation2d.
double edu.wpi.first.math.geometry.Rotation2d.getSin | ( | ) |
Returns the sine of the Rotation2d.
double edu.wpi.first.math.geometry.Rotation2d.getTan | ( | ) |
Returns the tangent of the Rotation2d.
Rotation2d edu.wpi.first.math.geometry.Rotation2d.minus | ( | Rotation2d | other | ) |
Subtracts the new rotation from the current rotation and returns the new rotation.
For example, Rotation2d.fromDegrees(10).minus(Rotation2d.fromDegrees(100))
equals Rotation2d(-Math.PI/2.0)
other | The rotation to subtract. |
Rotation2d edu.wpi.first.math.geometry.Rotation2d.plus | ( | Rotation2d | other | ) |
Adds two rotations together, with the result being bounded between -pi and pi.
For example, Rotation2d.fromDegrees(30).plus(Rotation2d.fromDegrees(60))
equals Rotation2d(Math.PI/2.0)
other | The rotation to add. |
Rotation2d edu.wpi.first.math.geometry.Rotation2d.rotateBy | ( | Rotation2d | other | ) |
Adds the new rotation to the current rotation using a rotation matrix.
The matrix multiplication is as follows:
[cos_new] [other.cos, -other.sin][cos] [sin_new] = [other.sin, other.cos][sin] value_new = atan2(sin_new, cos_new)
other | The rotation to rotate by. |
Rotation2d edu.wpi.first.math.geometry.Rotation2d.times | ( | double | scalar | ) |
Multiplies the current rotation by a scalar.
scalar | The scalar. |
Rotation2d edu.wpi.first.math.geometry.Rotation2d.unaryMinus | ( | ) |
Takes the inverse of the current rotation. This is simply the negative of the current angular value.
|
static |
Rotation2d protobuf for serialization.
|
static |
Rotation2d struct for serialization.