blob: 58ff12b08dd0e69f296d9ebe2fe709dfc9eee07b [file] [log] [blame]
James Kuszmaula60aee12024-02-02 22:57:47 -08001#ifndef FRC971_IMU_IMU_CALIBRATOR_H_
2#define FRC971_IMU_IMU_CALIBRATOR_H_
3
4#include <optional>
5#include <span>
6#include <tuple>
7#include <vector>
8
9#include "absl/strings/str_format.h"
10#include "absl/strings/str_join.h"
11#include "ceres/ceres.h"
12#include "glog/logging.h"
13#include <Eigen/Core>
14#include <Eigen/Geometry>
15
16#include "aos/time/time.h"
17
18namespace frc971::imu {
19
20// Contains a reading that comes directly from an IMU.
21// These should not be zeroed or corrected for yet.
22struct RawImuReading {
23 aos::monotonic_clock::time_point capture_time;
24 // gyro readings are in radians / sec; accelerometer readings are in g's.
25 const Eigen::Vector3d gyro;
26 const Eigen::Vector3d accel;
27};
28
29// Note on how we manage populating ceres parameters:
30// * We use dynamically-sized parameter lists for convenience.
31// * For every struct that we have that corresponds to problem parameters,
32// there is a PopulateParameters() method that takes a:
33// * ceres::Problem* that is used for setting parameter constraints.
34// * ceres::DynamicCostFunction* that is used to mark that we have added
35// a parameter block.
36// * A std::vector<double*> that will later be passed to AddResidualBlock.
37// We add any parameter blocks which we add to the problem.
38// * post_populate_methods is a list of std::function's that will get called
39// after everything is populated and added (this is necessary because
40// we cannot add constraints to the Problem until after everything
41// has been added).
42// * Additionally, there is a PopulateFromParameters() method which is used
43// in the ceres cost functor and:
44// * Takes a parameters double-pointer where parameters[X] is the
45// parameter block X.
46// * Returns a pair where the first value is a populated instance of the
47// struct and an updated parameters pointer which points to the next
48// set of pointers.
49// * All the Populate* methods must be called in the same order every
50// time so that they result in the raw pointers getting populated
51// consistently.
52
53// These are the parameters corresponding to things which will vary at every
54// power-on of the IMU.
55template <typename Scalar>
56struct DynamicImuParameters {
57 // A scalar to represent the current magnitude of gravity, in g's.
58 // This currently compensates both for any variations in local gravity as well
59 // as for some amount of variations in the IMU itself. In the future we may
60 // expand this to have a local gravity number that is global to all IMUs while
61 // separately calibrating per-axis information.
62 Scalar gravity;
63 // Current gyro zero, in radians / sec.
64 // These are the per-axis values that the gyro will read when it is sitting
65 // still. Technically these zeroes will drift over time; however, the
66 // time-windows that we expect to use for calibration are short enough that
67 // this should be a non-issue.
68 Eigen::Matrix<Scalar, 3, 1> gyro_zero;
69 void PopulateParameters(
70 ceres::Problem *problem, ceres::DynamicCostFunction *cost_function,
71 std::vector<double *> *parameters,
72 std::vector<std::function<void()>> *post_populate_methods) {
73 cost_function->AddParameterBlock(1);
74 parameters->push_back(&gravity);
75 cost_function->AddParameterBlock(3);
76 parameters->push_back(gyro_zero.data());
77 post_populate_methods->emplace_back([this, problem]() {
78 // Gravity shouldn't vary by much (these bounds are significantly larger
79 // than any real variations which we will experience).
80 problem->SetParameterLowerBound(&gravity, 0, 0.95);
81 problem->SetParameterUpperBound(&gravity, 0, 1.05);
82 for (int i = 0; i < 3; ++i) {
83 problem->SetParameterLowerBound(gyro_zero.data(), i, -0.05);
84 problem->SetParameterUpperBound(gyro_zero.data(), i, 0.05);
85 }
86 });
87 }
88 static std::tuple<DynamicImuParameters<Scalar>, const Scalar *const *>
89 PopulateFromParameters(const Scalar *const *parameters) {
90 const Scalar *const gravity = parameters[0];
91 ++parameters;
92 const Scalar *const gyro = parameters[0];
93 ++parameters;
94 return std::make_tuple(
95 DynamicImuParameters<Scalar>{
96 *gravity, Eigen::Matrix<Scalar, 3, 1>(gyro[0], gyro[1], gyro[2])},
97 parameters);
98 }
99 std::string ToString() const {
100 std::stringstream out;
101 out << "gravity: " << gravity << " gyro_zero: " << gyro_zero.transpose();
102 return out.str();
103 }
104};
105
106// These parameters correspond to IMU parameters which will not vary between
107// boots. Namely, the relative positions and time offsets of the IMU(s).
108template <typename Scalar>
109struct StaticImuParameters {
110 // If you have a point p_imu in this IMU's frame then (rotation *
111 // p_imu + position) will give you that point's position in the board frame
112 // (the "board" frame refers to the frame associated with the entire PCB,
113 // where the PCB itself contains multiple IMUs. The board frame will be
114 // attached to whichever IMU is being treated as the origin).
115 Eigen::Quaternion<Scalar> rotation;
116 // position is currently unused because it is only observeable when there
117 // are coriolis effects, and we currently only make use of accelerometer
118 // readings from when the IMU is sat still.
119 // As such, we currently assume that all position offsets are zero.
120 // Eigen::Matrix<Scalar, 3, 1> position;
121 // The "true" time at which the event occurred is equal to the capture time -
122 // time_offset. I.e., a more positive time offset implies that the there is a
123 // large delay between the imu readings being taken and us observing them.
124 Scalar time_offset;
125
126 void PopulateParameters(
Austin Schuh31f99a22024-06-25 18:30:13 -0700127 ceres::EigenQuaternionManifold *quaternion_local_parameterization,
James Kuszmaula60aee12024-02-02 22:57:47 -0800128 ceres::Problem *problem, ceres::DynamicCostFunction *cost_function,
129 std::vector<double *> *parameters,
130 std::vector<std::function<void()>> *post_populate_methods) {
131 cost_function->AddParameterBlock(4);
132 parameters->push_back(rotation.coeffs().data());
133 cost_function->AddParameterBlock(1);
134 parameters->push_back(&time_offset);
135 post_populate_methods->emplace_back(
136 [this, problem, quaternion_local_parameterization]() {
Austin Schuh31f99a22024-06-25 18:30:13 -0700137 problem->SetManifold(rotation.coeffs().data(),
138 quaternion_local_parameterization);
James Kuszmaula60aee12024-02-02 22:57:47 -0800139 problem->SetParameterLowerBound(&time_offset, 0, -0.03);
140 problem->SetParameterUpperBound(&time_offset, 0, 0.03);
141 });
142 }
143 static std::tuple<StaticImuParameters, const Scalar *const *>
144 PopulateFromParameters(const Scalar *const *parameters) {
145 const Scalar *const quat = parameters[0];
146 ++parameters;
147 const Scalar *const time = parameters[0];
148 ++parameters;
149 return std::make_tuple(
150 StaticImuParameters{
151 Eigen::Quaternion<Scalar>(quat[3], quat[0], quat[1], quat[2]),
152 *time},
153 parameters);
154 }
155 std::string ToString() const {
156 std::stringstream out;
157 out << "quat: " << rotation.coeffs().transpose()
158 << " time_offset: " << time_offset;
159 return out.str();
160 }
161};
162
163// Represents the calibration for a single IMU.
164template <typename Scalar>
165struct ImuConfig {
166 // Set to true if this IMU is to be considered the origin of the coordinate
167 // system. This will also mean that this IMU is treated as the source-of-truth
168 // for clock offsets.
169 bool is_origin;
170 // Will be nullopt if is_origin is true (the corresponding rotations and
171 // offsets will all be the identity/zero as appropriate).
172 std::optional<StaticImuParameters<Scalar>> parameters;
173
174 DynamicImuParameters<Scalar> dynamic_params{
175 .gravity = static_cast<Scalar>(1.0),
176 .gyro_zero = Eigen::Matrix<Scalar, 3, 1>::Zero()};
177 std::string ToString() const {
178 return absl::StrFormat(
179 "is_origin: %d params: %s dynamic: %s", is_origin,
180 parameters.has_value() ? parameters->ToString() : std::string("<null>"),
181 dynamic_params.ToString());
182 }
183};
184
185// Represents all of the configuration parameters for the entire system.
186template <typename Scalar>
187struct AllParameters {
188 // Each entry in the imus vector will be a single imu.
189 std::vector<ImuConfig<Scalar>> imus;
190 std::tuple<std::vector<double *>, std::vector<std::function<void()>>>
191 PopulateParameters(
Austin Schuh31f99a22024-06-25 18:30:13 -0700192 ceres::EigenQuaternionManifold *quaternion_local_parameterization,
James Kuszmaula60aee12024-02-02 22:57:47 -0800193 ceres::Problem *problem, ceres::DynamicCostFunction *cost_function) {
194 std::vector<std::function<void()>> post_populate_methods;
195 std::vector<double *> parameters;
196 for (auto &imu : imus) {
197 if (imu.parameters.has_value()) {
198 imu.parameters.value().PopulateParameters(
199 quaternion_local_parameterization, problem, cost_function,
200 &parameters, &post_populate_methods);
201 }
202 imu.dynamic_params.PopulateParameters(problem, cost_function, &parameters,
203 &post_populate_methods);
204 }
205 return std::make_tuple(parameters, post_populate_methods);
206 }
207 static AllParameters PopulateFromParameters(
208 const std::vector<ImuConfig<double>> &nominal_configs,
209 const Scalar *const *parameters) {
210 std::vector<ImuConfig<Scalar>> result;
211 for (size_t imu_index = 0; imu_index < nominal_configs.size();
212 ++imu_index) {
213 ImuConfig<Scalar> config;
214 config.is_origin = nominal_configs[imu_index].is_origin;
215 if (!config.is_origin) {
216 std::tie(config.parameters, parameters) =
217 StaticImuParameters<Scalar>::PopulateFromParameters(parameters);
218 }
219 std::tie(config.dynamic_params, parameters) =
220 DynamicImuParameters<Scalar>::PopulateFromParameters(parameters);
221 result.emplace_back(std::move(config));
222 }
223 return {.imus = std::move(result)};
224 }
225 std::string ToString() const {
226 std::vector<std::string> imu_strings;
227 for (const auto &imu : imus) {
228 std::vector<std::string> dynamic_params;
229 imu_strings.push_back(absl::StrFormat("config: %s", imu.ToString()));
230 }
231 return absl::StrJoin(imu_strings, "\n");
232 }
233};
234
235// This class does the hard work to support calibrating multiple IMU's
236// orientations relative to one another. It is set up to readily be used with a
237// ceres solver (see imu_calibrator.*).
238//
239// The current theory of operation is to have some number of imus, one of which
240// we will consider to be fixed in position. We have a fixed set of data that we
241// feed into this class, which can be parameterized based on:
242// * The current zeroes for each IMU.
243// * The orientation of each non-fixed IMU.
244// * The time-offset of each non-fixed IMU.
245//
246// When run under ceres, ceres can then vary these parameters to solve for the
247// current calibrations of the IMUs.
248//
249// When solving, the main complexity is that some internal state has to be
250// tracked to try to determine when we should be calculating zeroes and when we
251// can calibrate out the magnitude of gravity. This is done by tracking when the
252// IMUs are "stationary". For a reading to be stationary, all values with
253// FLAGS_imu_zeroing_buffer readings of the reading must be "plausibly
254// stationary". Readings are plausibly stationary if they have sufficiently low
255// gyro values.
256//
257// TODO: Provide some utilities to plot the results of a calibration.
258template <typename Scalar>
259class ImuCalibrator {
260 public:
261 ImuCalibrator(const std::vector<ImuConfig<Scalar>> &imu_configs)
262 : imu_configs_(imu_configs), imu_readings_(imu_configs.size()) {
263 origin_index_ = -1;
264 for (size_t imu_index = 0; imu_index < imu_configs_.size(); ++imu_index) {
265 if (imu_configs_[imu_index].is_origin) {
266 CHECK_EQ(origin_index_, -1)
267 << ": Can't have more than one IMU specified as the origin.";
268 origin_index_ = imu_index;
269 }
270 }
271 CHECK_NE(origin_index_, -1)
272 << ": Must have at least one IMU specified as the origin.";
273 }
274
275 // These gyro readings will be "raw"---i.e., they still need to get
276 // transformed by nominal_transform.
277 // gyro readings are in radians / sec; accelerometer readings are in g's.
278 // Within a given imu, must be called in time order.
279 void InsertImu(size_t imu_index, const RawImuReading &reading);
280
281 // Populates all the residuals that we use for the cost in ceres.
282 void CalculateResiduals(std::span<Scalar> residuals);
283
284 // Returns the total number of residuals that this problem will have, given
285 // the number of readings for each IMU.
286 static size_t CalculateNumResiduals(const std::vector<size_t> &num_readings);
287
288 private:
289 // Represents an imu reading. The values in this are generally already
290 // adjusted for the provided parameters.
291 struct ImuReading {
292 // The "actual" provided capture time. Used for debugging.
293 aos::monotonic_clock::time_point capture_time_raw;
294 // The capture time, adjusted for this IMU's time offset.
295 Scalar capture_time_adjusted;
296 // gyro reading, adjusted for gyro zero but NOT rotation.
297 // In radians / sec.
298 Eigen::Matrix<Scalar, 3, 1> gyro;
299 // accelerometer reading, adjusted for gravity value but NOT rotation.
300 // In g's.
301 Eigen::Matrix<Scalar, 3, 1> accel;
302 // Residuals associated with the DynamicImuParameters for this imu.
303 DynamicImuParameters<Scalar> parameter_residuals;
304 // Set if this measurement *could* be part of a segment of time where the
305 // IMU is stationary.
306 bool plausibly_stationary;
307 // Set to true if all values with FLAGS_imu_zeroing_buffer of this reading
308 // are plausibly_stationary.
309 bool stationary;
310 // We set stationary_is_locked once we have enough readings to either side
311 // of this value to guarantee that it is stationary.
312 bool stationary_is_locked;
313 // Residuals that are used for calibrating the rotation values. These are
314 // nullopt if we can't calibrate for some reason (e.g., this is the origin
315 // IMU, or for the accelerometer residual, we don't populate it if we are
316 // not stationary).
317 std::optional<Eigen::Matrix<Scalar, 3, 1>> gyro_residual;
318 std::optional<Eigen::Matrix<Scalar, 3, 1>> accel_residual;
319 };
320 void EvaluateRelativeResiduals();
321
322 const std::vector<ImuConfig<Scalar>> imu_configs_;
323 // Index of the IMU which is the origin IMU.
324 int origin_index_;
325 std::vector<std::vector<ImuReading>> imu_readings_;
326};
327
328} // namespace frc971::imu
329
330#include "frc971/imu/imu_calibrator-tmpl.h"
331#endif // FRC971_IMU_IMU_CALIBRATOR_H_