Skip to content

Commit

Permalink
[wpimath] Make Rotation2d member initialization order match declarati…
Browse files Browse the repository at this point in the history
…on order
  • Loading branch information
calcmogul committed Jan 4, 2025
1 parent 17a0351 commit 0eae12f
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -117,11 +117,11 @@ public Rotation2d(@JsonProperty(required = true, value = "radians") double value
public Rotation2d(double x, double y) {
double magnitude = Math.hypot(x, y);
if (magnitude > 1e-6) {
m_sin = y / magnitude;
m_cos = x / magnitude;
m_sin = y / magnitude;
} else {
m_sin = 0.0;
m_cos = 1.0;
m_sin = 0.0;
MathSharedStore.reportError(
"x and y components of Rotation2d are zero\n", Thread.currentThread().getStackTrace());
}
Expand Down
4 changes: 2 additions & 2 deletions wpimath/src/main/native/include/frc/geometry/Rotation2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,11 +55,11 @@ class WPILIB_DLLEXPORT Rotation2d {
constexpr Rotation2d(double x, double y) {
double magnitude = gcem::hypot(x, y);
if (magnitude > 1e-6) {
m_sin = y / magnitude;
m_cos = x / magnitude;
m_sin = y / magnitude;
} else {
m_sin = 0.0;
m_cos = 1.0;
m_sin = 0.0;
if (!std::is_constant_evaluated()) {
wpi::math::MathSharedStore::ReportError(
"x and y components of Rotation2d are zero\n{}",
Expand Down

0 comments on commit 0eae12f

Please sign in to comment.