mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Revert Rotation2D change that limits angles (#4781)
Reverts "[wpimath] Constrain Rotation2d range to -pi to pi (#4611)"
This reverts commit d1d458db2b.
This broke multiple teams code in beta. It is also easier to limit the angle externally, then reconstruct a larger angle that got limited. This additionally adds comments to clarify the behavior and retains tests that were added in the reverted commit, and fixes a javadoc comment angle reference.
This commit is contained in:
@@ -15,15 +15,21 @@ import java.util.Objects;
|
||||
|
||||
/**
|
||||
* A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
|
||||
*
|
||||
* <p>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.
|
||||
*/
|
||||
@JsonIgnoreProperties(ignoreUnknown = true)
|
||||
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
|
||||
public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
private final double m_value;
|
||||
private final double m_cos;
|
||||
private final double m_sin;
|
||||
|
||||
/** Constructs a Rotation2d with a default angle of 0 degrees. */
|
||||
public Rotation2d() {
|
||||
m_value = 0.0;
|
||||
m_cos = 1.0;
|
||||
m_sin = 0.0;
|
||||
}
|
||||
@@ -35,7 +41,9 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
*/
|
||||
@JsonCreator
|
||||
public Rotation2d(@JsonProperty(required = true, value = "radians") double value) {
|
||||
this(Math.cos(value), Math.sin(value));
|
||||
m_value = value;
|
||||
m_cos = Math.cos(value);
|
||||
m_sin = Math.sin(value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -53,12 +61,13 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
m_sin = 0.0;
|
||||
m_cos = 1.0;
|
||||
}
|
||||
m_value = Math.atan2(m_sin, m_cos);
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs and returns a Rotation2d with the given radian value.
|
||||
*
|
||||
* @param radians The value of the angle in degrees.
|
||||
* @param radians The value of the angle in radians.
|
||||
* @return The rotation object with the desired angle value.
|
||||
*/
|
||||
public static Rotation2d fromRadians(double radians) {
|
||||
@@ -118,7 +127,7 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
* @return The inverse of the current rotation.
|
||||
*/
|
||||
public Rotation2d unaryMinus() {
|
||||
return new Rotation2d(m_cos, -m_sin);
|
||||
return new Rotation2d(-m_value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -128,7 +137,7 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
* @return The new scaled Rotation2d.
|
||||
*/
|
||||
public Rotation2d times(double scalar) {
|
||||
return new Rotation2d(getRadians() * scalar);
|
||||
return new Rotation2d(m_value * scalar);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -161,22 +170,22 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the radian value of the Rotation2d within (-pi, pi].
|
||||
* Returns the radian value of the Rotation2d.
|
||||
*
|
||||
* @return The radian value of the Rotation2d.
|
||||
*/
|
||||
@JsonProperty
|
||||
public double getRadians() {
|
||||
return Math.atan2(m_sin, m_cos);
|
||||
return m_value;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the degree value of the Rotation2d within (-180, 180].
|
||||
* Returns the degree value of the Rotation2d.
|
||||
*
|
||||
* @return The degree value of the Rotation2d.
|
||||
*/
|
||||
public double getDegrees() {
|
||||
return Math.toDegrees(getRadians());
|
||||
return Math.toDegrees(m_value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -185,7 +194,7 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
* @return The number of rotations of the Rotation2d.
|
||||
*/
|
||||
public double getRotations() {
|
||||
return Units.radiansToRotations(getRadians());
|
||||
return Units.radiansToRotations(m_value);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -217,7 +226,7 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
|
||||
@Override
|
||||
public String toString() {
|
||||
return String.format("Rotation2d(Rads: %.2f, Deg: %.2f)", getRadians(), getDegrees());
|
||||
return String.format("Rotation2d(Rads: %.2f, Deg: %.2f)", m_value, Math.toDegrees(m_value));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -237,7 +246,7 @@ public class Rotation2d implements Interpolatable<Rotation2d> {
|
||||
|
||||
@Override
|
||||
public int hashCode() {
|
||||
return Objects.hash(getRadians());
|
||||
return Objects.hash(m_value);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
Reference in New Issue
Block a user