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