WPILibC++ 2027.0.0-alpha-4
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#include "wpi/util/json_fwd.hpp"
19
20namespace wpi::math {
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(wpi::units::angle_unit auto value) // NOLINT
39 : m_cos{gcem::cos(value.template convert<wpi::units::radian>().value())},
40 m_sin{gcem::sin(value.template convert<wpi::units::radian>().value())} {
41 }
42
43 /**
44 * Constructs a Rotation2d with the given x and y (cosine and sine)
45 * components. The x and y don't have to be normalized.
46 *
47 * @param x The x component or cosine of the rotation.
48 * @param y The y component or sine of the rotation.
49 */
50 constexpr Rotation2d(double x, double y) {
51 double magnitude = gcem::hypot(x, y);
52 if (magnitude > 1e-6) {
53 m_cos = x / magnitude;
54 m_sin = y / magnitude;
55 } else {
56 m_cos = 1.0;
57 m_sin = 0.0;
58 if (!std::is_constant_evaluated()) {
60 "x and y components of Rotation2d are zero\n{}",
62 }
63 }
64 }
65
66 /**
67 * Constructs a Rotation2d from a rotation matrix.
68 *
69 * @param rotationMatrix The rotation matrix.
70 * @throws std::domain_error if the rotation matrix isn't special orthogonal.
71 */
72 constexpr explicit Rotation2d(const Eigen::Matrix2d& rotationMatrix) {
73 auto impl =
74 []<typename Matrix2d>(const Matrix2d& R) -> std::pair<double, double> {
75 // Require that the rotation matrix is special orthogonal. This is true if
76 // the matrix is orthogonal (RRᵀ = I) and normalized (determinant is 1).
77 if ((R * R.transpose() - Matrix2d::Identity()).norm() > 1e-9) {
78 throw std::domain_error("Rotation matrix isn't orthogonal");
79 }
80 // HACK: Uses ct_matrix instead of <Eigen/LU> for determinant because
81 // including <Eigen/LU> doubles compilation times on MSVC, even if
82 // this constructor is unused. MSVC's frontend inefficiently parses
83 // large headers; GCC and Clang are largely unaffected.
84 if (gcem::abs(ct_matrix{R}.determinant() - 1.0) > 1e-9) {
85 throw std::domain_error(
86 "Rotation matrix is orthogonal but not special orthogonal");
87 }
88
89 // R = [cosθ −sinθ]
90 // [sinθ cosθ]
91 return {R(0, 0), R(1, 0)};
92 };
93
94 if (std::is_constant_evaluated()) {
95 auto cossin = impl(ct_matrix2d{rotationMatrix});
96 m_cos = std::get<0>(cossin);
97 m_sin = std::get<1>(cossin);
98 } else {
99 auto cossin = impl(rotationMatrix);
100 m_cos = std::get<0>(cossin);
101 m_sin = std::get<1>(cossin);
102 }
103 }
104
105 /**
106 * Adds two rotations together, with the result being bounded between -π and
107 * π.
108 *
109 * For example, <code>Rotation2d{30_deg} + Rotation2d{60_deg}</code> equals
110 * <code>Rotation2d{wpi::units::radian_t{std::numbers::pi/2.0}}</code>
111 *
112 * @param other The rotation to add.
113 *
114 * @return The sum of the two rotations.
115 */
116 constexpr Rotation2d operator+(const Rotation2d& other) const {
117 return RotateBy(other);
118 }
119
120 /**
121 * Returns this rotation relative to another rotation.
122 *
123 * For example, <code>Rotation2d{10_deg} - Rotation2d{100_deg}</code> equals
124 * <code>Rotation2d{wpi::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 the current rotation relative to the given rotation.
194 *
195 * @param other The rotation describing the orientation of the new coordinate
196 * frame that the current rotation will be converted into.
197 *
198 * @return The current rotation relative to the new orientation of the
199 * coordinate frame.
200 */
201 constexpr Rotation2d RelativeTo(const Rotation2d& other) const {
202 return RotateBy(-other);
203 }
204
205 /**
206 * Returns matrix representation of this rotation.
207 */
208 constexpr Eigen::Matrix2d ToMatrix() const {
209 // R = [cosθ −sinθ]
210 // [sinθ cosθ]
211 return Eigen::Matrix2d{{m_cos, -m_sin}, {m_sin, m_cos}};
212 }
213
214 /**
215 * Returns the radian value of the rotation constrained within [-π, π].
216 *
217 * @return The radian value of the rotation constrained within [-π, π].
218 */
219 constexpr wpi::units::radian_t Radians() const {
220 return wpi::units::radian_t{gcem::atan2(m_sin, m_cos)};
221 }
222
223 /**
224 * Returns the degree value of the rotation constrained within [-180, 180].
225 *
226 * @return The degree value of the rotation constrained within [-180, 180].
227 */
228 constexpr wpi::units::degree_t Degrees() const { return Radians(); }
229
230 /**
231 * Returns the cosine of the rotation.
232 *
233 * @return The cosine of the rotation.
234 */
235 constexpr double Cos() const { return m_cos; }
236
237 /**
238 * Returns the sine of the rotation.
239 *
240 * @return The sine of the rotation.
241 */
242 constexpr double Sin() const { return m_sin; }
243
244 /**
245 * Returns the tangent of the rotation.
246 *
247 * @return The tangent of the rotation.
248 */
249 constexpr double Tan() const { return Sin() / Cos(); }
250
251 private:
252 double m_cos = 1;
253 double m_sin = 0;
254};
255
257void to_json(wpi::util::json& json, const Rotation2d& rotation);
258
260void from_json(const wpi::util::json& json, Rotation2d& rotation);
261
262} // namespace wpi::math
263
#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
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)
std::string GetStackTrace(int offset)
Get a stack trace, ignoring the first "offset" symbols.
Definition CvSource.hpp:15