45 m_cos{
gcem::cos(value.template convert<
units::radian>().value())},
46 m_sin{
gcem::sin(value.template convert<
units::radian>().value())} {}
57 if (magnitude > 1e-6) {
58 m_cos = x / magnitude;
59 m_sin = y / magnitude;
63 if (!std::is_constant_evaluated()) {
65 "x and y components of Rotation2d are zero\n{}",
69 m_value = units::radian_t{
gcem::atan2(m_sin, m_cos)};
78 constexpr explicit Rotation2d(
const Eigen::Matrix2d& rotationMatrix) {
80 []<
typename Matrix2d>(
const Matrix2d& R) -> std::pair<double, double> {
83 if ((R * R.transpose() - Matrix2d::Identity()).norm() > 1e-9) {
84 throw std::domain_error(
"Rotation matrix isn't orthogonal");
91 throw std::domain_error(
92 "Rotation matrix is orthogonal but not special orthogonal");
97 return {R(0, 0), R(1, 0)};
100 if (std::is_constant_evaluated()) {
102 m_cos = std::get<0>(cossin);
103 m_sin = std::get<1>(cossin);
105 auto cossin = impl(rotationMatrix);
106 m_cos = std::get<0>(cossin);
107 m_sin = std::get<1>(cossin);
110 m_value = units::radian_t{
gcem::atan2(m_sin, m_cos)};
125 return RotateBy(other);
140 return *
this + -other;
170 return *
this * (1.0 /
scalar);
180 return gcem::hypot(Cos() - other.Cos(), Sin() - other.Sin()) < 1E-9;
197 return {Cos() * other.Cos() - Sin() * other.Sin(),
198 Cos() * other.Sin() + Sin() * other.Cos()};
207 return Eigen::Matrix2d{{m_cos, -m_sin}, {m_sin, m_cos}};
216 constexpr units::radian_t
Radians()
const {
return m_value; }
224 constexpr units::degree_t
Degrees()
const {
return m_value; }
231 constexpr double Cos()
const {
return m_cos; }
238 constexpr double Sin()
const {
return m_sin; }
245 constexpr double Tan()
const {
return Sin() / Cos(); }
248 units::radian_t m_value = 0_rad;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
constexpr Rotation2d operator/(double scalar) const
Divides the current rotation by a scalar.
Definition Rotation2d.h:169
constexpr Rotation2d(units::angle_unit auto value)
Constructs a Rotation2d with the given angle.
Definition Rotation2d.h:43
constexpr Rotation2d operator-() const
Takes the inverse of the current rotation.
Definition Rotation2d.h:149
constexpr Rotation2d operator-(const Rotation2d &other) const
Subtracts the new rotation from the current rotation and returns the new rotation.
Definition Rotation2d.h:139
constexpr bool operator==(const Rotation2d &other) const
Checks equality between this Rotation2d and another object.
Definition Rotation2d.h:179
constexpr double Tan() const
Returns the tangent of the rotation.
Definition Rotation2d.h:245
constexpr Rotation2d RotateBy(const Rotation2d &other) const
Adds the new rotation to the current rotation using a rotation matrix.
Definition Rotation2d.h:196
constexpr Rotation2d(const Eigen::Matrix2d &rotationMatrix)
Constructs a Rotation2d from a rotation matrix.
Definition Rotation2d.h:78
constexpr units::degree_t Degrees() const
Returns the degree value of the rotation.
Definition Rotation2d.h:224
constexpr Eigen::Matrix2d ToMatrix() const
Returns matrix representation of this rotation.
Definition Rotation2d.h:204
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:231
constexpr Rotation2d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Definition Rotation2d.h:158
constexpr Rotation2d()=default
Constructs a Rotation2d with a default angle of 0 degrees.
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:238
constexpr units::radian_t Radians() const
Returns the radian value of the rotation.
Definition Rotation2d.h:216
constexpr Rotation2d operator+(const Rotation2d &other) const
Adds two rotations together, with the result being bounded between -π and π.
Definition Rotation2d.h:124
constexpr Rotation2d(double x, double y)
Constructs a Rotation2d with the given x and y (cosine and sine) components.
Definition Rotation2d.h:55
Compile-time wrapper for Eigen::Matrix.
Definition ct_matrix.h:26
constexpr Scalar determinant() const
Constexpr version of Eigen's 2x2 matrix determinant member function.
Definition ct_matrix.h:316
static void ReportError(const S &format, Args &&... args)
Definition MathShared.h:62
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
constexpr common_return_t< T1, T2 > atan2(const T1 y, const T2 x) noexcept
Compile-time two-argument arctangent function.
Definition atan2.hpp:88
Unit Conversion Library namespace.
Definition acceleration.h:33
std::string GetStackTrace(int offset)
Get a stack trace, ignoring the first "offset" symbols.
Type representing an arbitrary unit.
Definition base.h:888