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