Brian Silverman | dac0a4b | 2020-06-23 17:03:09 -0700 | [diff] [blame^] | 1 | #include "Eigen/Dense" |
| 2 | |
| 3 | #include <random> |
| 4 | |
| 5 | #include "aos/controls/quaternion_utils.h" |
| 6 | #include "aos/testing/random_seed.h" |
| 7 | #include "glog/logging.h" |
| 8 | #include "gtest/gtest.h" |
| 9 | |
| 10 | namespace aos { |
| 11 | namespace controls { |
| 12 | namespace testing { |
| 13 | |
| 14 | // Tests that small perturbations around a couple quaternions averaged out |
| 15 | // return the original quaternion. |
| 16 | TEST(DownEstimatorTest, QuaternionMean) { |
| 17 | Eigen::Matrix<double, 4, 7> vectors; |
| 18 | vectors.col(0) << 0, 0, 0, 1; |
| 19 | for (int i = 0; i < 3; ++i) { |
| 20 | Eigen::Matrix<double, 4, 1> perturbation; |
| 21 | perturbation.setZero(); |
| 22 | perturbation(i, 0) = 0.1; |
| 23 | |
| 24 | vectors.col(i * 2 + 1) = vectors.col(0) + perturbation; |
| 25 | vectors.col(i * 2 + 2) = vectors.col(0) - perturbation; |
| 26 | } |
| 27 | |
| 28 | for (int i = 0; i < 7; ++i) { |
| 29 | vectors.col(i).normalize(); |
| 30 | } |
| 31 | |
| 32 | Eigen::Matrix<double, 4, 1> mean = QuaternionMean(vectors); |
| 33 | |
| 34 | for (int i = 0; i < 4; ++i) { |
| 35 | EXPECT_NEAR(mean(i, 0), vectors(i, 0), 0.001) << ": Failed on index " << i; |
| 36 | } |
| 37 | } |
| 38 | |
| 39 | // Tests that ToRotationVectorFromQuaternion works for a 0 rotation. |
| 40 | TEST(DownEstimatorTest, ToRotationVectorFromQuaternionAtZero) { |
| 41 | Eigen::Matrix<double, 3, 1> vector = ToRotationVectorFromQuaternion( |
| 42 | Eigen::Quaternion<double>( |
| 43 | Eigen::AngleAxis<double>(0.0, Eigen::Vector3d::UnitX())) |
| 44 | .coeffs()); |
| 45 | |
| 46 | EXPECT_NEAR(0.0, (vector - Eigen::Vector3d::Zero()).norm(), 1e-4); |
| 47 | } |
| 48 | |
| 49 | // Tests that ToRotationVectorFromQuaternion works for a real rotation. |
| 50 | TEST(DownEstimatorTest, ToRotationVectorFromQuaternion) { |
| 51 | Eigen::Matrix<double, 3, 1> vector = ToRotationVectorFromQuaternion( |
| 52 | Eigen::Quaternion<double>( |
| 53 | Eigen::AngleAxis<double>(M_PI * 0.5, Eigen::Vector3d::UnitX())) |
| 54 | .coeffs()); |
| 55 | |
| 56 | EXPECT_NEAR(0.0, (vector - Eigen::Vector3d::UnitX() * M_PI * 0.5).norm(), |
| 57 | 1e-4); |
| 58 | } |
| 59 | |
| 60 | // Tests that ToRotationVectorFromQuaternion works for a solution with negative |
| 61 | // coefficients. |
| 62 | TEST(DownEstimatorTest, ToRotationVectorFromQuaternionNegative) { |
| 63 | Eigen::Matrix<double, 3, 1> vector = ToRotationVectorFromQuaternion( |
| 64 | Eigen::Quaternion<double>( |
| 65 | -Eigen::Quaternion<double>( |
| 66 | Eigen::AngleAxis<double>(M_PI * 0.5, Eigen::Vector3d::UnitX())) |
| 67 | .coeffs()) |
| 68 | .coeffs()); |
| 69 | |
| 70 | EXPECT_NEAR(0.0, (vector - Eigen::Vector3d::UnitX() * M_PI * 0.5).norm(), |
| 71 | 1e-4); |
| 72 | } |
| 73 | |
| 74 | // Tests that ToQuaternionFromRotationVector works for a 0 rotation. |
| 75 | TEST(DownEstimatorTest, ToQuaternionFromRotationVectorAtZero) { |
| 76 | Eigen::Matrix<double, 4, 1> quaternion = |
| 77 | ToQuaternionFromRotationVector(Eigen::Vector3d::Zero()); |
| 78 | |
| 79 | EXPECT_NEAR( |
| 80 | 0.0, |
| 81 | (quaternion - Eigen::Quaternion<double>( |
| 82 | Eigen::AngleAxis<double>(0.0, Eigen::Vector3d::UnitX())) |
| 83 | .coeffs()) |
| 84 | .norm(), |
| 85 | 1e-4); |
| 86 | } |
| 87 | |
| 88 | // Tests that ToQuaternionFromRotationVector works for a real rotation. |
| 89 | TEST(DownEstimatorTest, ToQuaternionFromRotationVector) { |
| 90 | Eigen::Matrix<double, 4, 1> quaternion = |
| 91 | ToQuaternionFromRotationVector(Eigen::Vector3d::UnitX() * M_PI * 0.5); |
| 92 | |
| 93 | EXPECT_NEAR(0.0, |
| 94 | (quaternion - Eigen::Quaternion<double>( |
| 95 | Eigen::AngleAxis<double>( |
| 96 | M_PI * 0.5, Eigen::Vector3d::UnitX())) |
| 97 | .coeffs()) |
| 98 | |
| 99 | .norm(), |
| 100 | 1e-4); |
| 101 | } |
| 102 | |
| 103 | // Tests that ToQuaternionFromRotationVector correctly clips a rotation vector |
| 104 | // that is too large in magnitude. |
| 105 | TEST(DownEstimatorTest, ToQuaternionFromLargeRotationVector) { |
| 106 | const double kMaxAngle = 2.0; |
| 107 | const Eigen::Vector3d rotation_vector = |
| 108 | Eigen::Vector3d::UnitX() * kMaxAngle * 2.0; |
| 109 | const Eigen::Matrix<double, 3, 1> clipped_vector = |
| 110 | ToRotationVectorFromQuaternion( |
| 111 | ToQuaternionFromRotationVector(rotation_vector, kMaxAngle)); |
| 112 | |
| 113 | EXPECT_NEAR(0.0, (rotation_vector / 2.0 - clipped_vector).norm(), 1e-4); |
| 114 | } |
| 115 | |
| 116 | // Tests that ToQuaternionFromRotationVector and ToRotationVectorFromQuaternion |
| 117 | // works for random rotations. |
| 118 | TEST(DownEstimatorTest, RandomQuaternions) { |
| 119 | std::mt19937 generator(aos::testing::RandomSeed()); |
| 120 | std::uniform_real_distribution<double> random_scalar(-1.0, 1.0); |
| 121 | |
| 122 | for (int i = 0; i < 1000; ++i) { |
| 123 | Eigen::Matrix<double, 3, 1> axis; |
| 124 | axis << random_scalar(generator), random_scalar(generator), |
| 125 | random_scalar(generator); |
| 126 | EXPECT_GE(axis.norm(), 1e-6); |
| 127 | axis.normalize(); |
| 128 | |
| 129 | const double angle = random_scalar(generator) * M_PI; |
| 130 | |
| 131 | Eigen::Matrix<double, 4, 1> quaternion = |
| 132 | ToQuaternionFromRotationVector(axis * angle); |
| 133 | |
| 134 | Eigen::Quaternion<double> answer(Eigen::AngleAxis<double>(angle, axis)); |
| 135 | |
| 136 | EXPECT_NEAR(quaternion(3, 0), std::cos(angle / 2.0), 1e-8); |
| 137 | EXPECT_NEAR(answer.w(), std::cos(angle / 2.0), 1e-8); |
| 138 | |
| 139 | EXPECT_NEAR(1.0, (answer.coeffs() * quaternion.transpose()).norm(), 1e-6); |
| 140 | |
| 141 | const Eigen::Matrix<double, 3, 1> recalculated_axis = |
| 142 | ToRotationVectorFromQuaternion(quaternion); |
| 143 | |
| 144 | EXPECT_NEAR(std::abs(angle), recalculated_axis.norm(), 1e-8); |
| 145 | |
| 146 | EXPECT_NEAR(0.0, (axis * angle - recalculated_axis).norm(), 1e-8); |
| 147 | } |
| 148 | } |
| 149 | |
| 150 | } // namespace testing |
| 151 | } // namespace controls |
| 152 | } // namespace aos |