mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Make Rotation2d member initialization order match declaration order (#7632)
This commit is contained in:
@@ -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());
|
||||
}
|
||||
|
||||
@@ -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{}",
|
||||
|
||||
Reference in New Issue
Block a user