15#include "wpi/units/angle.hpp"
39 : m_cos{
gcem::cos(value.template convert<
wpi::units::radian>().value())},
40 m_sin{
gcem::sin(value.template convert<
wpi::units::radian>().value())} {
52 if (magnitude > 1e-6) {
53 m_cos = x / magnitude;
54 m_sin = y / magnitude;
58 if (!std::is_constant_evaluated()) {
60 "x and y components of Rotation2d are zero\n{}",
72 constexpr explicit Rotation2d(
const Eigen::Matrix2d& rotationMatrix) {
74 []<
typename Matrix2d>(
const Matrix2d& R) -> std::pair<double, double> {
77 if ((R * R.transpose() - Matrix2d::Identity()).norm() > 1e-9) {
78 throw std::domain_error(
"Rotation matrix isn't orthogonal");
85 throw std::domain_error(
86 "Rotation matrix is orthogonal but not special orthogonal");
91 return {R(0, 0), R(1, 0)};
94 if (std::is_constant_evaluated()) {
96 m_cos = std::get<0>(cossin);
97 m_sin = std::get<1>(cossin);
99 auto cossin =
impl(rotationMatrix);
100 m_cos = std::get<0>(cossin);
101 m_sin = std::get<1>(cossin);
131 return *
this + -other;
161 return *
this * (1.0 / scalar);
211 return Eigen::Matrix2d{{m_cos, -m_sin}, {m_sin, m_cos}};
219 constexpr wpi::units::radian_t
Radians()
const {
220 return wpi::units::radian_t{
gcem::atan2(m_sin, m_cos)};
235 constexpr double Cos()
const {
return m_cos; }
242 constexpr double Sin()
const {
return m_sin; }
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
static void ReportError(const S &format, Args &&... args)
Definition MathShared.hpp:48
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
constexpr Rotation2d operator+(const Rotation2d &other) const
Adds two rotations together, with the result being bounded between -π and π.
Definition Rotation2d.hpp:116
constexpr Rotation2d RotateBy(const Rotation2d &other) const
Adds the new rotation to the current rotation using a rotation matrix.
Definition Rotation2d.hpp:187
constexpr Rotation2d(wpi::units::angle_unit auto value)
Constructs a Rotation2d with the given angle.
Definition Rotation2d.hpp:38
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.hpp:235
constexpr Rotation2d operator/(double scalar) const
Divides the current rotation by a scalar.
Definition Rotation2d.hpp:160
constexpr Rotation2d(const Eigen::Matrix2d &rotationMatrix)
Constructs a Rotation2d from a rotation matrix.
Definition Rotation2d.hpp:72
constexpr wpi::units::radian_t Radians() const
Returns the radian value of the rotation constrained within [-π, π].
Definition Rotation2d.hpp:219
constexpr Rotation2d operator-() const
Takes the inverse of the current rotation.
Definition Rotation2d.hpp:140
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.hpp:242
constexpr Rotation2d operator-(const Rotation2d &other) const
Returns this rotation relative to another rotation.
Definition Rotation2d.hpp:130
constexpr double Tan() const
Returns the tangent of the rotation.
Definition Rotation2d.hpp:249
constexpr Rotation2d()=default
Constructs a Rotation2d with a default angle of 0 degrees.
constexpr wpi::units::degree_t Degrees() const
Returns the degree value of the rotation constrained within [-180, 180].
Definition Rotation2d.hpp:228
constexpr Rotation2d RelativeTo(const Rotation2d &other) const
Returns the current rotation relative to the given rotation.
Definition Rotation2d.hpp:201
constexpr bool operator==(const Rotation2d &other) const
Checks equality between this Rotation2d and another object.
Definition Rotation2d.hpp:170
constexpr Rotation2d(double x, double y)
Constructs a Rotation2d with the given x and y (cosine and sine) components.
Definition Rotation2d.hpp:50
constexpr Rotation2d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Definition Rotation2d.hpp:149
constexpr Eigen::Matrix2d ToMatrix() const
Returns matrix representation of this rotation.
Definition Rotation2d.hpp:208
Compile-time wrapper for Eigen::Matrix.
Definition ct_matrix.hpp:26
constexpr Scalar determinant() const
Constexpr version of Eigen's 2x2 matrix determinant member function.
Definition ct_matrix.hpp:316
basic_json<> json
default specialization
Definition json_fwd.hpp:62
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
Definition RobotBase.hpp:26
Definition LinearSystem.hpp:20
ct_matrix< double, 2, 2 > ct_matrix2d
Definition ct_matrix.hpp:384
WPILIB_DLLEXPORT void to_json(wpi::util::json &json, const Translation2d &state)
WPILIB_DLLEXPORT void from_json(const wpi::util::json &json, Translation2d &state)
std::string GetStackTrace(int offset)
Get a stack trace, ignoring the first "offset" symbols.
Definition CvSource.hpp:15