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