[wpimath] Remove Rotation2d value field (#7490)

It's not part of SO(2).
This commit is contained in:
Tyler Veness
2024-12-06 21:00:09 -08:00
committed by GitHub
parent 38b09a6dfd
commit 144e79a614
6 changed files with 29 additions and 48 deletions

View File

@@ -23,10 +23,6 @@ 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)
@@ -81,13 +77,11 @@ public class Rotation2d
*/
public static final Rotation2d k180deg = kPi;
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;
}
@@ -99,7 +93,6 @@ public class Rotation2d
*/
@JsonCreator
public Rotation2d(@JsonProperty(required = true, value = "radians") double value) {
m_value = value;
m_cos = Math.cos(value);
m_sin = Math.sin(value);
}
@@ -121,7 +114,6 @@ public class Rotation2d
MathSharedStore.reportError(
"x and y components of Rotation2d are zero\n", Thread.currentThread().getStackTrace());
}
m_value = Math.atan2(m_sin, m_cos);
}
/**
@@ -196,7 +188,7 @@ public class Rotation2d
* @return The inverse of the current rotation.
*/
public Rotation2d unaryMinus() {
return new Rotation2d(-m_value);
return new Rotation2d(m_cos, -m_sin);
}
/**
@@ -206,7 +198,7 @@ public class Rotation2d
* @return The new scaled Rotation2d.
*/
public Rotation2d times(double scalar) {
return new Rotation2d(m_value * scalar);
return new Rotation2d(getRadians() * scalar);
}
/**
@@ -248,25 +240,22 @@ public class Rotation2d
}
/**
* Returns the radian value of the Rotation2d.
* Returns the radian value of the Rotation2d constrained within [-π, π].
*
* @return The radian value of the Rotation2d.
* @see edu.wpi.first.math.MathUtil#angleModulus(double) to constrain the angle within (-π, π]
* @return The radian value of the Rotation2d constrained within [-π, π].
*/
@JsonProperty
public double getRadians() {
return m_value;
return Math.atan2(m_sin, m_cos);
}
/**
* Returns the degree value of the Rotation2d.
* Returns the degree value of the Rotation2d constrained within [-180, 180].
*
* @return The degree value of the Rotation2d.
* @see edu.wpi.first.math.MathUtil#inputModulus(double, double, double) to constrain the angle
* within (-180, 180]
* @return The degree value of the Rotation2d constrained within [-180, 180].
*/
public double getDegrees() {
return Math.toDegrees(m_value);
return Math.toDegrees(getRadians());
}
/**
@@ -275,7 +264,7 @@ public class Rotation2d
* @return The number of rotations of the Rotation2d.
*/
public double getRotations() {
return Units.radiansToRotations(m_value);
return Units.radiansToRotations(getRadians());
}
/**
@@ -307,7 +296,7 @@ public class Rotation2d
@Override
public String toString() {
return String.format("Rotation2d(Rads: %.2f, Deg: %.2f)", m_value, Math.toDegrees(m_value));
return String.format("Rotation2d(Rads: %.2f, Deg: %.2f)", getRadians(), getDegrees());
}
/**
@@ -324,7 +313,7 @@ public class Rotation2d
@Override
public int hashCode() {
return Objects.hash(m_value);
return Objects.hash(getRadians());
}
@Override