WPILibC++ 2024.3.2
Quaternion.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 <Eigen/Core>
8#include <wpi/SymbolExports.h>
9#include <wpi/json_fwd.h>
10
11namespace frc {
12
13/**
14 * Represents a quaternion.
15 */
17 public:
18 /**
19 * Constructs a quaternion with a default angle of 0 degrees.
20 */
21 Quaternion() = default;
22
23 /**
24 * Constructs a quaternion with the given components.
25 *
26 * @param w W component of the quaternion.
27 * @param x X component of the quaternion.
28 * @param y Y component of the quaternion.
29 * @param z Z component of the quaternion.
30 */
31 Quaternion(double w, double x, double y, double z);
32
33 /**
34 * Adds with another quaternion.
35 *
36 * @param other the other quaternion
37 */
38 Quaternion operator+(const Quaternion& other) const;
39
40 /**
41 * Subtracts another quaternion.
42 *
43 * @param other the other quaternion
44 */
45 Quaternion operator-(const Quaternion& other) const;
46
47 /**
48 * Multiples with a scalar value.
49 *
50 * @param other the scalar value
51 */
52 Quaternion operator*(const double other) const;
53
54 /**
55 * Divides by a scalar value.
56 *
57 * @param other the scalar value
58 */
59 Quaternion operator/(const double other) const;
60
61 /**
62 * Multiply with another quaternion.
63 *
64 * @param other The other quaternion.
65 */
66 Quaternion operator*(const Quaternion& other) const;
67
68 /**
69 * Checks equality between this Quaternion and another object.
70 *
71 * @param other The other object.
72 * @return Whether the two objects are equal.
73 */
74 bool operator==(const Quaternion& other) const;
75
76 /**
77 * Returns the elementwise product of two quaternions.
78 */
79 double Dot(const Quaternion& other) const;
80
81 /**
82 * Returns the conjugate of the quaternion.
83 */
85
86 /**
87 * Returns the inverse of the quaternion.
88 */
90
91 /**
92 * Normalizes the quaternion.
93 */
95
96 /**
97 * Calculates the L2 norm of the quaternion.
98 */
99 double Norm() const;
100
101 /**
102 * Calculates this quaternion raised to a power.
103 *
104 * @param t the power to raise this quaternion to.
105 */
106 Quaternion Pow(const double t) const;
107
108 /**
109 * Matrix exponential of a quaternion.
110 *
111 * @param other the "Twist" that will be applied to this quaternion.
112 */
113 Quaternion Exp(const Quaternion& other) const;
114
115 /**
116 * Matrix exponential of a quaternion.
117 *
118 * source: wpimath/algorithms.md
119 *
120 * If this quaternion is in 𝖘𝖔(3) and you are looking for an element of
121 * SO(3), use FromRotationVector
122 */
124
125 /**
126 * Log operator of a quaternion.
127 *
128 * @param other The quaternion to map this quaternion onto
129 */
130 Quaternion Log(const Quaternion& other) const;
131
132 /**
133 * Log operator of a quaternion.
134 *
135 * source: wpimath/algorithms.md
136 *
137 * If this quaternion is in SO(3) and you are looking for an element of 𝖘𝖔(3),
138 * use ToRotationVector
139 */
141
142 /**
143 * Returns W component of the quaternion.
144 */
145 double W() const;
146
147 /**
148 * Returns X component of the quaternion.
149 */
150 double X() const;
151
152 /**
153 * Returns Y component of the quaternion.
154 */
155 double Y() const;
156
157 /**
158 * Returns Z component of the quaternion.
159 */
160 double Z() const;
161
162 /**
163 * Returns the rotation vector representation of this quaternion.
164 *
165 * This is also the log operator of SO(3).
166 */
167 Eigen::Vector3d ToRotationVector() const;
168
169 /**
170 * Returns the quaternion representation of this rotation vector.
171 *
172 * This is also the exp operator of 𝖘𝖔(3).
173 *
174 * source: wpimath/algorithms.md
175 */
176 static Quaternion FromRotationVector(const Eigen::Vector3d& rvec);
177
178 private:
179 // Scalar r in versor form
180 double m_r = 1.0;
181
182 // Vector v in versor form
183 Eigen::Vector3d m_v{0.0, 0.0, 0.0};
184};
185
187void to_json(wpi::json& json, const Quaternion& quaternion);
188
190void from_json(const wpi::json& json, Quaternion& quaternion);
191
192} // namespace frc
193
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a quaternion.
Definition: Quaternion.h:16
Quaternion()=default
Constructs a quaternion with a default angle of 0 degrees.
Quaternion operator*(const double other) const
Multiples with a scalar value.
bool operator==(const Quaternion &other) const
Checks equality between this Quaternion and another object.
Quaternion operator-(const Quaternion &other) const
Subtracts another quaternion.
double W() const
Returns W component of the quaternion.
Quaternion Exp() const
Matrix exponential of a quaternion.
Quaternion Exp(const Quaternion &other) const
Matrix exponential of a quaternion.
Eigen::Vector3d ToRotationVector() const
Returns the rotation vector representation of this quaternion.
Quaternion Normalize() const
Normalizes the quaternion.
Quaternion operator*(const Quaternion &other) const
Multiply with another quaternion.
double Norm() const
Calculates the L2 norm of the quaternion.
Quaternion operator+(const Quaternion &other) const
Adds with another quaternion.
double Dot(const Quaternion &other) const
Returns the elementwise product of two quaternions.
Quaternion Inverse() const
Returns the inverse of the quaternion.
double Z() const
Returns Z component of the quaternion.
double X() const
Returns X component of the quaternion.
Quaternion Pow(const double t) const
Calculates this quaternion raised to a power.
Quaternion Log() const
Log operator of a quaternion.
double Y() const
Returns Y component of the quaternion.
Quaternion Log(const Quaternion &other) const
Log operator of a quaternion.
Quaternion operator/(const double other) const
Divides by a scalar value.
static Quaternion FromRotationVector(const Eigen::Vector3d &rvec)
Returns the quaternion representation of this rotation vector.
Quaternion(double w, double x, double y, double z)
Constructs a quaternion with the given components.
Quaternion Conjugate() const
Returns the conjugate of the quaternion.
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)