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