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