blob: 6017258a2eedb92ae83688af5ae4ee39ed85a731 [file] [log] [blame]
Austin Schuhdcb6b362022-02-25 18:06:21 -08001#include "frc971/vision/extrinsics_calibration.h"
2
Austin Schuhdcb6b362022-02-25 18:06:21 -08003#include "ceres/ceres.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08004#include <opencv2/core.hpp>
5#include <opencv2/core/eigen.hpp>
6#include <opencv2/highgui.hpp>
7#include <opencv2/highgui/highgui.hpp>
8#include <opencv2/imgproc.hpp>
Austin Schuhdcb6b362022-02-25 18:06:21 -08009
Philipp Schrader790cb542023-07-05 21:06:52 -070010#include "aos/time/time.h"
11#include "frc971/analysis/in_process_plotter.h"
12#include "frc971/control_loops/runge_kutta.h"
13#include "frc971/vision/calibration_accumulator.h"
14#include "frc971/vision/charuco_lib.h"
15#include "frc971/vision/visualize_robot.h"
16
Stephan Pleinesf63bde82024-01-13 15:59:33 -080017namespace frc971::vision {
Austin Schuhdcb6b362022-02-25 18:06:21 -080018
19namespace chrono = std::chrono;
20using aos::distributed_clock;
21using aos::monotonic_clock;
22
23constexpr double kGravity = 9.8;
24
25// The basic ideas here are taken from Kalibr.
26// (https://github.com/ethz-asl/kalibr), but adapted to work with AOS, and to be
27// simpler.
28//
29// Camera readings and IMU readings come in at different times, on different
30// time scales. Our first problem is to align them in time so we can actually
31// compute an error. This is done in the calibration accumulator code. The
32// kalibr paper uses splines, while this uses kalman filters to solve the same
33// interpolation problem so we can get the expected vs actual pose at the time
34// each image arrives.
35//
36// The cost function is then fed the computed angular and positional error for
37// each camera sample before the kalman filter update. Intuitively, the smaller
38// the corrections to the kalman filter each step, the better the estimate
39// should be.
40//
41// We don't actually implement the angular kalman filter because the IMU is so
42// good. We give the solver an initial position and bias, and let it solve from
43// there. This lets us represent drift that is linear in time, which should be
44// good enough for ~1 minute calibration.
45//
46// TODO(austin): Kalman smoother ala
47// https://stanford.edu/~boyd/papers/pdf/auto_ks.pdf should allow for better
48// parallelism, and since we aren't causal, will take that into account a lot
49// better.
50
51// This class takes the initial parameters and biases, and computes the error
52// between the measured and expected camera readings. When optimized, this
53// gives us a cost function to minimize.
54template <typename Scalar>
55class CeresPoseFilter : public CalibrationDataObserver {
56 public:
57 typedef Eigen::Transform<Scalar, 3, Eigen::Affine> Affine3s;
58
59 CeresPoseFilter(Eigen::Quaternion<Scalar> initial_orientation,
Austin Schuh2895f4c2022-02-26 16:38:46 -080060 Eigen::Quaternion<Scalar> pivot_to_camera,
61 Eigen::Quaternion<Scalar> pivot_to_imu,
Austin Schuhdcb6b362022-02-25 18:06:21 -080062 Eigen::Matrix<Scalar, 3, 1> gyro_bias,
63 Eigen::Matrix<Scalar, 6, 1> initial_state,
64 Eigen::Quaternion<Scalar> board_to_world,
Austin Schuh2895f4c2022-02-26 16:38:46 -080065 Eigen::Matrix<Scalar, 3, 1> pivot_to_camera_translation,
66 Eigen::Matrix<Scalar, 3, 1> pivot_to_imu_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -080067 Scalar gravity_scalar,
68 Eigen::Matrix<Scalar, 3, 1> accelerometer_bias)
69 : accel_(Eigen::Matrix<double, 3, 1>::Zero()),
70 omega_(Eigen::Matrix<double, 3, 1>::Zero()),
71 imu_bias_(gyro_bias),
72 orientation_(initial_orientation),
73 x_hat_(initial_state),
74 p_(Eigen::Matrix<Scalar, 6, 6>::Zero()),
Austin Schuh2895f4c2022-02-26 16:38:46 -080075 pivot_to_camera_rotation_(pivot_to_camera),
76 pivot_to_camera_translation_(pivot_to_camera_translation),
77 pivot_to_imu_rotation_(pivot_to_imu),
78 pivot_to_imu_translation_(pivot_to_imu_translation),
Austin Schuhdcb6b362022-02-25 18:06:21 -080079 board_to_world_(board_to_world),
80 gravity_scalar_(gravity_scalar),
81 accelerometer_bias_(accelerometer_bias) {}
82
83 Scalar gravity_scalar() { return gravity_scalar_; }
84
85 virtual void ObserveCameraUpdate(
86 distributed_clock::time_point /*t*/,
87 Eigen::Vector3d /*board_to_camera_rotation*/,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080088 Eigen::Vector3d /*board_to_camera_translation*/,
Austin Schuhdcb6b362022-02-25 18:06:21 -080089 Eigen::Quaternion<Scalar> /*imu_to_world_rotation*/,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080090 Affine3s /*imu_to_world*/, double /*turret_angle*/) {}
Austin Schuh2895f4c2022-02-26 16:38:46 -080091
Austin Schuhdcb6b362022-02-25 18:06:21 -080092 // Observes a camera measurement by applying a kalman filter correction and
93 // accumulating up the error associated with the step.
94 void UpdateCamera(distributed_clock::time_point t,
95 std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) override {
96 Integrate(t);
97
Austin Schuh2895f4c2022-02-26 16:38:46 -080098 const double pivot_angle =
99 state_time_ == distributed_clock::min_time
100 ? 0.0
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800101 : turret_state_(0) +
102 turret_state_(1) *
103 chrono::duration<double>(t - state_time_).count();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800104
Austin Schuhdcb6b362022-02-25 18:06:21 -0800105 const Eigen::Quaternion<Scalar> board_to_camera_rotation(
106 frc971::controls::ToQuaternionFromRotationVector(rt.first)
107 .cast<Scalar>());
108 const Affine3s board_to_camera =
109 Eigen::Translation3d(rt.second).cast<Scalar>() *
110 board_to_camera_rotation;
111
Austin Schuh2895f4c2022-02-26 16:38:46 -0800112 const Affine3s pivot_to_camera =
113 pivot_to_camera_translation_ * pivot_to_camera_rotation_;
114 const Affine3s pivot_to_imu =
115 pivot_to_imu_translation_ * pivot_to_imu_rotation_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800116
117 // This converts us from (facing the board),
118 // x right, y up, z towards us -> x right, y away, z up.
119 // Confirmed to be right.
120
121 // Want world -> imu rotation.
122 // world <- board <- camera <- imu.
123 const Eigen::Quaternion<Scalar> imu_to_world_rotation =
124 board_to_world_ * board_to_camera_rotation.inverse() *
Austin Schuh2895f4c2022-02-26 16:38:46 -0800125 pivot_to_camera_rotation_ *
126 Eigen::AngleAxis<Scalar>(static_cast<Scalar>(-pivot_angle),
127 Eigen::Vector3d::UnitZ().cast<Scalar>()) *
128 pivot_to_imu_rotation_.inverse();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800129
130 const Affine3s imu_to_world =
Austin Schuh2895f4c2022-02-26 16:38:46 -0800131 board_to_world_ * board_to_camera.inverse() * pivot_to_camera *
132 Eigen::AngleAxis<Scalar>(static_cast<Scalar>(-pivot_angle),
133 Eigen::Vector3d::UnitZ().cast<Scalar>()) *
134 pivot_to_imu.inverse();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800135
136 const Eigen::Matrix<Scalar, 3, 1> z =
137 imu_to_world * Eigen::Matrix<Scalar, 3, 1>::Zero();
138
139 Eigen::Matrix<Scalar, 3, 6> H = Eigen::Matrix<Scalar, 3, 6>::Zero();
140 H(0, 0) = static_cast<Scalar>(1.0);
141 H(1, 1) = static_cast<Scalar>(1.0);
142 H(2, 2) = static_cast<Scalar>(1.0);
143 const Eigen::Matrix<Scalar, 3, 1> y = z - H * x_hat_;
144
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800145 // TODO<Jim>: Need to understand dependence on this-- solutions vary by 20cm
146 // when changing from 0.01 -> 0.1
147 double obs_noise_var = ::std::pow(0.01, 2);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800148 const Eigen::Matrix<double, 3, 3> R =
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800149 (::Eigen::DiagonalMatrix<double, 3>().diagonal() << obs_noise_var,
150 obs_noise_var, obs_noise_var)
Austin Schuhdcb6b362022-02-25 18:06:21 -0800151 .finished()
152 .asDiagonal();
153
154 const Eigen::Matrix<Scalar, 3, 3> S =
155 H * p_ * H.transpose() + R.cast<Scalar>();
156 const Eigen::Matrix<Scalar, 6, 3> K = p_ * H.transpose() * S.inverse();
157
158 x_hat_ += K * y;
159 p_ = (Eigen::Matrix<Scalar, 6, 6>::Identity() - K * H) * p_;
160
161 const Eigen::Quaternion<Scalar> error(imu_to_world_rotation.inverse() *
162 orientation());
163
164 errors_.emplace_back(
165 Eigen::Matrix<Scalar, 3, 1>(error.x(), error.y(), error.z()));
166 position_errors_.emplace_back(y);
167
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800168 ObserveCameraUpdate(t, rt.first, rt.second, imu_to_world_rotation,
169 imu_to_world, pivot_angle);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800170 }
171
172 virtual void ObserveIMUUpdate(
173 distributed_clock::time_point /*t*/,
174 std::pair<Eigen::Vector3d, Eigen::Vector3d> /*wa*/) {}
175
176 void UpdateIMU(distributed_clock::time_point t,
177 std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override {
178 Integrate(t);
179 omega_ = wa.first;
180 accel_ = wa.second;
181
182 ObserveIMUUpdate(t, wa);
183 }
184
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800185 virtual void ObserveTurretUpdate(distributed_clock::time_point /*t*/,
186 Eigen::Vector2d /*turret_state*/) {}
187
188 void UpdateTurret(distributed_clock::time_point t,
189 Eigen::Vector2d state) override {
190 turret_state_ = state;
191 state_time_ = t;
192
193 ObserveTurretUpdate(t, state);
194 }
195
196 Eigen::Vector2d turret_state_ = Eigen::Vector2d::Zero();
197 distributed_clock::time_point state_time_ = distributed_clock::min_time;
198
Austin Schuhdcb6b362022-02-25 18:06:21 -0800199 const Eigen::Quaternion<Scalar> &orientation() const { return orientation_; }
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800200 const Eigen::Matrix<Scalar, 6, 1> &get_x_hat() const { return x_hat_; }
Austin Schuhdcb6b362022-02-25 18:06:21 -0800201
202 size_t num_errors() const { return errors_.size(); }
203 Scalar errorx(size_t i) const { return errors_[i].x(); }
204 Scalar errory(size_t i) const { return errors_[i].y(); }
205 Scalar errorz(size_t i) const { return errors_[i].z(); }
206
207 size_t num_perrors() const { return position_errors_.size(); }
208 Scalar errorpx(size_t i) const { return position_errors_[i].x(); }
209 Scalar errorpy(size_t i) const { return position_errors_[i].y(); }
210 Scalar errorpz(size_t i) const { return position_errors_[i].z(); }
211
212 private:
213 Eigen::Matrix<Scalar, 46, 1> Pack(Eigen::Quaternion<Scalar> q,
214 Eigen::Matrix<Scalar, 6, 1> x_hat,
215 Eigen::Matrix<Scalar, 6, 6> p) {
216 Eigen::Matrix<Scalar, 46, 1> result = Eigen::Matrix<Scalar, 46, 1>::Zero();
217 result.template block<4, 1>(0, 0) = q.coeffs();
218 result.template block<6, 1>(4, 0) = x_hat;
219 result.template block<36, 1>(10, 0) =
220 Eigen::Map<Eigen::Matrix<Scalar, 36, 1>>(p.data(), p.size());
221
222 return result;
223 }
224
225 std::tuple<Eigen::Quaternion<Scalar>, Eigen::Matrix<Scalar, 6, 1>,
226 Eigen::Matrix<Scalar, 6, 6>>
227 UnPack(Eigen::Matrix<Scalar, 46, 1> input) {
228 Eigen::Quaternion<Scalar> q(input.template block<4, 1>(0, 0));
229 Eigen::Matrix<Scalar, 6, 1> x_hat(input.template block<6, 1>(4, 0));
230 Eigen::Matrix<Scalar, 6, 6> p =
231 Eigen::Map<Eigen::Matrix<Scalar, 6, 6>>(input.data() + 10, 6, 6);
232 return std::make_tuple(q, x_hat, p);
233 }
234
235 Eigen::Matrix<Scalar, 46, 1> Derivative(
236 const Eigen::Matrix<Scalar, 46, 1> &input) {
237 auto [q, x_hat, p] = UnPack(input);
238
239 Eigen::Quaternion<Scalar> omega_q;
240 omega_q.w() = Scalar(0.0);
241 omega_q.vec() = 0.5 * (omega_.cast<Scalar>() - imu_bias_);
242 Eigen::Matrix<Scalar, 4, 1> q_dot = (q * omega_q).coeffs();
243
244 Eigen::Matrix<double, 6, 6> A = Eigen::Matrix<double, 6, 6>::Zero();
245 A(0, 3) = 1.0;
246 A(1, 4) = 1.0;
247 A(2, 5) = 1.0;
248
249 Eigen::Matrix<Scalar, 6, 1> x_hat_dot = A * x_hat;
250 x_hat_dot.template block<3, 1>(3, 0) =
251 orientation() * (accel_.cast<Scalar>() - accelerometer_bias_) -
252 Eigen::Vector3d(0, 0, kGravity).cast<Scalar>() * gravity_scalar_;
253
254 // Initialize the position noise to 0. If the solver is going to back-solve
255 // for the most likely starting position, let's just say that the noise is
256 // small.
257 constexpr double kPositionNoise = 0.0;
258 constexpr double kAccelerometerNoise = 2.3e-6 * 9.8;
259 constexpr double kIMUdt = 5.0e-4;
260 Eigen::Matrix<double, 6, 6> Q_dot(
261 (::Eigen::DiagonalMatrix<double, 6>().diagonal()
262 << ::std::pow(kPositionNoise, 2) / kIMUdt,
263 ::std::pow(kPositionNoise, 2) / kIMUdt,
264 ::std::pow(kPositionNoise, 2) / kIMUdt,
265 ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
266 ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
267 ::std::pow(kAccelerometerNoise, 2) / kIMUdt)
268 .finished()
269 .asDiagonal());
270 Eigen::Matrix<Scalar, 6, 6> p_dot = A.cast<Scalar>() * p +
271 p * A.transpose().cast<Scalar>() +
272 Q_dot.cast<Scalar>();
273
274 return Pack(Eigen::Quaternion<Scalar>(q_dot), x_hat_dot, p_dot);
275 }
276
277 virtual void ObserveIntegrated(distributed_clock::time_point /*t*/,
278 Eigen::Matrix<Scalar, 6, 1> /*x_hat*/,
279 Eigen::Quaternion<Scalar> /*orientation*/,
280 Eigen::Matrix<Scalar, 6, 6> /*p*/) {}
281
282 void Integrate(distributed_clock::time_point t) {
283 if (last_time_ != distributed_clock::min_time) {
284 Eigen::Matrix<Scalar, 46, 1> next = control_loops::RungeKutta(
285 [this](auto r) { return Derivative(r); },
286 Pack(orientation_, x_hat_, p_),
287 aos::time::DurationInSeconds(t - last_time_));
288
289 std::tie(orientation_, x_hat_, p_) = UnPack(next);
290
291 // Normalize q so it doesn't drift.
292 orientation_.normalize();
293 }
294
295 last_time_ = t;
296 ObserveIntegrated(t, x_hat_, orientation_, p_);
297 }
298
299 Eigen::Matrix<double, 3, 1> accel_;
300 Eigen::Matrix<double, 3, 1> omega_;
301 Eigen::Matrix<Scalar, 3, 1> imu_bias_;
302
303 // IMU -> world quaternion
304 Eigen::Quaternion<Scalar> orientation_;
305 Eigen::Matrix<Scalar, 6, 1> x_hat_;
306 Eigen::Matrix<Scalar, 6, 6> p_;
307 distributed_clock::time_point last_time_ = distributed_clock::min_time;
308
Austin Schuh2895f4c2022-02-26 16:38:46 -0800309 Eigen::Quaternion<Scalar> pivot_to_camera_rotation_;
310 Eigen::Translation<Scalar, 3> pivot_to_camera_translation_ =
311 Eigen::Translation3d(0, 0, 0).cast<Scalar>();
312
313 Eigen::Quaternion<Scalar> pivot_to_imu_rotation_;
314 Eigen::Translation<Scalar, 3> pivot_to_imu_translation_ =
Austin Schuhdcb6b362022-02-25 18:06:21 -0800315 Eigen::Translation3d(0, 0, 0).cast<Scalar>();
316
317 Eigen::Quaternion<Scalar> board_to_world_;
318 Scalar gravity_scalar_;
319 Eigen::Matrix<Scalar, 3, 1> accelerometer_bias_;
320 // States:
321 // xyz position
322 // xyz velocity
323 //
324 // Inputs
325 // xyz accel
326 //
327 // Measurement:
328 // xyz position from camera.
329 //
330 // Since the gyro is so good, we can just solve for the bias and initial
331 // position with the solver and see what it learns.
332
333 // Returns the angular errors for each camera sample.
334 std::vector<Eigen::Matrix<Scalar, 3, 1>> errors_;
335 std::vector<Eigen::Matrix<Scalar, 3, 1>> position_errors_;
336};
337
Austin Schuh2895f4c2022-02-26 16:38:46 -0800338// Drives the Z coordinate of the quaternion to 0.
339struct PenalizeQuaternionZ {
340 template <typename S>
341 bool operator()(const S *const pivot_to_imu_ptr, S *residual) const {
342 Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0],
343 pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]);
344 residual[0] = pivot_to_imu.z();
345 return true;
346 }
347};
348
Austin Schuhdcb6b362022-02-25 18:06:21 -0800349// Subclass of the filter above which has plotting. This keeps debug code and
350// actual code separate.
351class PoseFilter : public CeresPoseFilter<double> {
352 public:
353 PoseFilter(Eigen::Quaternion<double> initial_orientation,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800354 Eigen::Quaternion<double> pivot_to_camera,
355 Eigen::Quaternion<double> pivot_to_imu,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800356 Eigen::Matrix<double, 3, 1> gyro_bias,
357 Eigen::Matrix<double, 6, 1> initial_state,
358 Eigen::Quaternion<double> board_to_world,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800359 Eigen::Matrix<double, 3, 1> pivot_to_camera_translation,
360 Eigen::Matrix<double, 3, 1> pivot_to_imu_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800361 double gravity_scalar,
362 Eigen::Matrix<double, 3, 1> accelerometer_bias)
Austin Schuh2895f4c2022-02-26 16:38:46 -0800363 : CeresPoseFilter<double>(
364 initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias,
365 initial_state, board_to_world, pivot_to_camera_translation,
366 pivot_to_imu_translation, gravity_scalar, accelerometer_bias) {}
Austin Schuhdcb6b362022-02-25 18:06:21 -0800367
368 void Plot() {
369 std::vector<double> rx;
370 std::vector<double> ry;
371 std::vector<double> rz;
372 std::vector<double> x;
373 std::vector<double> y;
374 std::vector<double> z;
375 std::vector<double> vx;
376 std::vector<double> vy;
377 std::vector<double> vz;
378 for (const Eigen::Quaternion<double> &q : orientations_) {
379 Eigen::Matrix<double, 3, 1> rotation_vector =
380 frc971::controls::ToRotationVectorFromQuaternion(q);
381 rx.emplace_back(rotation_vector(0, 0));
382 ry.emplace_back(rotation_vector(1, 0));
383 rz.emplace_back(rotation_vector(2, 0));
384 }
385 for (const Eigen::Matrix<double, 6, 1> &x_hat : x_hats_) {
386 x.emplace_back(x_hat(0));
387 y.emplace_back(x_hat(1));
388 z.emplace_back(x_hat(2));
389 vx.emplace_back(x_hat(3));
390 vy.emplace_back(x_hat(4));
391 vz.emplace_back(x_hat(5));
392 }
393
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800394 // TODO<Jim>: Could probably still do a bit more work on naming
395 // conventions and what is being shown here
Austin Schuhdcb6b362022-02-25 18:06:21 -0800396 frc971::analysis::Plotter plotter;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800397 plotter.AddFigure("bot (imu) position");
398 plotter.AddLine(times_, x, "x_hat(0)");
399 plotter.AddLine(times_, y, "x_hat(1)");
400 plotter.AddLine(times_, z, "x_hat(2)");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800401 plotter.Publish();
402
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800403 plotter.AddFigure("bot (imu) rotation");
404 plotter.AddLine(camera_times_, imu_rot_x_, "bot (imu) rot x");
405 plotter.AddLine(camera_times_, imu_rot_y_, "bot (imu) rot y");
406 plotter.AddLine(camera_times_, imu_rot_z_, "bot (imu) rot z");
407 plotter.Publish();
408
409 plotter.AddFigure("rotation error");
410 plotter.AddLine(camera_times_, rotation_error_x_, "Error x");
411 plotter.AddLine(camera_times_, rotation_error_y_, "Error y");
412 plotter.AddLine(camera_times_, rotation_error_z_, "Error z");
413 plotter.Publish();
414
415 plotter.AddFigure("translation error");
416 plotter.AddLine(camera_times_, translation_error_x_, "Error x");
417 plotter.AddLine(camera_times_, translation_error_y_, "Error y");
418 plotter.AddLine(camera_times_, translation_error_z_, "Error z");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800419 plotter.Publish();
420
421 plotter.AddFigure("imu");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800422 plotter.AddLine(imu_times_, imu_rate_x_, "imu gyro x");
423 plotter.AddLine(imu_times_, imu_rate_y_, "imu gyro y");
424 plotter.AddLine(imu_times_, imu_rate_z_, "imu gyro z");
425 plotter.AddLine(imu_times_, imu_accel_x_, "imu accel x");
426 plotter.AddLine(imu_times_, imu_accel_y_, "imu accel y");
427 plotter.AddLine(imu_times_, imu_accel_z_, "imu accel z");
428 plotter.AddLine(camera_times_, accel_minus_gravity_x_,
429 "accel_minus_gravity(0)");
430 plotter.AddLine(camera_times_, accel_minus_gravity_y_,
431 "accel_minus_gravity(1)");
432 plotter.AddLine(camera_times_, accel_minus_gravity_z_,
433 "accel_minus_gravity(2)");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800434 plotter.Publish();
435
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800436 plotter.AddFigure("raw camera observations");
437 plotter.AddLine(camera_times_, raw_camera_rot_x_, "Camera rot x");
438 plotter.AddLine(camera_times_, raw_camera_rot_y_, "Camera rot y");
439 plotter.AddLine(camera_times_, raw_camera_rot_z_, "Camera rot z");
440 plotter.AddLine(camera_times_, raw_camera_trans_x_, "Camera trans x");
441 plotter.AddLine(camera_times_, raw_camera_trans_y_, "Camera trans y");
442 plotter.AddLine(camera_times_, raw_camera_trans_z_, "Camera trans z");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800443 plotter.Publish();
444
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800445 plotter.AddFigure("xyz pos, vel estimates");
446 plotter.AddLine(times_, x, "x (x_hat(0))");
447 plotter.AddLine(times_, y, "y (x_hat(1))");
448 plotter.AddLine(times_, z, "z (x_hat(2))");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800449 plotter.AddLine(times_, vx, "vx");
450 plotter.AddLine(times_, vy, "vy");
451 plotter.AddLine(times_, vz, "vz");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800452 plotter.AddLine(camera_times_, imu_position_x_, "x pos from board");
453 plotter.AddLine(camera_times_, imu_position_y_, "y pos from board");
454 plotter.AddLine(camera_times_, imu_position_z_, "z pos from board");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800455 plotter.Publish();
456
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800457 // If we've got 'em, plot 'em
458 if (turret_times_.size() > 0) {
459 plotter.AddFigure("Turret angle");
460 plotter.AddLine(turret_times_, turret_angles_, "turret angle");
461 plotter.Publish();
462 }
463
Austin Schuhdcb6b362022-02-25 18:06:21 -0800464 plotter.Spin();
465 }
466
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800467 void Visualize(const CalibrationParameters &calibration_parameters) {
468 // Set up virtual camera for visualization
469 VisualizeRobot vis_robot;
470
471 // Set virtual viewing point 10 meters above the origin, rotated so the
472 // camera faces straight down
473 Eigen::Translation3d camera_trans(0, 0, 10.0);
474 Eigen::AngleAxisd camera_rot(M_PI, Eigen::Vector3d::UnitX());
475 Eigen::Affine3d camera_viewpoint = camera_trans * camera_rot;
476 vis_robot.SetViewpoint(camera_viewpoint);
477
478 // Create camera with origin in center, and focal length suitable to fit
479 // robot visualization fully in view
480 int image_width = 500;
481 double focal_length = 1000.0;
482 double intr[] = {focal_length, 0.0, image_width / 2.0,
483 0.0, focal_length, image_width / 2.0,
484 0.0, 0.0, 1.0};
485 cv::Mat camera_mat = cv::Mat(3, 3, CV_64FC1, intr);
486 cv::Mat dist_coeffs = cv::Mat(1, 5, CV_64F, 0.0);
487 vis_robot.SetCameraParameters(camera_mat);
488 vis_robot.SetDistortionCoefficients(dist_coeffs);
489
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800490 uint current_state_index = 0;
491 uint current_turret_index = 0;
492 for (uint i = 0; i < camera_times_.size() - 1; i++) {
493 // reset image each frame
494 cv::Mat image_mat =
495 cv::Mat::zeros(cv::Size(image_width, image_width), CV_8UC3);
496 vis_robot.SetImage(image_mat);
497
498 // Jump to state closest to current camera_time
499 while (camera_times_[i] > times_[current_state_index] &&
500 current_state_index < times_.size()) {
501 current_state_index++;
502 }
503
504 // H_world_imu: map from world origin to imu (robot) frame
505 Eigen::Vector3d T_world_imu_vec =
506 x_hats_[current_state_index].block<3, 1>(0, 0);
507 Eigen::Translation3d T_world_imu(T_world_imu_vec);
508 Eigen::Affine3d H_world_imu =
509 T_world_imu * orientations_[current_state_index];
510
511 vis_robot.DrawFrameAxes(H_world_imu, "imu_kf");
512
513 // H_world_pivot: map from world origin to pivot point
514 // Do this via the imu (using H_world_pivot = H_world_imu * H_imu_pivot)
515 Eigen::Quaterniond R_imu_pivot(calibration_parameters.pivot_to_imu);
516 Eigen::Translation3d T_imu_pivot(
517 calibration_parameters.pivot_to_imu_translation);
518 Eigen::Affine3d H_imu_pivot = T_imu_pivot * R_imu_pivot;
519 Eigen::Affine3d H_world_pivot = H_world_imu * H_imu_pivot;
520 vis_robot.DrawFrameAxes(H_world_pivot, "pivot");
521
522 // Jump to turret sample closest to current camera_time
523 while (turret_times_.size() > 0 &&
524 camera_times_[i] > turret_times_[current_turret_index] &&
525 current_turret_index < turret_times_.size()) {
526 current_turret_index++;
527 }
528
529 // Draw the camera frame
530
531 Eigen::Affine3d H_imupivot_camerapivot(Eigen::Matrix4d::Identity());
532 if (turret_angles_.size() > 0) {
533 // Need to rotate by the turret angle in the middle of all this
534 H_imupivot_camerapivot = Eigen::Affine3d(Eigen::AngleAxisd(
535 turret_angles_[current_turret_index], Eigen::Vector3d::UnitZ()));
536 }
537
538 // H_world_camera: map from world origin to camera frame
539 // Via imu->pivot->pivot rotation
540 Eigen::Quaterniond R_camera_pivot(calibration_parameters.pivot_to_camera);
541 Eigen::Translation3d T_camera_pivot(
542 calibration_parameters.pivot_to_camera_translation);
543 Eigen::Affine3d H_camera_pivot = T_camera_pivot * R_camera_pivot;
544 Eigen::Affine3d H_world_camera = H_world_imu * H_imu_pivot *
545 H_imupivot_camerapivot *
546 H_camera_pivot.inverse();
547 vis_robot.DrawFrameAxes(H_world_camera, "camera");
548
549 // H_world_board: board location from world reference frame
550 // Uses the estimate from camera-> board, on top of H_world_camera
551 Eigen::Quaterniond R_camera_board(
552 frc971::controls::ToQuaternionFromRotationVector(
553 board_to_camera_rotations_[i]));
554 Eigen::Translation3d T_camera_board(board_to_camera_translations_[i]);
555 Eigen::Affine3d H_camera_board = T_camera_board * R_camera_board;
556 Eigen::Affine3d H_world_board = H_world_camera * H_camera_board;
557
558 vis_robot.DrawFrameAxes(H_world_board, "board est");
559
560 // H_world_board_solve: board in world frame based on solver
561 // Find world -> board via solved parameter of H_world_board
562 // (parameter "board_to_world" and assuming origin of board frame is
563 // coincident with origin of world frame, i.e., T_world_board == 0)
564 Eigen::Quaterniond R_world_board_solve(
565 calibration_parameters.board_to_world);
566 Eigen::Translation3d T_world_board_solve(Eigen::Vector3d(0, 0, 0));
567 Eigen::Affine3d H_world_board_solve =
568 T_world_board_solve * R_world_board_solve;
569
570 vis_robot.DrawFrameAxes(H_world_board_solve, "board_solve");
571
572 // H_world_imu_from_board: imu location in world frame, via the board
573 // Determine the imu location via the board_to_world solved
574 // transformation
575 Eigen::Affine3d H_world_imu_from_board =
576 H_world_board_solve * H_camera_board.inverse() * H_camera_pivot *
577 H_imupivot_camerapivot.inverse() * H_imu_pivot.inverse();
578
579 vis_robot.DrawFrameAxes(H_world_imu_from_board, "imu_board");
580
581 // These errors should match up with the residuals in the optimizer
582 // (Note: rotation seems to differ by sign, but that's OK in residual)
583 Eigen::Affine3d error = H_world_imu_from_board.inverse() * H_world_imu;
584 Eigen::Vector3d trans_error =
585 H_world_imu_from_board.translation() - H_world_imu.translation();
586 Eigen::Quaterniond error_rot(error.rotation());
587 VLOG(1) << "Error: \n"
588 << "Rotation: " << error_rot.coeffs().transpose() << "\n"
589 << "Translation: " << trans_error.transpose();
590
591 cv::imshow("Live", image_mat);
592 cv::waitKey(50);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800593 }
594 LOG(INFO) << "Finished visualizing robot. Press any key to continue";
595 cv::waitKey();
596 }
597
Austin Schuhdcb6b362022-02-25 18:06:21 -0800598 void ObserveIntegrated(distributed_clock::time_point t,
599 Eigen::Matrix<double, 6, 1> x_hat,
600 Eigen::Quaternion<double> orientation,
601 Eigen::Matrix<double, 6, 6> p) override {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800602 VLOG(2) << t << " -> " << p;
603 VLOG(2) << t << " xhat -> " << x_hat.transpose();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800604 times_.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
605 x_hats_.emplace_back(x_hat);
606 orientations_.emplace_back(orientation);
607 }
608
609 void ObserveIMUUpdate(
610 distributed_clock::time_point t,
611 std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800612 imu_times_.emplace_back(
613 chrono::duration<double>(t.time_since_epoch()).count());
614 imu_rate_x_.emplace_back(wa.first.x());
615 imu_rate_y_.emplace_back(wa.first.y());
616 imu_rate_z_.emplace_back(wa.first.z());
617 imu_accel_x_.emplace_back(wa.second.x());
618 imu_accel_y_.emplace_back(wa.second.y());
619 imu_accel_z_.emplace_back(wa.second.z());
Austin Schuhdcb6b362022-02-25 18:06:21 -0800620
621 last_accel_ = wa.second;
622 }
623
624 void ObserveCameraUpdate(distributed_clock::time_point t,
625 Eigen::Vector3d board_to_camera_rotation,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800626 Eigen::Vector3d board_to_camera_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800627 Eigen::Quaternion<double> imu_to_world_rotation,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800628 Eigen::Affine3d imu_to_world,
629 double turret_angle) override {
630 board_to_camera_rotations_.emplace_back(board_to_camera_rotation);
631 board_to_camera_translations_.emplace_back(board_to_camera_translation);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800632
Austin Schuhcf848fc2022-02-25 21:34:18 -0800633 camera_times_.emplace_back(
634 chrono::duration<double>(t.time_since_epoch()).count());
Austin Schuhdcb6b362022-02-25 18:06:21 -0800635
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800636 raw_camera_rot_x_.emplace_back(board_to_camera_rotation(0, 0));
637 raw_camera_rot_y_.emplace_back(board_to_camera_rotation(1, 0));
638 raw_camera_rot_z_.emplace_back(board_to_camera_rotation(2, 0));
639
640 raw_camera_trans_x_.emplace_back(board_to_camera_translation(0, 0));
641 raw_camera_trans_y_.emplace_back(board_to_camera_translation(1, 0));
642 raw_camera_trans_z_.emplace_back(board_to_camera_translation(2, 0));
643
644 Eigen::Matrix<double, 3, 1> rotation_vector =
645 frc971::controls::ToRotationVectorFromQuaternion(imu_to_world_rotation);
646 imu_rot_x_.emplace_back(rotation_vector(0, 0));
647 imu_rot_y_.emplace_back(rotation_vector(1, 0));
648 imu_rot_z_.emplace_back(rotation_vector(2, 0));
649
650 Eigen::Matrix<double, 3, 1> rotation_error =
Austin Schuhdcb6b362022-02-25 18:06:21 -0800651 frc971::controls::ToRotationVectorFromQuaternion(
652 imu_to_world_rotation.inverse() * orientation());
653
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800654 rotation_error_x_.emplace_back(rotation_error(0, 0));
655 rotation_error_y_.emplace_back(rotation_error(1, 0));
656 rotation_error_z_.emplace_back(rotation_error(2, 0));
Austin Schuhdcb6b362022-02-25 18:06:21 -0800657
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800658 Eigen::Matrix<double, 3, 1> imu_pos = get_x_hat().block<3, 1>(0, 0);
659 Eigen::Translation3d T_world_imu(imu_pos);
660 Eigen::Affine3d H_world_imu = T_world_imu * orientation();
661 Eigen::Affine3d H_error = imu_to_world.inverse() * H_world_imu;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800662
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800663 Eigen::Matrix<double, 3, 1> translation_error = H_error.translation();
664 translation_error_x_.emplace_back(translation_error(0, 0));
665 translation_error_y_.emplace_back(translation_error(1, 0));
666 translation_error_z_.emplace_back(translation_error(2, 0));
667
668 const Eigen::Vector3d accel_minus_gravity =
Austin Schuhdcb6b362022-02-25 18:06:21 -0800669 imu_to_world_rotation * last_accel_ -
670 Eigen::Vector3d(0, 0, kGravity) * gravity_scalar();
671
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800672 accel_minus_gravity_x_.emplace_back(accel_minus_gravity.x());
673 accel_minus_gravity_y_.emplace_back(accel_minus_gravity.y());
674 accel_minus_gravity_z_.emplace_back(accel_minus_gravity.z());
Austin Schuhdcb6b362022-02-25 18:06:21 -0800675
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800676 const Eigen::Vector3d imu_position = imu_to_world * Eigen::Vector3d::Zero();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800677
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800678 imu_position_x_.emplace_back(imu_position.x());
679 imu_position_y_.emplace_back(imu_position.y());
680 imu_position_z_.emplace_back(imu_position.z());
681
682 turret_angles_from_camera_.emplace_back(turret_angle);
683 imu_to_world_save_.emplace_back(imu_to_world);
684 }
685
686 void ObserveTurretUpdate(distributed_clock::time_point t,
687 Eigen::Vector2d turret_state) override {
688 turret_times_.emplace_back(
689 chrono::duration<double>(t.time_since_epoch()).count());
690 turret_angles_.emplace_back(turret_state(0));
Austin Schuhdcb6b362022-02-25 18:06:21 -0800691 }
692
Austin Schuhcf848fc2022-02-25 21:34:18 -0800693 std::vector<double> camera_times_;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800694 std::vector<double> imu_rot_x_;
695 std::vector<double> imu_rot_y_;
696 std::vector<double> imu_rot_z_;
697 std::vector<double> raw_camera_rot_x_;
698 std::vector<double> raw_camera_rot_y_;
699 std::vector<double> raw_camera_rot_z_;
700 std::vector<double> raw_camera_trans_x_;
701 std::vector<double> raw_camera_trans_y_;
702 std::vector<double> raw_camera_trans_z_;
703 std::vector<double> rotation_error_x_;
704 std::vector<double> rotation_error_y_;
705 std::vector<double> rotation_error_z_;
706 std::vector<double> translation_error_x_;
707 std::vector<double> translation_error_y_;
708 std::vector<double> translation_error_z_;
709 std::vector<Eigen::Vector3d> board_to_camera_rotations_;
710 std::vector<Eigen::Vector3d> board_to_camera_translations_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800711
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800712 std::vector<double> turret_angles_from_camera_;
713 std::vector<Eigen::Affine3d> imu_to_world_save_;
714
715 std::vector<double> imu_position_x_;
716 std::vector<double> imu_position_y_;
717 std::vector<double> imu_position_z_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800718
Austin Schuhcf848fc2022-02-25 21:34:18 -0800719 std::vector<double> imu_times_;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800720 std::vector<double> imu_rate_x_;
721 std::vector<double> imu_rate_y_;
722 std::vector<double> imu_rate_z_;
723 std::vector<double> accel_minus_gravity_x_;
724 std::vector<double> accel_minus_gravity_y_;
725 std::vector<double> accel_minus_gravity_z_;
726 std::vector<double> imu_accel_x_;
727 std::vector<double> imu_accel_y_;
728 std::vector<double> imu_accel_z_;
729
730 std::vector<double> turret_times_;
731 std::vector<double> turret_angles_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800732
733 std::vector<double> times_;
734 std::vector<Eigen::Matrix<double, 6, 1>> x_hats_;
735 std::vector<Eigen::Quaternion<double>> orientations_;
736
737 Eigen::Matrix<double, 3, 1> last_accel_ = Eigen::Matrix<double, 3, 1>::Zero();
738};
739
740// Adapter class from the KF above to a Ceres cost function.
741struct CostFunctor {
742 CostFunctor(const CalibrationData *d) : data(d) {}
743
744 const CalibrationData *data;
745
746 template <typename S>
Austin Schuh2895f4c2022-02-26 16:38:46 -0800747 bool operator()(const S *const initial_orientation_ptr,
748 const S *const pivot_to_camera_ptr,
749 const S *const pivot_to_imu_ptr, const S *const gyro_bias_ptr,
750 const S *const initial_state_ptr,
751 const S *const board_to_world_ptr,
752 const S *const pivot_to_camera_translation_ptr,
753 const S *const pivot_to_imu_translation_ptr,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800754 const S *const gravity_scalar_ptr,
755 const S *const accelerometer_bias_ptr, S *residual) const {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800756 const aos::monotonic_clock::time_point start_time =
757 aos::monotonic_clock::now();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800758 Eigen::Quaternion<S> initial_orientation(
759 initial_orientation_ptr[3], initial_orientation_ptr[0],
760 initial_orientation_ptr[1], initial_orientation_ptr[2]);
761 Eigen::Quaternion<S> pivot_to_camera(
762 pivot_to_camera_ptr[3], pivot_to_camera_ptr[0], pivot_to_camera_ptr[1],
763 pivot_to_camera_ptr[2]);
764 Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0],
765 pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]);
766 Eigen::Quaternion<S> board_to_world(
767 board_to_world_ptr[3], board_to_world_ptr[0], board_to_world_ptr[1],
768 board_to_world_ptr[2]);
769 Eigen::Matrix<S, 3, 1> gyro_bias(gyro_bias_ptr[0], gyro_bias_ptr[1],
770 gyro_bias_ptr[2]);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800771 Eigen::Matrix<S, 6, 1> initial_state;
Austin Schuh2895f4c2022-02-26 16:38:46 -0800772 initial_state(0) = initial_state_ptr[0];
773 initial_state(1) = initial_state_ptr[1];
774 initial_state(2) = initial_state_ptr[2];
775 initial_state(3) = initial_state_ptr[3];
776 initial_state(4) = initial_state_ptr[4];
777 initial_state(5) = initial_state_ptr[5];
778 Eigen::Matrix<S, 3, 1> pivot_to_camera_translation(
779 pivot_to_camera_translation_ptr[0], pivot_to_camera_translation_ptr[1],
780 pivot_to_camera_translation_ptr[2]);
781 Eigen::Matrix<S, 3, 1> pivot_to_imu_translation(
782 pivot_to_imu_translation_ptr[0], pivot_to_imu_translation_ptr[1],
783 pivot_to_imu_translation_ptr[2]);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800784 Eigen::Matrix<S, 3, 1> accelerometer_bias(accelerometer_bias_ptr[0],
785 accelerometer_bias_ptr[1],
786 accelerometer_bias_ptr[2]);
787
Austin Schuh2895f4c2022-02-26 16:38:46 -0800788 CeresPoseFilter<S> filter(
789 initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias,
790 initial_state, board_to_world, pivot_to_camera_translation,
791 pivot_to_imu_translation, *gravity_scalar_ptr, accelerometer_bias);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800792 data->ReviewData(&filter);
793
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800794 // Since the angular error scale is bounded by 1 (quaternion, so unit
795 // vector, scaled by sin(alpha)), I found it necessary to scale the
796 // angular error to have it properly balance with the translational error
797 double ang_error_scale = 5.0;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800798 for (size_t i = 0; i < filter.num_errors(); ++i) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800799 residual[3 * i + 0] = ang_error_scale * filter.errorx(i);
800 residual[3 * i + 1] = ang_error_scale * filter.errory(i);
801 residual[3 * i + 2] = ang_error_scale * filter.errorz(i);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800802 }
803
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800804 double trans_error_scale = 1.0;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800805 for (size_t i = 0; i < filter.num_perrors(); ++i) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800806 residual[3 * filter.num_errors() + 3 * i + 0] =
807 trans_error_scale * filter.errorpx(i);
808 residual[3 * filter.num_errors() + 3 * i + 1] =
809 trans_error_scale * filter.errorpy(i);
810 residual[3 * filter.num_errors() + 3 * i + 2] =
811 trans_error_scale * filter.errorpz(i);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800812 }
813
Jim Ostrowski86203682023-02-22 19:43:10 -0800814 VLOG(2) << "Cost function calc took "
815 << chrono::duration<double>(aos::monotonic_clock::now() -
816 start_time)
817 .count()
818 << " seconds";
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800819
Austin Schuhdcb6b362022-02-25 18:06:21 -0800820 return true;
821 }
822};
823
James Kuszmaul086d0192023-02-11 15:35:03 -0800824std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H) {
825 std::vector<float> data;
826 for (int row = 0; row < 4; ++row) {
827 for (int col = 0; col < 4; ++col) {
828 data.push_back(H(row, col));
829 }
830 }
831 return data;
832}
833
834aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> Solve(
835 const CalibrationData &data,
836 CalibrationParameters *calibration_parameters) {
Austin Schuhdcb6b362022-02-25 18:06:21 -0800837 ceres::Problem problem;
838
839 ceres::EigenQuaternionParameterization *quaternion_local_parameterization =
840 new ceres::EigenQuaternionParameterization();
841 // Set up the only cost function (also known as residual). This uses
842 // auto-differentiation to obtain the derivative (jacobian).
843
Austin Schuh2895f4c2022-02-26 16:38:46 -0800844 {
845 ceres::CostFunction *cost_function =
846 new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 4, 3,
847 6, 4, 3, 3, 1, 3>(
848 new CostFunctor(&data), data.camera_samples_size() * 6);
849 problem.AddResidualBlock(
850 cost_function, new ceres::HuberLoss(1.0),
851 calibration_parameters->initial_orientation.coeffs().data(),
852 calibration_parameters->pivot_to_camera.coeffs().data(),
853 calibration_parameters->pivot_to_imu.coeffs().data(),
854 calibration_parameters->gyro_bias.data(),
855 calibration_parameters->initial_state.data(),
856 calibration_parameters->board_to_world.coeffs().data(),
857 calibration_parameters->pivot_to_camera_translation.data(),
858 calibration_parameters->pivot_to_imu_translation.data(),
859 &calibration_parameters->gravity_scalar,
860 calibration_parameters->accelerometer_bias.data());
861 }
862
Jim Ostrowski86203682023-02-22 19:43:10 -0800863 if (calibration_parameters->has_pivot) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800864 // The turret's Z rotation is redundant with the camera's mounting z
865 // rotation since it's along the rotation axis.
Austin Schuh2895f4c2022-02-26 16:38:46 -0800866 ceres::CostFunction *turret_z_cost_function =
867 new ceres::AutoDiffCostFunction<PenalizeQuaternionZ, 1, 4>(
868 new PenalizeQuaternionZ());
869 problem.AddResidualBlock(
870 turret_z_cost_function, nullptr,
871 calibration_parameters->pivot_to_imu.coeffs().data());
872 }
873
874 if (calibration_parameters->has_pivot) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800875 // Constrain Z since it's along the rotation axis and therefore
876 // redundant.
Austin Schuh2895f4c2022-02-26 16:38:46 -0800877 problem.SetParameterization(
878 calibration_parameters->pivot_to_imu_translation.data(),
879 new ceres::SubsetParameterization(3, {2}));
880 } else {
881 problem.SetParameterBlockConstant(
882 calibration_parameters->pivot_to_imu.coeffs().data());
883 problem.SetParameterBlockConstant(
884 calibration_parameters->pivot_to_imu_translation.data());
885 }
886
Jim Ostrowski86203682023-02-22 19:43:10 -0800887 {
888 // The board rotation in z is a bit arbitrary, so hoping to limit it to
889 // increase repeatability
890 ceres::CostFunction *board_z_cost_function =
891 new ceres::AutoDiffCostFunction<PenalizeQuaternionZ, 1, 4>(
892 new PenalizeQuaternionZ());
893 problem.AddResidualBlock(
894 board_z_cost_function, nullptr,
895 calibration_parameters->board_to_world.coeffs().data());
896 }
897
Austin Schuhdcb6b362022-02-25 18:06:21 -0800898 problem.SetParameterization(
899 calibration_parameters->initial_orientation.coeffs().data(),
900 quaternion_local_parameterization);
901 problem.SetParameterization(
Austin Schuh2895f4c2022-02-26 16:38:46 -0800902 calibration_parameters->pivot_to_camera.coeffs().data(),
Austin Schuhdcb6b362022-02-25 18:06:21 -0800903 quaternion_local_parameterization);
904 problem.SetParameterization(
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800905 calibration_parameters->pivot_to_imu.coeffs().data(),
906 quaternion_local_parameterization);
907 problem.SetParameterization(
Austin Schuhdcb6b362022-02-25 18:06:21 -0800908 calibration_parameters->board_to_world.coeffs().data(),
909 quaternion_local_parameterization);
910 for (int i = 0; i < 3; ++i) {
911 problem.SetParameterLowerBound(calibration_parameters->gyro_bias.data(), i,
912 -0.05);
913 problem.SetParameterUpperBound(calibration_parameters->gyro_bias.data(), i,
914 0.05);
915 problem.SetParameterLowerBound(
916 calibration_parameters->accelerometer_bias.data(), i, -0.05);
917 problem.SetParameterUpperBound(
918 calibration_parameters->accelerometer_bias.data(), i, 0.05);
919 }
920 problem.SetParameterLowerBound(&calibration_parameters->gravity_scalar, 0,
921 0.95);
922 problem.SetParameterUpperBound(&calibration_parameters->gravity_scalar, 0,
923 1.05);
924
925 // Run the solver!
926 ceres::Solver::Options options;
927 options.minimizer_progress_to_stdout = true;
Jim Ostrowski86203682023-02-22 19:43:10 -0800928 options.gradient_tolerance = 1e-6;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800929 options.function_tolerance = 1e-6;
Jim Ostrowski86203682023-02-22 19:43:10 -0800930 options.parameter_tolerance = 1e-6;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800931 ceres::Solver::Summary summary;
932 Solve(options, &problem, &summary);
933 LOG(INFO) << summary.FullReport();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800934 LOG(INFO) << "Solution is " << (summary.IsSolutionUsable() ? "" : "NOT ")
935 << "usable";
James Kuszmaul086d0192023-02-11 15:35:03 -0800936
937 {
938 flatbuffers::FlatBufferBuilder fbb;
939 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
940 fbb.CreateVector(MatrixToVector(
941 (Eigen::Translation3d(
942 calibration_parameters->pivot_to_camera_translation) *
943 Eigen::Quaterniond(calibration_parameters->pivot_to_camera))
944 .inverse()
945 .matrix()));
946 calibration::TransformationMatrix::Builder matrix_builder(fbb);
947 matrix_builder.add_data(data_offset);
948 flatbuffers::Offset<calibration::TransformationMatrix>
949 camera_to_pivot_offset = matrix_builder.Finish();
950
951 flatbuffers::Offset<calibration::TransformationMatrix> pivot_to_imu_offset;
952 if (calibration_parameters->has_pivot) {
953 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
954 fbb.CreateVector(MatrixToVector(
955 (Eigen::Translation3d(
956 calibration_parameters->pivot_to_imu_translation) *
957 Eigen::Quaterniond(calibration_parameters->pivot_to_imu))
958 .matrix()));
959 calibration::TransformationMatrix::Builder matrix_builder(fbb);
960 matrix_builder.add_data(data_offset);
961 pivot_to_imu_offset = matrix_builder.Finish();
962 }
963
964 calibration::CameraCalibration::Builder calibration_builder(fbb);
965 if (calibration_parameters->has_pivot) {
966 calibration_builder.add_fixed_extrinsics(pivot_to_imu_offset);
967 calibration_builder.add_turret_extrinsics(camera_to_pivot_offset);
968 } else {
969 calibration_builder.add_fixed_extrinsics(camera_to_pivot_offset);
970 }
971 fbb.Finish(calibration_builder.Finish());
972 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> extrinsics =
973 fbb.Release();
974 return extrinsics;
975 }
Austin Schuhdcb6b362022-02-25 18:06:21 -0800976}
977
978void Plot(const CalibrationData &data,
979 const CalibrationParameters &calibration_parameters) {
980 PoseFilter filter(calibration_parameters.initial_orientation,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800981 calibration_parameters.pivot_to_camera,
982 calibration_parameters.pivot_to_imu,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800983 calibration_parameters.gyro_bias,
984 calibration_parameters.initial_state,
985 calibration_parameters.board_to_world,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800986 calibration_parameters.pivot_to_camera_translation,
987 calibration_parameters.pivot_to_imu_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800988 calibration_parameters.gravity_scalar,
989 calibration_parameters.accelerometer_bias);
990 data.ReviewData(&filter);
991 filter.Plot();
992}
993
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800994void Visualize(const CalibrationData &data,
995 const CalibrationParameters &calibration_parameters) {
996 PoseFilter filter(calibration_parameters.initial_orientation,
997 calibration_parameters.pivot_to_camera,
998 calibration_parameters.pivot_to_imu,
999 calibration_parameters.gyro_bias,
1000 calibration_parameters.initial_state,
1001 calibration_parameters.board_to_world,
1002 calibration_parameters.pivot_to_camera_translation,
1003 calibration_parameters.pivot_to_imu_translation,
1004 calibration_parameters.gravity_scalar,
1005 calibration_parameters.accelerometer_bias);
1006 data.ReviewData(&filter);
1007 filter.Visualize(calibration_parameters);
1008}
1009
Stephan Pleinesf63bde82024-01-13 15:59:33 -08001010} // namespace frc971::vision