Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 1 | #include "absl/flags/declare.h" |
| 2 | #include "absl/flags/flag.h" |
| 3 | |
James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 4 | #include "frc971/imu/imu_calibrator.h" |
| 5 | #include "frc971/math/interpolate.h" |
| 6 | |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 7 | ABSL_DECLARE_FLAG(int32_t, imu_zeroing_buffer); |
James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 8 | |
| 9 | namespace frc971::imu { |
| 10 | |
| 11 | inline constexpr double kGravityGs = 1.0; |
| 12 | // rad / sec |
| 13 | inline constexpr double kGyroMaxZeroingValue = 0.1; |
| 14 | |
| 15 | template <typename Scalar> |
| 16 | void ImuCalibrator<Scalar>::InsertImu(size_t imu_index, |
| 17 | const RawImuReading &reading) { |
| 18 | CHECK_LT(imu_index, imu_readings_.size()); |
| 19 | std::vector<ImuReading> &readings = imu_readings_[imu_index]; |
| 20 | if (readings.size() > 0u) { |
| 21 | CHECK_LT(readings.back().capture_time_raw, reading.capture_time) |
| 22 | << ": Readings must be inserted in time order per IMU."; |
| 23 | } |
| 24 | // Execute the stationary logic. We identify if this reading is plausibly |
| 25 | // stationary, then if it is not stationary, we go back in time to any |
| 26 | // potentially relevant readings and mark them as not stationary. Finally, we |
| 27 | // go through and as values exit the FLAGS_imu_zeroing_buffer window we do any |
| 28 | // processing that we can given that we know it must be stationary. |
| 29 | const bool plausibly_stationary = |
| 30 | reading.gyro.squaredNorm() < kGyroMaxZeroingValue * kGyroMaxZeroingValue; |
| 31 | bool stationary = plausibly_stationary; |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 32 | int earliest_affected_index = |
| 33 | readings.size() - absl::GetFlag(FLAGS_imu_zeroing_buffer); |
James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 34 | for (size_t index = std::max(0, earliest_affected_index); |
| 35 | index < readings.size(); ++index) { |
| 36 | if (!plausibly_stationary) { |
| 37 | readings[index].stationary = false; |
| 38 | } |
| 39 | if (!readings[index].plausibly_stationary) { |
| 40 | stationary = false; |
| 41 | } |
| 42 | } |
| 43 | |
| 44 | // Since we don't have data from before the start, assume that we may have |
| 45 | // been moving. |
| 46 | if (earliest_affected_index < 0) { |
| 47 | stationary = false; |
| 48 | } |
| 49 | |
| 50 | if (earliest_affected_index >= 0) { |
| 51 | ImuReading &earliest_reading = readings[earliest_affected_index]; |
| 52 | // The stationary flag for this reading can no longer change, so we can |
| 53 | // start to do things based on it. |
| 54 | earliest_reading.stationary_is_locked = true; |
| 55 | if (earliest_reading.stationary) { |
| 56 | earliest_reading.parameter_residuals.gravity = |
| 57 | earliest_reading.accel.norm() - kGravityGs; |
| 58 | earliest_reading.parameter_residuals.gyro_zero = earliest_reading.gyro; |
| 59 | LOG(INFO) << earliest_reading.gyro.transpose(); |
| 60 | } |
| 61 | } |
| 62 | |
| 63 | const ImuConfig<Scalar> &config = imu_configs_[imu_index]; |
| 64 | Scalar capture_time_adjusted = |
| 65 | static_cast<Scalar>(aos::time::DurationInSeconds( |
| 66 | reading.capture_time.time_since_epoch())) - |
| 67 | (config.parameters.has_value() ? config.parameters->time_offset |
| 68 | : static_cast<Scalar>(0.0)); |
| 69 | |
| 70 | imu_readings_[imu_index].emplace_back( |
| 71 | reading.capture_time, capture_time_adjusted, |
| 72 | reading.gyro - config.dynamic_params.gyro_zero, |
| 73 | reading.accel / config.dynamic_params.gravity, |
| 74 | DynamicImuParameters<Scalar>{static_cast<Scalar>(0.0), |
| 75 | Eigen::Matrix<Scalar, 3, 1>::Zero()}, |
| 76 | plausibly_stationary, stationary, false, std::nullopt, std::nullopt); |
| 77 | } |
| 78 | |
| 79 | template <typename Scalar> |
| 80 | void ImuCalibrator<Scalar>::EvaluateRelativeResiduals() { |
| 81 | for (const auto &readings : imu_readings_) { |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 82 | CHECK_LT(static_cast<size_t>(absl::GetFlag(FLAGS_imu_zeroing_buffer) * 2), |
| 83 | readings.size()) |
James Kuszmaul | a60aee1 | 2024-02-02 22:57:47 -0800 | [diff] [blame] | 84 | << ": Insufficient readings to perform calibration."; |
| 85 | } |
| 86 | Scalar base_clock = imu_readings_[origin_index_][0].capture_time_adjusted; |
| 87 | // Current index corresponding to the base_clock time. |
| 88 | std::vector<size_t> reading_indices(imu_configs_.size(), 0); |
| 89 | // The for loops are set up so that we: |
| 90 | // 1. Iterate over every pair of readings from the origin/base IMU. |
| 91 | // 2. For each other IMU, we identify 0 or 1 readings that fall between those |
| 92 | // two readings of the origin IMU. We then calculate the residuals for |
| 93 | // that IMU relative to the origin IMU, linearly interpolating between |
| 94 | // the pair of readings from (1) (by doing a linear interpolation, we can |
| 95 | // get sub-cycle accuracy on time offsets). |
| 96 | for (; |
| 97 | reading_indices[origin_index_] < imu_readings_[origin_index_].size() - 1; |
| 98 | ++reading_indices[origin_index_]) { |
| 99 | const ImuReading &base_reading = |
| 100 | imu_readings_[origin_index_][reading_indices[origin_index_]]; |
| 101 | const ImuReading &next_base_reading = |
| 102 | imu_readings_[origin_index_][reading_indices[origin_index_] + 1]; |
| 103 | base_clock = base_reading.capture_time_adjusted; |
| 104 | const Scalar next_base_clock = next_base_reading.capture_time_adjusted; |
| 105 | for (size_t imu_index = 0; imu_index < imu_configs_.size(); ++imu_index) { |
| 106 | const ImuConfig<Scalar> &imu_config = imu_configs_[imu_index]; |
| 107 | // We don't care about calculating the offsets from the origin IMU to |
| 108 | // itself... |
| 109 | if (imu_config.is_origin) { |
| 110 | continue; |
| 111 | } |
| 112 | auto &readings = imu_readings_[imu_index]; |
| 113 | bool done_with_imu = false; |
| 114 | // This will put the index for the current IMU just past the base_clock |
| 115 | // timepoint, allowing us to interpolate between |
| 116 | // reading_indices[origin_index_] and reading_indices[origin_index_] + 1. |
| 117 | while (readings[reading_indices[imu_index]].capture_time_adjusted < |
| 118 | base_clock) { |
| 119 | if (reading_indices[imu_index] == imu_readings_[imu_index].size() - 1) { |
| 120 | done_with_imu = true; |
| 121 | break; |
| 122 | } |
| 123 | ++reading_indices[imu_index]; |
| 124 | } |
| 125 | // If we've run out of readings on this imu, stop doing anything. |
| 126 | if (done_with_imu) { |
| 127 | continue; |
| 128 | } |
| 129 | ImuReading &reading = readings[reading_indices[imu_index]]; |
| 130 | const Scalar reading_time = reading.capture_time_adjusted; |
| 131 | if (reading_time >= next_base_clock) { |
| 132 | // There is a gap in readings for this imu; we can't meaningfully |
| 133 | // populate the residuals. |
| 134 | continue; |
| 135 | } |
| 136 | // Sanity check the above logic. |
| 137 | CHECK_LE(base_clock, reading_time); |
| 138 | CHECK_LT(reading_time, next_base_clock); |
| 139 | CHECK(imu_config.parameters.has_value()); |
| 140 | reading.gyro_residual = |
| 141 | imu_config.parameters.value().rotation * reading.gyro - |
| 142 | frc971::math::Interpolate<Eigen::Matrix<Scalar, 3, 1>, Scalar>( |
| 143 | base_clock, next_base_clock, base_reading.gyro, |
| 144 | next_base_reading.gyro, reading_time); |
| 145 | if (!reading.stationary_is_locked || !reading.stationary) { |
| 146 | continue; |
| 147 | } |
| 148 | // In order to calculate the accelerometer residual, we are assuming that |
| 149 | // the two IMUs "should" produce identical accelerations. This is only |
| 150 | // true when not rotating. Future changes may account for coriolis |
| 151 | // effects. |
| 152 | reading.accel_residual = |
| 153 | imu_config.parameters.value().rotation * reading.accel - |
| 154 | frc971::math::Interpolate(base_clock, next_base_clock, |
| 155 | base_reading.accel, next_base_reading.accel, |
| 156 | reading_time); |
| 157 | } |
| 158 | } |
| 159 | } |
| 160 | |
| 161 | // Helpers to accommodate serializing residuals into the ceres buffer. These |
| 162 | // helpers all return a buffer that points to the next value to be populated. |
| 163 | namespace internal { |
| 164 | template <typename Scalar> |
| 165 | std::span<Scalar> SerializeScalar(Scalar value, std::span<Scalar> out) { |
| 166 | DCHECK(!out.empty()); |
| 167 | out[0] = value; |
| 168 | return out.subspan(1); |
| 169 | } |
| 170 | template <typename Scalar, int kSize> |
| 171 | std::span<Scalar> SerializeVector(const Eigen::Matrix<Scalar, kSize, 1> &value, |
| 172 | std::span<Scalar> out) { |
| 173 | DCHECK_LE(static_cast<size_t>(value.size()), out.size()); |
| 174 | for (int index = 0; index < kSize; ++index) { |
| 175 | out[index] = value(index); |
| 176 | } |
| 177 | return out.subspan(kSize); |
| 178 | } |
| 179 | template <typename Scalar> |
| 180 | std::span<Scalar> SerializeParams(const DynamicImuParameters<Scalar> ¶ms, |
| 181 | std::span<Scalar> out) { |
| 182 | return SerializeVector(params.gyro_zero, |
| 183 | SerializeScalar(params.gravity, out)); |
| 184 | } |
| 185 | inline constexpr int kResidualsPerReading = 10u; |
| 186 | } // namespace internal |
| 187 | |
| 188 | template <typename Scalar> |
| 189 | void ImuCalibrator<Scalar>::CalculateResiduals(std::span<Scalar> residuals) { |
| 190 | EvaluateRelativeResiduals(); |
| 191 | for (size_t imu_index = 0; imu_index < imu_configs_.size(); ++imu_index) { |
| 192 | const auto &readings = imu_readings_[imu_index]; |
| 193 | double valid_gyro_reading_count = 0; |
| 194 | double valid_accel_reading_count = 0; |
| 195 | for (size_t reading_index = 0; reading_index < readings.size(); |
| 196 | ++reading_index) { |
| 197 | const auto &reading = readings[reading_index]; |
| 198 | if (reading.gyro_residual.has_value()) { |
| 199 | ++valid_gyro_reading_count; |
| 200 | } |
| 201 | if (reading.accel_residual.has_value()) { |
| 202 | ++valid_accel_reading_count; |
| 203 | } |
| 204 | } |
| 205 | if (!imu_configs_[imu_index].is_origin) { |
| 206 | CHECK_LT(0, valid_gyro_reading_count); |
| 207 | CHECK_LT(0, valid_accel_reading_count); |
| 208 | } else { |
| 209 | valid_gyro_reading_count = readings.size(); |
| 210 | valid_accel_reading_count = readings.size(); |
| 211 | } |
| 212 | // Adjust the residuals of the readings to ensure that the solver doesn't |
| 213 | // cheat by just making it so that the time-offsets are completely |
| 214 | // misaligned and we can say that all the residuals are "zero". |
| 215 | const Scalar gyro_reading_scalar = |
| 216 | static_cast<Scalar>(readings.size() / valid_gyro_reading_count); |
| 217 | const Scalar accel_reading_scalar = |
| 218 | static_cast<Scalar>(readings.size() / valid_accel_reading_count); |
| 219 | for (size_t reading_index = 0; reading_index < readings.size(); |
| 220 | ++reading_index) { |
| 221 | const auto &reading = readings[reading_index]; |
| 222 | const Scalar *const start_residual = residuals.data(); |
| 223 | // 4 residuals (gravity scalar; gyro zeroes) |
| 224 | residuals = |
| 225 | internal::SerializeParams(reading.parameter_residuals, residuals); |
| 226 | const Eigen::Matrix<Scalar, 3, 1> gyro_residual = |
| 227 | reading.gyro_residual.value_or(Eigen::Matrix<Scalar, 3, 1>::Zero()) * |
| 228 | gyro_reading_scalar; |
| 229 | // 3 residuals |
| 230 | residuals = internal::SerializeVector(gyro_residual, residuals); |
| 231 | const Eigen::Matrix<Scalar, 3, 1> accel_residual = |
| 232 | reading.accel_residual.value_or(Eigen::Matrix<Scalar, 3, 1>::Zero()) * |
| 233 | accel_reading_scalar; |
| 234 | // 3 residuals |
| 235 | residuals = internal::SerializeVector(accel_residual, residuals); |
| 236 | CHECK_EQ(internal::kResidualsPerReading, |
| 237 | residuals.data() - start_residual) |
| 238 | << ": Need to update kResidualsPerReading."; |
| 239 | } |
| 240 | } |
| 241 | } |
| 242 | |
| 243 | template <typename Scalar> |
| 244 | size_t ImuCalibrator<Scalar>::CalculateNumResiduals( |
| 245 | const std::vector<size_t> &num_readings) { |
| 246 | size_t num_residuals = 0; |
| 247 | for (const size_t count : num_readings) { |
| 248 | num_residuals += internal::kResidualsPerReading * count; |
| 249 | } |
| 250 | return num_residuals; |
| 251 | } |
| 252 | |
| 253 | } // namespace frc971::imu |