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