blob: 63f45077edf5a77b83dd858ae925f9c60183ba58 [file] [log] [blame]
Philipp Schrader790cb542023-07-05 21:06:52 -07001#include "frc971/control_loops/quaternion_utils.h"
Brian Silvermandac0a4b2020-06-23 17:03:09 -07002
3#include <random>
4
Philipp Schrader790cb542023-07-05 21:06:52 -07005#include "Eigen/Dense"
Austin Schuh99f7c6a2024-06-25 22:07:44 -07006#include "absl/log/check.h"
7#include "absl/log/log.h"
Brian Silvermandac0a4b2020-06-23 17:03:09 -07008#include "gtest/gtest.h"
9
Philipp Schrader790cb542023-07-05 21:06:52 -070010#include "aos/testing/random_seed.h"
11#include "frc971/control_loops/jacobian.h"
12#include "frc971/control_loops/runge_kutta.h"
13
Stephan Pleinesf63bde82024-01-13 15:59:33 -080014namespace frc971::controls::testing {
Brian Silvermandac0a4b2020-06-23 17:03:09 -070015
16// Tests that small perturbations around a couple quaternions averaged out
17// return the original quaternion.
18TEST(DownEstimatorTest, QuaternionMean) {
19 Eigen::Matrix<double, 4, 7> vectors;
Jim Ostrowski6d242d52024-04-03 20:39:03 -070020 std::vector<Eigen::Vector4d> quaternion_list;
Brian Silvermandac0a4b2020-06-23 17:03:09 -070021 vectors.col(0) << 0, 0, 0, 1;
22 for (int i = 0; i < 3; ++i) {
23 Eigen::Matrix<double, 4, 1> perturbation;
24 perturbation.setZero();
25 perturbation(i, 0) = 0.1;
26
27 vectors.col(i * 2 + 1) = vectors.col(0) + perturbation;
28 vectors.col(i * 2 + 2) = vectors.col(0) - perturbation;
29 }
30
31 for (int i = 0; i < 7; ++i) {
32 vectors.col(i).normalize();
Jim Ostrowski6d242d52024-04-03 20:39:03 -070033 quaternion_list.push_back(Eigen::Vector4d(vectors.col(i)));
Brian Silvermandac0a4b2020-06-23 17:03:09 -070034 }
35
36 Eigen::Matrix<double, 4, 1> mean = QuaternionMean(vectors);
37
38 for (int i = 0; i < 4; ++i) {
39 EXPECT_NEAR(mean(i, 0), vectors(i, 0), 0.001) << ": Failed on index " << i;
40 }
Jim Ostrowski6d242d52024-04-03 20:39:03 -070041
42 // Test version of code that passes in a vector of quaternions
43 mean = QuaternionMean(quaternion_list);
44
45 for (int i = 0; i < 4; ++i) {
46 EXPECT_NEAR(mean(i, 0), quaternion_list[0](i, 0), 0.001)
47 << ": Failed on index " << i << " with mean = " << mean
48 << " and quat_list = " << quaternion_list[0];
49 }
Brian Silvermandac0a4b2020-06-23 17:03:09 -070050}
51
52// Tests that ToRotationVectorFromQuaternion works for a 0 rotation.
53TEST(DownEstimatorTest, ToRotationVectorFromQuaternionAtZero) {
54 Eigen::Matrix<double, 3, 1> vector = ToRotationVectorFromQuaternion(
55 Eigen::Quaternion<double>(
56 Eigen::AngleAxis<double>(0.0, Eigen::Vector3d::UnitX()))
57 .coeffs());
58
59 EXPECT_NEAR(0.0, (vector - Eigen::Vector3d::Zero()).norm(), 1e-4);
60}
61
62// Tests that ToRotationVectorFromQuaternion works for a real rotation.
63TEST(DownEstimatorTest, ToRotationVectorFromQuaternion) {
64 Eigen::Matrix<double, 3, 1> vector = ToRotationVectorFromQuaternion(
65 Eigen::Quaternion<double>(
66 Eigen::AngleAxis<double>(M_PI * 0.5, Eigen::Vector3d::UnitX()))
67 .coeffs());
68
69 EXPECT_NEAR(0.0, (vector - Eigen::Vector3d::UnitX() * M_PI * 0.5).norm(),
70 1e-4);
71}
72
73// Tests that ToRotationVectorFromQuaternion works for a solution with negative
74// coefficients.
75TEST(DownEstimatorTest, ToRotationVectorFromQuaternionNegative) {
76 Eigen::Matrix<double, 3, 1> vector = ToRotationVectorFromQuaternion(
77 Eigen::Quaternion<double>(
78 -Eigen::Quaternion<double>(
79 Eigen::AngleAxis<double>(M_PI * 0.5, Eigen::Vector3d::UnitX()))
80 .coeffs())
81 .coeffs());
82
83 EXPECT_NEAR(0.0, (vector - Eigen::Vector3d::UnitX() * M_PI * 0.5).norm(),
84 1e-4);
85}
86
87// Tests that ToQuaternionFromRotationVector works for a 0 rotation.
88TEST(DownEstimatorTest, ToQuaternionFromRotationVectorAtZero) {
89 Eigen::Matrix<double, 4, 1> quaternion =
90 ToQuaternionFromRotationVector(Eigen::Vector3d::Zero());
91
92 EXPECT_NEAR(
93 0.0,
94 (quaternion - Eigen::Quaternion<double>(
95 Eigen::AngleAxis<double>(0.0, Eigen::Vector3d::UnitX()))
96 .coeffs())
97 .norm(),
98 1e-4);
99}
100
101// Tests that ToQuaternionFromRotationVector works for a real rotation.
102TEST(DownEstimatorTest, ToQuaternionFromRotationVector) {
103 Eigen::Matrix<double, 4, 1> quaternion =
104 ToQuaternionFromRotationVector(Eigen::Vector3d::UnitX() * M_PI * 0.5);
105
106 EXPECT_NEAR(0.0,
107 (quaternion - Eigen::Quaternion<double>(
108 Eigen::AngleAxis<double>(
109 M_PI * 0.5, Eigen::Vector3d::UnitX()))
110 .coeffs())
111
112 .norm(),
113 1e-4);
114}
115
116// Tests that ToQuaternionFromRotationVector correctly clips a rotation vector
117// that is too large in magnitude.
118TEST(DownEstimatorTest, ToQuaternionFromLargeRotationVector) {
119 const double kMaxAngle = 2.0;
120 const Eigen::Vector3d rotation_vector =
121 Eigen::Vector3d::UnitX() * kMaxAngle * 2.0;
122 const Eigen::Matrix<double, 3, 1> clipped_vector =
123 ToRotationVectorFromQuaternion(
124 ToQuaternionFromRotationVector(rotation_vector, kMaxAngle));
125
126 EXPECT_NEAR(0.0, (rotation_vector / 2.0 - clipped_vector).norm(), 1e-4);
127}
128
129// Tests that ToQuaternionFromRotationVector and ToRotationVectorFromQuaternion
130// works for random rotations.
131TEST(DownEstimatorTest, RandomQuaternions) {
132 std::mt19937 generator(aos::testing::RandomSeed());
133 std::uniform_real_distribution<double> random_scalar(-1.0, 1.0);
134
135 for (int i = 0; i < 1000; ++i) {
136 Eigen::Matrix<double, 3, 1> axis;
137 axis << random_scalar(generator), random_scalar(generator),
138 random_scalar(generator);
139 EXPECT_GE(axis.norm(), 1e-6);
140 axis.normalize();
141
142 const double angle = random_scalar(generator) * M_PI;
143
144 Eigen::Matrix<double, 4, 1> quaternion =
145 ToQuaternionFromRotationVector(axis * angle);
146
147 Eigen::Quaternion<double> answer(Eigen::AngleAxis<double>(angle, axis));
148
149 EXPECT_NEAR(quaternion(3, 0), std::cos(angle / 2.0), 1e-8);
150 EXPECT_NEAR(answer.w(), std::cos(angle / 2.0), 1e-8);
151
152 EXPECT_NEAR(1.0, (answer.coeffs() * quaternion.transpose()).norm(), 1e-6);
153
154 const Eigen::Matrix<double, 3, 1> recalculated_axis =
155 ToRotationVectorFromQuaternion(quaternion);
156
157 EXPECT_NEAR(std::abs(angle), recalculated_axis.norm(), 1e-8);
158
159 EXPECT_NEAR(0.0, (axis * angle - recalculated_axis).norm(), 1e-8);
160 }
161}
162
milind-ue53bf552021-12-11 14:42:00 -0800163// Do a known transformation to see if quaternion integration is working
164// correctly.
165TEST(DownEstimatorTest, QuaternionIntegral) {
166 Eigen::Vector3d ux = Eigen::Vector3d::UnitX();
167 Eigen::Vector3d uy = Eigen::Vector3d::UnitY();
168 Eigen::Vector3d uz = Eigen::Vector3d::UnitZ();
169
170 Eigen::Quaternion<double> q(
171 Eigen::AngleAxis<double>(0.5 * M_PI, Eigen::Vector3d::UnitY()));
172
173 Eigen::Quaternion<double> q0(
174 Eigen::AngleAxis<double>(0, Eigen::Vector3d::UnitY()));
175
176 auto qux = q * ux;
177
178 VLOG(1) << "Q is w: " << q.w() << " vec: " << q.vec();
179 VLOG(1) << "ux is " << ux;
180 VLOG(1) << "qux is " << qux;
181
182 // Start by rotating around the X body vector for pi/2
183 Eigen::Quaternion<double> integral1(control_loops::RungeKutta(
184 std::bind(&QuaternionDerivative, ux, std::placeholders::_1), q0.coeffs(),
185 0.5 * M_PI));
186
187 VLOG(1) << "integral1 * uz => " << integral1 * uz;
188
189 // Then rotate around the Y body vector for pi/2
190 Eigen::Quaternion<double> integral2(control_loops::RungeKutta(
191 std::bind(&QuaternionDerivative, uy, std::placeholders::_1),
192 integral1.normalized().coeffs(), 0.5 * M_PI));
193
194 VLOG(1) << "integral2 * uz => " << integral2 * uz;
195
196 // Then rotate around the X body vector for -pi/2
197 Eigen::Quaternion<double> integral3(control_loops::RungeKutta(
198 std::bind(&QuaternionDerivative, -ux, std::placeholders::_1),
199 integral2.normalized().coeffs(), 0.5 * M_PI));
200
201 integral1.normalize();
202 integral2.normalize();
203 integral3.normalize();
204
205 VLOG(1) << "Integral is w: " << integral1.w() << " vec: " << integral1.vec()
206 << " norm " << integral1.norm();
207
208 VLOG(1) << "Integral is w: " << integral3.w() << " vec: " << integral3.vec()
209 << " norm " << integral3.norm();
210
211 VLOG(1) << "ux => " << integral3 * ux;
212 EXPECT_NEAR(0.0, (ux - integral1 * ux).norm(), 5e-2);
213 EXPECT_NEAR(0.0, (uz - integral1 * uy).norm(), 5e-2);
214 EXPECT_NEAR(0.0, (-uy - integral1 * uz).norm(), 5e-2);
215
216 EXPECT_NEAR(0.0, (uy - integral2 * ux).norm(), 5e-2);
217 EXPECT_NEAR(0.0, (uz - integral2 * uy).norm(), 5e-2);
218 EXPECT_NEAR(0.0, (ux - integral2 * uz).norm(), 5e-2);
219
220 EXPECT_NEAR(0.0, (uy - integral3 * ux).norm(), 5e-2);
221 EXPECT_NEAR(0.0, (-ux - integral3 * uy).norm(), 5e-2);
222 EXPECT_NEAR(0.0, (uz - integral3 * uz).norm(), 5e-2);
223}
224
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800225} // namespace frc971::controls::testing