James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 1 | #include "frc971/imu/imu_calibrator.h" |
| 2 | |
| 3 | #include <random> |
| 4 | |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame^] | 5 | #include "absl/flags/reflection.h" |
James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 6 | #include "gtest/gtest.h" |
| 7 | |
| 8 | #include "frc971/imu/imu_calibrator_solver.h" |
| 9 | |
| 10 | namespace frc971::imu::testing { |
| 11 | class ImuSimulator { |
| 12 | public: |
| 13 | ImuSimulator(const std::vector<ImuConfig<double>> &imu_configs) |
| 14 | : imu_configs_(imu_configs), readings_(imu_configs.size()) {} |
| 15 | void SimulateForTime(aos::monotonic_clock::duration duration, |
| 16 | aos::monotonic_clock::duration dt, |
| 17 | const Eigen::Vector3d &gravity_vector, |
| 18 | const Eigen::Vector3d &accel, |
| 19 | const Eigen::Vector3d &gyro) { |
| 20 | for (const aos::monotonic_clock::time_point end_time = now + duration; |
| 21 | now < end_time; now += dt) { |
| 22 | for (size_t imu_index = 0; imu_index < imu_configs_.size(); ++imu_index) { |
| 23 | const ImuConfig<double> &config = imu_configs_[imu_index]; |
| 24 | const Eigen::Quaterniond rotation = |
| 25 | config.is_origin ? Eigen::Quaterniond::Identity() |
| 26 | : config.parameters->rotation.inverse(); |
| 27 | const std::chrono::nanoseconds time_offset{ |
| 28 | config.is_origin |
| 29 | ? 0 |
| 30 | : static_cast<uint64_t>(config.parameters->time_offset * 1e9)}; |
| 31 | readings_[imu_index].emplace_back( |
| 32 | now + time_offset, |
| 33 | rotation * gyro + config.dynamic_params.gyro_zero + GyroNoise(), |
| 34 | rotation * |
| 35 | (accel + gravity_vector * config.dynamic_params.gravity) + |
| 36 | AccelNoise()); |
| 37 | } |
| 38 | } |
| 39 | } |
| 40 | Eigen::Vector3d GyroNoise() { |
| 41 | return (enable_noise_ ? 1.0 : 0.0) * |
| 42 | Eigen::Vector3d(distribution_(generator_), distribution_(generator_), |
| 43 | distribution_(generator_)); |
| 44 | } |
| 45 | Eigen::Vector3d AccelNoise() { return GyroNoise() * 2.0; } |
| 46 | void set_enable_noise(bool enable) { enable_noise_ = enable; } |
| 47 | std::vector<std::vector<RawImuReading>> readings() const { |
| 48 | return readings_; |
| 49 | }; |
| 50 | |
| 51 | private: |
| 52 | const std::vector<ImuConfig<double>> imu_configs_; |
| 53 | std::vector<std::vector<RawImuReading>> readings_; |
| 54 | aos::monotonic_clock::time_point now = aos::monotonic_clock::epoch(); |
| 55 | |
| 56 | std::mt19937 generator_; |
| 57 | std::normal_distribution<> distribution_{0.0, 0.00025}; |
| 58 | bool enable_noise_ = false; |
| 59 | }; |
| 60 | |
| 61 | namespace { |
| 62 | void VerifyParameters(const std::vector<ImuConfig<double>> &imus, |
| 63 | const AllParameters<double> ¶ms, double eps = 1e-8) { |
| 64 | ASSERT_EQ(imus.size(), params.imus.size()); |
| 65 | for (size_t imu_index = 0; imu_index < imus.size(); ++imu_index) { |
| 66 | SCOPED_TRACE(imu_index); |
| 67 | const ImuConfig<double> &expected = imus[imu_index]; |
| 68 | const ImuConfig<double> &calculated = params.imus[imu_index]; |
| 69 | EXPECT_EQ(expected.parameters.has_value(), |
| 70 | calculated.parameters.has_value()); |
| 71 | EXPECT_NEAR(expected.dynamic_params.gravity, |
| 72 | calculated.dynamic_params.gravity, eps); |
| 73 | EXPECT_LT((expected.dynamic_params.gyro_zero - |
| 74 | calculated.dynamic_params.gyro_zero) |
| 75 | .norm(), |
| 76 | eps) |
| 77 | << expected.dynamic_params.gyro_zero.transpose() << " vs. " |
| 78 | << calculated.dynamic_params.gyro_zero.transpose(); |
| 79 | if (expected.parameters.has_value()) { |
| 80 | EXPECT_NEAR(expected.parameters->time_offset, |
| 81 | calculated.parameters->time_offset, eps); |
| 82 | EXPECT_LT(((expected.parameters->rotation * |
| 83 | calculated.parameters->rotation.inverse()) |
| 84 | .coeffs() - |
| 85 | Eigen::Quaterniond::Identity().coeffs()) |
| 86 | .norm(), |
| 87 | eps) |
| 88 | << expected.parameters->rotation.coeffs().transpose() << " vs. " |
| 89 | << calculated.parameters->rotation.coeffs().transpose(); |
| 90 | } |
| 91 | } |
| 92 | } |
| 93 | } // namespace |
| 94 | |
| 95 | // Confirms that we can calibrate in a relatively simple scenario where we have |
| 96 | // some gyro/accelerometer offsets and a small rotation that is not accounted |
| 97 | // for in the nominal parameters. |
| 98 | TEST(ImuCalibratorTest, BasicCalibrationTest) { |
| 99 | std::vector<ImuConfig<double>> nominal_imus = { |
| 100 | ImuConfig<double>{true, std::nullopt}, |
| 101 | ImuConfig<double>{false, std::make_optional<StaticImuParameters<double>>( |
| 102 | Eigen::Quaterniond::Identity(), 0.0)}}; |
| 103 | |
| 104 | std::vector<ImuConfig<double>> real_imus = nominal_imus; |
| 105 | real_imus[0].dynamic_params.gravity = 1.005; |
| 106 | real_imus[0].dynamic_params.gyro_zero << 0.001, 0.002, 0.003; |
| 107 | real_imus[1].dynamic_params.gyro_zero << -0.009, -0.007, -0.001; |
| 108 | real_imus[1].parameters->rotation = |
| 109 | Eigen::AngleAxisd(0.01, Eigen::Vector3d::UnitZ()); |
| 110 | ImuSimulator simulator(real_imus); |
| 111 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 112 | std::chrono::milliseconds(1), |
| 113 | Eigen::Vector3d(0, 0, 1), Eigen::Vector3d(0, 0, 0), |
| 114 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 115 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 116 | std::chrono::milliseconds(1), |
| 117 | Eigen::Vector3d(0, 1, 0), Eigen::Vector3d(0, 0, 0), |
| 118 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 119 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 120 | std::chrono::milliseconds(1), |
| 121 | Eigen::Vector3d(1, 0, 0), Eigen::Vector3d(0, 0, 0), |
| 122 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 123 | simulator.SimulateForTime( |
| 124 | std::chrono::seconds(1), std::chrono::milliseconds(1), |
| 125 | Eigen::Vector3d(0, 0, 1), Eigen::Vector3d(0.1, 0.2, 0.3), |
| 126 | Eigen::Vector3d(1.0, 0.0, 0.0)); |
| 127 | simulator.SimulateForTime( |
| 128 | std::chrono::seconds(1), std::chrono::milliseconds(1), |
| 129 | Eigen::Vector3d(0, 0, 1), Eigen::Vector3d(0.1, 0.2, 0.3), |
| 130 | Eigen::Vector3d(0.0, 1.0, 0.0)); |
| 131 | auto params = Solve(simulator.readings(), nominal_imus); |
| 132 | LOG(INFO) << params.ToString(); |
| 133 | LOG(INFO) << real_imus[0].ToString(); |
| 134 | LOG(INFO) << real_imus[1].ToString(); |
| 135 | VerifyParameters(real_imus, params); |
| 136 | } |
| 137 | |
| 138 | // Separately test the estimation of the time offset between IMUs. |
| 139 | // This is done separately because the optimization problem is poorly condition |
| 140 | // for estimating time offsets when there is just a handful of step changes in |
| 141 | // the IMU inputs; feeding in a sine wave works much better for allowing the |
| 142 | // solver to estimate the offset. |
| 143 | TEST(ImuCalibratorTest, TimeOffsetTest) { |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame^] | 144 | absl::FlagSaver flag_saver; |
James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 145 | |
| 146 | std::vector<ImuConfig<double>> nominal_imus = { |
| 147 | ImuConfig<double>{true, std::nullopt}, |
| 148 | ImuConfig<double>{false, std::make_optional<StaticImuParameters<double>>( |
| 149 | Eigen::Quaterniond::Identity(), 0.0)}}; |
| 150 | |
| 151 | std::vector<ImuConfig<double>> real_imus = nominal_imus; |
| 152 | real_imus[1].parameters->time_offset = 0.0255; |
| 153 | ImuSimulator simulator(real_imus); |
| 154 | // Note on convergence: It is easy to end up in situations where the problem |
| 155 | // is not outstandingly well conditioned and we can end up with local minima |
| 156 | // where changes to physical calibration attributes can explain the time |
| 157 | // offset. |
| 158 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 159 | std::chrono::milliseconds(1), |
| 160 | Eigen::Vector3d(0, 0, 1), Eigen::Vector3d(0, 0, 0), |
| 161 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 162 | for (size_t ii = 0; ii < 10000; ++ii) { |
| 163 | simulator.SimulateForTime( |
| 164 | std::chrono::milliseconds(1), std::chrono::milliseconds(1), |
| 165 | Eigen::Vector3d(0, 0, 1), Eigen::Vector3d(0.0, 0.0, 0.0), |
| 166 | Eigen::Vector3d(std::sin(ii / 1000.0), 0.0, 0.0)); |
| 167 | } |
| 168 | auto params = Solve(simulator.readings(), nominal_imus); |
| 169 | LOG(INFO) << params.ToString(); |
| 170 | LOG(INFO) << real_imus[0].ToString(); |
| 171 | LOG(INFO) << real_imus[1].ToString(); |
| 172 | VerifyParameters(real_imus, params, 1e-6); |
| 173 | } |
| 174 | |
| 175 | // Test that if we add in some random noise that the solver still behaves |
| 176 | // itself. |
| 177 | TEST(ImuCalibratorTest, RandomNoise) { |
| 178 | std::vector<ImuConfig<double>> nominal_imus = { |
| 179 | ImuConfig<double>{true, std::nullopt}, |
| 180 | ImuConfig<double>{false, std::make_optional<StaticImuParameters<double>>( |
| 181 | Eigen::Quaterniond::Identity(), 0.0)}}; |
| 182 | |
| 183 | std::vector<ImuConfig<double>> real_imus = nominal_imus; |
| 184 | real_imus[0].dynamic_params.gravity = 0.999; |
| 185 | real_imus[0].dynamic_params.gyro_zero << 0.001, 0.002, 0.003; |
| 186 | real_imus[1].dynamic_params.gyro_zero << -0.009, -0.007, -0.001; |
| 187 | real_imus[1].parameters->rotation = |
| 188 | Eigen::AngleAxisd(0.01, Eigen::Vector3d::UnitZ()); |
| 189 | ImuSimulator simulator(real_imus); |
| 190 | simulator.set_enable_noise(true); |
| 191 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 192 | std::chrono::milliseconds(1), |
| 193 | Eigen::Vector3d(0, 0, 1), Eigen::Vector3d(0, 0, 0), |
| 194 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 195 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 196 | std::chrono::milliseconds(1), |
| 197 | Eigen::Vector3d(0, 1, 0), Eigen::Vector3d(0, 0, 0), |
| 198 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 199 | simulator.SimulateForTime(std::chrono::seconds(1), |
| 200 | std::chrono::milliseconds(1), |
| 201 | Eigen::Vector3d(1, 0, 0), Eigen::Vector3d(0, 0, 0), |
| 202 | Eigen::Vector3d(0.0, 0.0, 0.0)); |
| 203 | for (size_t ii = 0; ii < 6000; ++ii) { |
| 204 | simulator.SimulateForTime(std::chrono::milliseconds(1), |
| 205 | std::chrono::milliseconds(1), |
| 206 | Eigen::Vector3d(0, 0, 1), |
| 207 | Eigen::Vector3d(std::sin(ii / 1000.0), 0.0, 0.0), |
| 208 | Eigen::Vector3d(1.0, 0.0, 0.0)); |
| 209 | } |
| 210 | auto params = Solve(simulator.readings(), nominal_imus); |
| 211 | LOG(INFO) << params.ToString(); |
| 212 | LOG(INFO) << real_imus[0].ToString(); |
| 213 | LOG(INFO) << real_imus[1].ToString(); |
| 214 | VerifyParameters(real_imus, params, 1e-4); |
| 215 | } |
| 216 | } // namespace frc971::imu::testing |