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