From 11a0c36737e50dd51d2b11e7e4b5a7edde3bfe78 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 3 Jan 2025 22:44:17 -0800 Subject: [PATCH] [wpimath] Make Rotation2d member initialization order match declaration order (#7632) --- .../src/main/java/edu/wpi/first/math/geometry/Rotation2d.java | 4 ++-- wpimath/src/main/native/include/frc/geometry/Rotation2d.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java index 693a7f2bfc..2d4206b8c6 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java @@ -117,11 +117,11 @@ public class Rotation2d 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()); } diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h index 398c2fdb61..82d9e39d78 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h @@ -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{}",