WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
Quaternion.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 <numbers>
8
9#include <Eigen/Core>
10#include <gcem.hpp>
11
13
14namespace wpi::util {
15class json;
16} // namespace wpi::util
17
18namespace wpi::math {
19
20/**
21 * Represents a quaternion.
22 */
24 public:
25 /**
26 * Constructs a quaternion with a default angle of 0 degrees.
27 */
28 constexpr Quaternion() = default;
29
30 /**
31 * Constructs a quaternion with the given components.
32 *
33 * @param w W component of the quaternion.
34 * @param x X component of the quaternion.
35 * @param y Y component of the quaternion.
36 * @param z Z component of the quaternion.
37 */
38 constexpr Quaternion(double w, double x, double y, double z)
39 : m_w{w}, m_x{x}, m_y{y}, m_z{z} {}
40
41 /**
42 * Adds with another quaternion.
43 *
44 * @param other the other quaternion
45 */
46 constexpr Quaternion operator+(const Quaternion& other) const {
47 return Quaternion{m_w + other.m_w, m_x + other.m_x, m_y + other.m_y,
48 m_z + other.m_z};
49 }
50
51 /**
52 * Subtracts another quaternion.
53 *
54 * @param other the other quaternion
55 */
56 constexpr Quaternion operator-(const Quaternion& other) const {
57 return Quaternion{m_w - other.m_w, m_x - other.m_x, m_y - other.m_y,
58 m_z - other.m_z};
59 }
60
61 /**
62 * Multiples with a scalar value.
63 *
64 * @param other the scalar value
65 */
66 constexpr Quaternion operator*(double other) const {
67 return Quaternion{m_w * other, m_x * other, m_y * other, m_z * other};
68 }
69
70 /**
71 * Divides by a scalar value.
72 *
73 * @param other the scalar value
74 */
75 constexpr Quaternion operator/(double other) const {
76 return Quaternion{m_w / other, m_x / other, m_y / other, m_z / other};
77 }
78
79 /**
80 * Multiply with another quaternion.
81 *
82 * @param other The other quaternion.
83 */
84 constexpr Quaternion operator*(const Quaternion& other) const {
85 // https://en.wikipedia.org/wiki/Quaternion#Scalar_and_vector_parts
86 const auto& r1 = m_w;
87 const auto& r2 = other.m_w;
88
89 // v₁ ⋅ v₂
90 double dot = m_x * other.m_x + m_y * other.m_y + m_z * other.m_z;
91
92 // v₁ x v₂
93 double cross_x = m_y * other.m_z - other.m_y * m_z;
94 double cross_y = other.m_x * m_z - m_x * other.m_z;
95 double cross_z = m_x * other.m_y - other.m_x * m_y;
96
97 return Quaternion{// r = r₁r₂ − v₁ ⋅ v₂
98 r1 * r2 - dot,
99 // v = r₁v₂ + r₂v₁ + v₁ x v₂
100 r1 * other.m_x + r2 * m_x + cross_x,
101 r1 * other.m_y + r2 * m_y + cross_y,
102 r1 * other.m_z + r2 * m_z + cross_z};
103 }
104
105 /**
106 * Checks equality between this Quaternion and another object.
107 *
108 * @param other The other object.
109 * @return Whether the two objects are equal.
110 */
111 constexpr bool operator==(const Quaternion& other) const {
112 return gcem::abs(Dot(other) - Norm() * other.Norm()) < 1e-9 &&
113 gcem::abs(Norm() - other.Norm()) < 1e-9;
114 }
115
116 /**
117 * Returns the elementwise product of two quaternions.
118 */
119 constexpr double Dot(const Quaternion& other) const {
120 return W() * other.W() + X() * other.X() + Y() * other.Y() +
121 Z() * other.Z();
122 }
123
124 /**
125 * Returns the conjugate of the quaternion.
126 */
127 constexpr Quaternion Conjugate() const {
128 return Quaternion{W(), -X(), -Y(), -Z()};
129 }
130
131 /**
132 * Returns the inverse of the quaternion.
133 */
134 constexpr Quaternion Inverse() const {
135 double norm = Norm();
136 return Conjugate() / (norm * norm);
137 }
138
139 /**
140 * Normalizes the quaternion.
141 */
142 constexpr Quaternion Normalize() const {
143 double norm = Norm();
144 if (norm == 0.0) {
145 return Quaternion{};
146 } else {
147 return Quaternion{W(), X(), Y(), Z()} / norm;
148 }
149 }
150
151 /**
152 * Calculates the L2 norm of the quaternion.
153 */
154 constexpr double Norm() const { return gcem::sqrt(Dot(*this)); }
155
156 /**
157 * Calculates this quaternion raised to a power.
158 *
159 * @param t the power to raise this quaternion to.
160 */
161 constexpr Quaternion Pow(double t) const { return (Log() * t).Exp(); }
162
163 /**
164 * Matrix exponential of a quaternion.
165 *
166 * source: wpimath/algorithms.md
167 *
168 * If this quaternion is in 𝖘𝖔(3) and you are looking for an element of
169 * SO(3), use FromRotationVector
170 */
171 constexpr Quaternion Exp() const {
172 double scalar = gcem::exp(m_w);
173
174 double axial_magnitude = gcem::hypot(m_x, m_y, m_z);
175 double cosine = gcem::cos(axial_magnitude);
176
177 double axial_scalar;
178
179 if (axial_magnitude < 1e-9) {
180 // Taylor series of sin(x)/x near x=0: 1 − x²/6 + x⁴/120 + O(n⁶)
181 double axial_magnitude_sq = axial_magnitude * axial_magnitude;
182 double axial_magnitude_sq_sq = axial_magnitude_sq * axial_magnitude_sq;
183 axial_scalar =
184 1.0 - axial_magnitude_sq / 6.0 + axial_magnitude_sq_sq / 120.0;
185 } else {
186 axial_scalar = gcem::sin(axial_magnitude) / axial_magnitude;
187 }
188
189 return Quaternion(cosine * scalar, X() * axial_scalar * scalar,
190 Y() * axial_scalar * scalar, Z() * axial_scalar * scalar);
191 }
192
193 /**
194 * Log operator of a quaternion.
195 *
196 * source: wpimath/algorithms.md
197 *
198 * If this quaternion is in SO(3) and you are looking for an element of 𝖘𝖔(3),
199 * use ToRotationVector
200 */
201 constexpr Quaternion Log() const {
202 double norm = Norm();
203 double scalar = gcem::log(norm);
204
205 double v_norm = gcem::hypot(m_x, m_y, m_z);
206
207 double s_norm = W() / norm;
208
209 if (gcem::abs(s_norm + 1) < 1e-9) {
210 return Quaternion{scalar, -std::numbers::pi, 0, 0};
211 }
212
213 double v_scalar;
214
215 if (v_norm < 1e-9) {
216 // Taylor series expansion of atan2(y/x)/y at y = 0:
217 //
218 // 1/x - 1/3 y²/x³ + O(y⁴)
219 v_scalar = 1.0 / W() - 1.0 / 3.0 * v_norm * v_norm / (W() * W() * W());
220 } else {
221 v_scalar = gcem::atan2(v_norm, W()) / v_norm;
222 }
223
224 return Quaternion{scalar, v_scalar * m_x, v_scalar * m_y, v_scalar * m_z};
225 }
226
227 /**
228 * Returns W component of the quaternion.
229 */
230 constexpr double W() const { return m_w; }
231
232 /**
233 * Returns X component of the quaternion.
234 */
235 constexpr double X() const { return m_x; }
236
237 /**
238 * Returns Y component of the quaternion.
239 */
240 constexpr double Y() const { return m_y; }
241
242 /**
243 * Returns Z component of the quaternion.
244 */
245 constexpr double Z() const { return m_z; }
246
247 /**
248 * Returns the rotation vector representation of this quaternion.
249 *
250 * This is also the log operator of SO(3).
251 */
252 constexpr Eigen::Vector3d ToRotationVector() const {
253 // See equation (31) in "Integrating Generic Sensor Fusion Algorithms with
254 // Sound State Representation through Encapsulation of Manifolds"
255 //
256 // https://arxiv.org/pdf/1107.1119.pdf
257
258 double norm = gcem::hypot(m_x, m_y, m_z);
259
260 double scalar;
261 if (norm < 1e-9) {
262 scalar = (2.0 / W() - 2.0 / 3.0 * norm * norm / (W() * W() * W()));
263 } else {
264 if (W() < 0.0) {
265 scalar = 2.0 * gcem::atan2(-norm, -W()) / norm;
266 } else {
267 scalar = 2.0 * gcem::atan2(norm, W()) / norm;
268 }
269 }
270
271 return Eigen::Vector3d{{scalar * m_x, scalar * m_y, scalar * m_z}};
272 }
273
274 /**
275 * Returns the quaternion representation of this rotation vector.
276 *
277 * This is also the exp operator of 𝖘𝖔(3).
278 *
279 * source: wpimath/algorithms.md
280 */
281 constexpr static Quaternion FromRotationVector(const Eigen::Vector3d& rvec) {
282 // 𝑣⃗ = θ * v̂
283 // v̂ = 𝑣⃗ / θ
284
285 // 𝑞 = cos(θ/2) + sin(θ/2) * v̂
286 // 𝑞 = cos(θ/2) + sin(θ/2) / θ * 𝑣⃗
287
288 double theta = gcem::hypot(rvec(0), rvec(1), rvec(2));
289 double cos = gcem::cos(theta / 2);
290
291 double axial_scalar;
292
293 if (theta < 1e-9) {
294 // taylor series expansion of sin(θ/2) / θ around θ = 0 = 1/2 - θ²/48 +
295 // O(θ⁴)
296 axial_scalar = 1.0 / 2.0 - theta * theta / 48.0;
297 } else {
298 axial_scalar = gcem::sin(theta / 2) / theta;
299 }
300
301 return Quaternion{cos, axial_scalar * rvec(0), axial_scalar * rvec(1),
302 axial_scalar * rvec(2)};
303 }
304
305 private:
306 // Scalar r in versor form
307 double m_w = 1.0;
308
309 // Vector v in versor form
310 double m_x = 0.0;
311 double m_y = 0.0;
312 double m_z = 0.0;
313};
314
316void to_json(wpi::util::json& json, const Quaternion& quaternion);
317
319void from_json(const wpi::util::json& json, Quaternion& quaternion);
320
321} // namespace wpi::math
322
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a quaternion.
Definition Quaternion.hpp:23
constexpr double W() const
Returns W component of the quaternion.
Definition Quaternion.hpp:230
constexpr Quaternion Inverse() const
Returns the inverse of the quaternion.
Definition Quaternion.hpp:134
constexpr Quaternion operator-(const Quaternion &other) const
Subtracts another quaternion.
Definition Quaternion.hpp:56
constexpr Quaternion operator/(double other) const
Divides by a scalar value.
Definition Quaternion.hpp:75
constexpr double Dot(const Quaternion &other) const
Returns the elementwise product of two quaternions.
Definition Quaternion.hpp:119
constexpr Quaternion operator+(const Quaternion &other) const
Adds with another quaternion.
Definition Quaternion.hpp:46
constexpr Quaternion Normalize() const
Normalizes the quaternion.
Definition Quaternion.hpp:142
constexpr Quaternion(double w, double x, double y, double z)
Constructs a quaternion with the given components.
Definition Quaternion.hpp:38
constexpr Quaternion Exp() const
Matrix exponential of a quaternion.
Definition Quaternion.hpp:171
constexpr Quaternion operator*(const Quaternion &other) const
Multiply with another quaternion.
Definition Quaternion.hpp:84
constexpr bool operator==(const Quaternion &other) const
Checks equality between this Quaternion and another object.
Definition Quaternion.hpp:111
constexpr double X() const
Returns X component of the quaternion.
Definition Quaternion.hpp:235
constexpr Eigen::Vector3d ToRotationVector() const
Returns the rotation vector representation of this quaternion.
Definition Quaternion.hpp:252
constexpr double Z() const
Returns Z component of the quaternion.
Definition Quaternion.hpp:245
constexpr Quaternion Pow(double t) const
Calculates this quaternion raised to a power.
Definition Quaternion.hpp:161
constexpr Quaternion Log() const
Log operator of a quaternion.
Definition Quaternion.hpp:201
constexpr Quaternion()=default
Constructs a quaternion with a default angle of 0 degrees.
static constexpr Quaternion FromRotationVector(const Eigen::Vector3d &rvec)
Returns the quaternion representation of this rotation vector.
Definition Quaternion.hpp:281
constexpr Quaternion Conjugate() const
Returns the conjugate of the quaternion.
Definition Quaternion.hpp:127
constexpr Quaternion operator*(double other) const
Multiples with a scalar value.
Definition Quaternion.hpp:66
constexpr double Y() const
Returns Y component of the quaternion.
Definition Quaternion.hpp:240
constexpr double Norm() const
Calculates the L2 norm of the quaternion.
Definition Quaternion.hpp:154
Definition json.hpp:85
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
constexpr return_t< T > log(const T x) noexcept
Compile-time natural logarithm function.
Definition log.hpp:186
constexpr return_t< T > cos(const T x) noexcept
Compile-time cosine function.
Definition cos.hpp:83
constexpr return_t< T > sin(const T x) noexcept
Compile-time sine function.
Definition sin.hpp:85
constexpr common_return_t< T1, T2 > hypot(const T1 x, const T2 y) noexcept
Compile-time Pythagorean addition function.
Definition hypot.hpp:147
constexpr return_t< T > sqrt(const T x) noexcept
Compile-time square-root function.
Definition sqrt.hpp:109
constexpr return_t< T > exp(const T x) noexcept
Compile-time exponential function.
Definition exp.hpp:130
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 LinearSystem.hpp:20
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