Package edu.wpi.first.math.geometry
Class Rotation2d
java.lang.Object
edu.wpi.first.math.geometry.Rotation2d
- All Implemented Interfaces:
Interpolatable<Rotation2d>
public class Rotation2d extends Object implements Interpolatable<Rotation2d>
A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine).
-
Constructor Summary
Constructors Constructor Description Rotation2d()
Constructs a Rotation2d with a default angle of 0 degrees.Rotation2d(double value)
Constructs a Rotation2d with the given radian value.Rotation2d(double x, double y)
Constructs a Rotation2d with the given x and y (cosine and sine) components. -
Method Summary
Modifier and Type Method Description boolean
equals(Object obj)
Checks equality between this Rotation2d and another object.static Rotation2d
fromDegrees(double degrees)
Constructs and returns a Rotation2d with the given degree value.double
getCos()
Returns the cosine of the rotation.double
getDegrees()
Returns the degree value of the rotation.double
getRadians()
Returns the radian value of the rotation.double
getSin()
Returns the sine of the rotation.double
getTan()
Returns the tangent of the rotation.int
hashCode()
Rotation2d
interpolate(Rotation2d endValue, double t)
Return the interpolated value.Rotation2d
minus(Rotation2d other)
Subtracts the new rotation from the current rotation and returns the new rotation.Rotation2d
plus(Rotation2d other)
Adds two rotations together, with the result being bounded between -pi and pi.Rotation2d
rotateBy(Rotation2d other)
Adds the new rotation to the current rotation using a rotation matrix.Rotation2d
times(double scalar)
Multiplies the current rotation by a scalar.String
toString()
Rotation2d
unaryMinus()
Takes the inverse of the current rotation.
-
Constructor Details
-
Rotation2d
public Rotation2d()Constructs a Rotation2d with a default angle of 0 degrees. -
Rotation2d
Constructs a Rotation2d with the given radian value. The x and y don't have to be normalized.- Parameters:
value
- The value of the angle in radians.
-
Rotation2d
Constructs a Rotation2d with the given x and y (cosine and sine) components.- Parameters:
x
- The x component or cosine of the rotation.y
- The y component or sine of the rotation.
-
-
Method Details
-
fromDegrees
Constructs and returns a Rotation2d with the given degree value.- Parameters:
degrees
- The value of the angle in degrees.- Returns:
- The rotation object with the desired angle value.
-
plus
Adds two rotations together, with the result being bounded between -pi and pi.For example, Rotation2d.fromDegrees(30) + Rotation2d.fromDegrees(60) = Rotation2d{-pi/2}
- Parameters:
other
- The rotation to add.- Returns:
- The sum of the two rotations.
-
minus
Subtracts the new rotation from the current rotation and returns the new rotation.For example, Rotation2d.fromDegrees(10) - Rotation2d.fromDegrees(100) = Rotation2d{-pi/2}
- Parameters:
other
- The rotation to subtract.- Returns:
- The difference between the two rotations.
-
unaryMinus
Takes the inverse of the current rotation. This is simply the negative of the current angular value.- Returns:
- The inverse of the current rotation.
-
times
Multiplies the current rotation by a scalar.- Parameters:
scalar
- The scalar.- Returns:
- The new scaled Rotation2d.
-
rotateBy
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)
- Parameters:
other
- The rotation to rotate by.- Returns:
- The new rotated Rotation2d.
-
getRadians
Returns the radian value of the rotation.- Returns:
- The radian value of the rotation.
-
getDegrees
Returns the degree value of the rotation.- Returns:
- The degree value of the rotation.
-
getCos
Returns the cosine of the rotation.- Returns:
- The cosine of the rotation.
-
getSin
Returns the sine of the rotation.- Returns:
- The sine of the rotation.
-
getTan
Returns the tangent of the rotation.- Returns:
- The tangent of the rotation.
-
toString
-
equals
Checks equality between this Rotation2d and another object. -
hashCode
-
interpolate
Description copied from interface:Interpolatable
Return the interpolated value. This object is assumed to be the starting position, or lower bound.- Specified by:
interpolate
in interfaceInterpolatable<Rotation2d>
- Parameters:
endValue
- The upper bound, or end.t
- How far between the lower and upper bound we are. This should be bounded in [0, 1].- Returns:
- The interpolated value.
-