Package xbot.common.math
Class WrappedRotation2d
java.lang.Object
edu.wpi.first.math.geometry.Rotation2d
xbot.common.math.WrappedRotation2d
- All Implemented Interfaces:
Interpolatable<Rotation2d>
,ProtobufSerializable
,StructSerializable
,WPISerializable
A rotation in a 2d coordinate frame, with its rotation wrapped from -pi to pi radians (-180 to 180 degrees).
Prefer this class over Rotation2d when representing robot pose.
-
Field Summary
Fields inherited from class edu.wpi.first.math.geometry.Rotation2d
k180deg, kCCW_90deg, kCCW_Pi_2, kCW_90deg, kCW_Pi_2, kPi, kZero, proto, struct
-
Constructor Summary
ConstructorDescriptionWrappedRotation2d
(double value) Constructs a WrappedRotation2d with the given radian value.WrappedRotation2d
(double x, double y) Constructs a WrappedRotation2d with the given x and y (cosine and sine) components. -
Method Summary
Modifier and TypeMethodDescriptionstatic WrappedRotation2d
fromDegrees
(double degrees) Constructs and returns a Rotation2d with the given degree value.static WrappedRotation2d
fromRotation2d
(Rotation2d rotation) Converts a Rotation2d to the wrapped equivalent.Methods inherited from class edu.wpi.first.math.geometry.Rotation2d
div, equals, fromRadians, fromRotations, getCos, getDegrees, getMeasure, getRadians, getRotations, getSin, getTan, hashCode, interpolate, minus, plus, rotateBy, times, toMatrix, toString, unaryMinus
-
Constructor Details
-
WrappedRotation2d
public WrappedRotation2d(double value) Constructs a WrappedRotation2d with the given radian value.- Parameters:
value
- The value of the angle in radians.
-
WrappedRotation2d
public WrappedRotation2d(double x, double y) Constructs a WrappedRotation2d with the given x and y (cosine and sine) components. The x and y don't have to be normalized.- Parameters:
x
- The x component or cosine of the rotation.y
- The y component or sine of the rotation.
-
-
Method Details
-
fromRotation2d
Converts a Rotation2d to the wrapped equivalent.- Parameters:
rotation
- The rotation.- Returns:
- The rotation with its angle wrapped from -pi to pi radians.
-
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.
-