Skip to content

Commit

Permalink
[wpimath] Report error when x and y components of Rotation2d are zero
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul committed Jun 22, 2024
1 parent 2ff7033 commit acfc0df
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,8 @@ public Rotation2d(double x, double y) {
} else {
m_sin = 0.0;
m_cos = 1.0;
MathSharedStore.reportError(
"x and y components of Rotation2d are zero\n", Thread.currentThread().getStackTrace());
}
m_value = Math.atan2(m_sin, m_cos);
}
Expand Down
11 changes: 11 additions & 0 deletions wpimath/src/main/native/include/frc/geometry/Rotation2d.inc
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,15 @@

#pragma once

#include <string>
#include <type_traits>

#include <gcem.hpp>
#include <wpi/StackTrace.h>

#include "frc/geometry/Rotation2d.h"
#include "units/angle.h"
#include "wpimath/MathShared.h"

namespace frc {

Expand All @@ -24,6 +29,12 @@ constexpr Rotation2d::Rotation2d(double x, double y) {
} else {
m_sin = 0.0;
m_cos = 1.0;
if (!std::is_constant_evaluated()) {
std::string msg =
fmt::format("x and y components of Rotation2d are zero\n{}",
wpi::GetStackTrace(1));
wpi::math::MathSharedStore::ReportError(msg);
}
}
m_value = units::radian_t{gcem::atan2(m_sin, m_cos)};
}
Expand Down

0 comments on commit acfc0df

Please sign in to comment.