WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
Rotation2d.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <type_traits>
8#include <utility>
9
10#include <Eigen/Core>
11#include <gcem.hpp>
12#include <wpi/StackTrace.h>
13#include <wpi/SymbolExports.h>
14#include <wpi/json_fwd.h>
15
16#include "frc/ct_matrix.h"
17#include "units/angle.h"
18#include "wpimath/MathShared.h"
19
20namespace frc {
21
22/**
23 * A rotation in a 2D coordinate frame represented by a point on the unit circle
24 * (cosine and sine).
25 */
27 public:
28 /**
29 * Constructs a Rotation2d with a default angle of 0 degrees.
30 */
31 constexpr Rotation2d() = default;
32
33 /**
34 * Constructs a Rotation2d with the given angle.
35 *
36 * @param value The value of the angle.
37 */
38 constexpr Rotation2d(units::angle_unit auto value) // NOLINT
39 : m_cos{gcem::cos(value.template convert<units::radian>().value())},
40 m_sin{gcem::sin(value.template convert<units::radian>().value())} {}
41
42 /**
43 * Constructs a Rotation2d with the given x and y (cosine and sine)
44 * components. The x and y don't have to be normalized.
45 *
46 * @param x The x component or cosine of the rotation.
47 * @param y The y component or sine of the rotation.
48 */
49 constexpr Rotation2d(double x, double y) {
50 double magnitude = gcem::hypot(x, y);
51 if (magnitude > 1e-6) {
52 m_cos = x / magnitude;
53 m_sin = y / magnitude;
54 } else {
55 m_cos = 1.0;
56 m_sin = 0.0;
57 if (!std::is_constant_evaluated()) {
59 "x and y components of Rotation2d are zero\n{}",
61 }
62 }
63 }
64
65 /**
66 * Constructs a Rotation2d from a rotation matrix.
67 *
68 * @param rotationMatrix The rotation matrix.
69 * @throws std::domain_error if the rotation matrix isn't special orthogonal.
70 */
71 constexpr explicit Rotation2d(const Eigen::Matrix2d& rotationMatrix) {
72 auto impl =
73 []<typename Matrix2d>(const Matrix2d& R) -> std::pair<double, double> {
74 // Require that the rotation matrix is special orthogonal. This is true if
75 // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
76 if ((R * R.transpose() - Matrix2d::Identity()).norm() > 1e-9) {
77 throw std::domain_error("Rotation matrix isn't orthogonal");
78 }
79 // HACK: Uses ct_matrix instead of <Eigen/LU> for determinant because
80 // including <Eigen/LU> doubles compilation times on MSVC, even if
81 // this constructor is unused. MSVC's frontend inefficiently parses
82 // large headers; GCC and Clang are largely unaffected.
83 if (gcem::abs(ct_matrix{R}.determinant() - 1.0) > 1e-9) {
84 throw std::domain_error(
85 "Rotation matrix is orthogonal but not special orthogonal");
86 }
87
88 // R = [cosθ −sinθ]
89 // [sinθ cosθ]
90 return {R(0, 0), R(1, 0)};
91 };
92
93 if (std::is_constant_evaluated()) {
94 auto cossin = impl(ct_matrix2d{rotationMatrix});
95 m_cos = std::get<0>(cossin);
96 m_sin = std::get<1>(cossin);
97 } else {
98 auto cossin = impl(rotationMatrix);
99 m_cos = std::get<0>(cossin);
100 m_sin = std::get<1>(cossin);
101 }
102 }
103
104 /**
105 * Adds two rotations together, with the result being bounded between -π and
106 * π.
107 *
108 * For example, <code>Rotation2d{30_deg} + Rotation2d{60_deg}</code> equals
109 * <code>Rotation2d{units::radian_t{std::numbers::pi/2.0}}</code>
110 *
111 * @param other The rotation to add.
112 *
113 * @return The sum of the two rotations.
114 */
115 constexpr Rotation2d operator+(const Rotation2d& other) const {
116 return RotateBy(other);
117 }
118
119 /**
120 * Subtracts the new rotation from the current rotation and returns the new
121 * rotation.
122 *
123 * For example, <code>Rotation2d{10_deg} - Rotation2d{100_deg}</code> equals
124 * <code>Rotation2d{units::radian_t{-std::numbers::pi/2.0}}</code>
125 *
126 * @param other The rotation to subtract.
127 *
128 * @return The difference between the two rotations.
129 */
130 constexpr Rotation2d operator-(const Rotation2d& other) const {
131 return *this + -other;
132 }
133
134 /**
135 * Takes the inverse of the current rotation. This is simply the negative of
136 * the current angular value.
137 *
138 * @return The inverse of the current rotation.
139 */
140 constexpr Rotation2d operator-() const { return Rotation2d{m_cos, -m_sin}; }
141
142 /**
143 * Multiplies the current rotation by a scalar.
144 *
145 * @param scalar The scalar.
146 *
147 * @return The new scaled Rotation2d.
148 */
149 constexpr Rotation2d operator*(double scalar) const {
150 return Rotation2d{Radians() * scalar};
151 }
152
153 /**
154 * Divides the current rotation by a scalar.
155 *
156 * @param scalar The scalar.
157 *
158 * @return The new scaled Rotation2d.
159 */
160 constexpr Rotation2d operator/(double scalar) const {
161 return *this * (1.0 / scalar);
162 }
163
164 /**
165 * Checks equality between this Rotation2d and another object.
166 *
167 * @param other The other object.
168 * @return Whether the two objects are equal.
169 */
170 constexpr bool operator==(const Rotation2d& other) const {
171 return gcem::hypot(Cos() - other.Cos(), Sin() - other.Sin()) < 1E-9;
172 }
173
174 /**
175 * Adds the new rotation to the current rotation using a rotation matrix.
176 *
177 * <pre>
178 * [cos_new] [other.cos, -other.sin][cos]
179 * [sin_new] = [other.sin, other.cos][sin]
180 * value_new = std::atan2(sin_new, cos_new)
181 * </pre>
182 *
183 * @param other The rotation to rotate by.
184 *
185 * @return The new rotated Rotation2d.
186 */
187 constexpr Rotation2d RotateBy(const Rotation2d& other) const {
188 return {Cos() * other.Cos() - Sin() * other.Sin(),
189 Cos() * other.Sin() + Sin() * other.Cos()};
190 }
191
192 /**
193 * Returns matrix representation of this rotation.
194 */
195 constexpr Eigen::Matrix2d ToMatrix() const {
196 // R = [cosθ −sinθ]
197 // [sinθ cosθ]
198 return Eigen::Matrix2d{{m_cos, -m_sin}, {m_sin, m_cos}};
199 }
200
201 /**
202 * Returns the radian value of the rotation constrained within [-π, π].
203 *
204 * @return The radian value of the rotation constrained within [-π, π].
205 */
206 constexpr units::radian_t Radians() const {
207 return units::radian_t{gcem::atan2(m_sin, m_cos)};
208 }
209
210 /**
211 * Returns the degree value of the rotation constrained within [-180, 180].
212 *
213 * @return The degree value of the rotation constrained within [-180, 180].
214 */
215 constexpr units::degree_t Degrees() const { return Radians(); }
216
217 /**
218 * Returns the cosine of the rotation.
219 *
220 * @return The cosine of the rotation.
221 */
222 constexpr double Cos() const { return m_cos; }
223
224 /**
225 * Returns the sine of the rotation.
226 *
227 * @return The sine of the rotation.
228 */
229 constexpr double Sin() const { return m_sin; }
230
231 /**
232 * Returns the tangent of the rotation.
233 *
234 * @return The tangent of the rotation.
235 */
236 constexpr double Tan() const { return Sin() / Cos(); }
237
238 private:
239 double m_cos = 1;
240 double m_sin = 0;
241};
242
244void to_json(wpi::json& json, const Rotation2d& rotation);
245
247void from_json(const wpi::json& json, Rotation2d& rotation);
248
249} // namespace frc
250
#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:26
constexpr Rotation2d operator/(double scalar) const
Divides the current rotation by a scalar.
Definition Rotation2d.h:160
constexpr Rotation2d(units::angle_unit auto value)
Constructs a Rotation2d with the given angle.
Definition Rotation2d.h:38
constexpr Rotation2d operator-() const
Takes the inverse of the current rotation.
Definition Rotation2d.h:140
constexpr Rotation2d operator-(const Rotation2d &other) const
Subtracts the new rotation from the current rotation and returns the new rotation.
Definition Rotation2d.h:130
constexpr bool operator==(const Rotation2d &other) const
Checks equality between this Rotation2d and another object.
Definition Rotation2d.h:170
constexpr double Tan() const
Returns the tangent of the rotation.
Definition Rotation2d.h:236
constexpr Rotation2d RotateBy(const Rotation2d &other) const
Adds the new rotation to the current rotation using a rotation matrix.
Definition Rotation2d.h:187
constexpr Rotation2d(const Eigen::Matrix2d &rotationMatrix)
Constructs a Rotation2d from a rotation matrix.
Definition Rotation2d.h:71
constexpr units::degree_t Degrees() const
Returns the degree value of the rotation constrained within [-180, 180].
Definition Rotation2d.h:215
constexpr Eigen::Matrix2d ToMatrix() const
Returns matrix representation of this rotation.
Definition Rotation2d.h:195
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:222
constexpr Rotation2d operator*(double scalar) const
Multiplies the current rotation by a scalar.
Definition Rotation2d.h:149
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:229
constexpr units::radian_t Radians() const
Returns the radian value of the rotation constrained within [-π, π].
Definition Rotation2d.h:206
constexpr Rotation2d operator+(const Rotation2d &other) const
Adds two rotations together, with the result being bounded between -π and π.
Definition Rotation2d.h:115
constexpr Rotation2d(double x, double y)
Constructs a Rotation2d with the given x and y (cosine and sine) components.
Definition Rotation2d.h:49
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:48
Definition SystemServer.h:9
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
Definition is_odd.hpp:29
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