blob: daa371eaaaca8c03b36cebbb8ca50eb04bab042d [file] [log] [blame]
Austin Schuhdcb6b362022-02-25 18:06:21 -08001#include "frc971/vision/extrinsics_calibration.h"
2
3#include "aos/time/time.h"
4#include "ceres/ceres.h"
5#include "frc971/analysis/in_process_plotter.h"
6#include "frc971/control_loops/runge_kutta.h"
7#include "frc971/vision/calibration_accumulator.h"
8#include "frc971/vision/charuco_lib.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08009#include "frc971/vision/visualize_robot.h"
10
11#include <opencv2/core.hpp>
12#include <opencv2/core/eigen.hpp>
13#include <opencv2/highgui.hpp>
14#include <opencv2/highgui/highgui.hpp>
15#include <opencv2/imgproc.hpp>
Austin Schuhdcb6b362022-02-25 18:06:21 -080016
17namespace frc971 {
18namespace vision {
19
20namespace chrono = std::chrono;
21using aos::distributed_clock;
22using aos::monotonic_clock;
23
24constexpr double kGravity = 9.8;
25
26// The basic ideas here are taken from Kalibr.
27// (https://github.com/ethz-asl/kalibr), but adapted to work with AOS, and to be
28// simpler.
29//
30// Camera readings and IMU readings come in at different times, on different
31// time scales. Our first problem is to align them in time so we can actually
32// compute an error. This is done in the calibration accumulator code. The
33// kalibr paper uses splines, while this uses kalman filters to solve the same
34// interpolation problem so we can get the expected vs actual pose at the time
35// each image arrives.
36//
37// The cost function is then fed the computed angular and positional error for
38// each camera sample before the kalman filter update. Intuitively, the smaller
39// the corrections to the kalman filter each step, the better the estimate
40// should be.
41//
42// We don't actually implement the angular kalman filter because the IMU is so
43// good. We give the solver an initial position and bias, and let it solve from
44// there. This lets us represent drift that is linear in time, which should be
45// good enough for ~1 minute calibration.
46//
47// TODO(austin): Kalman smoother ala
48// https://stanford.edu/~boyd/papers/pdf/auto_ks.pdf should allow for better
49// parallelism, and since we aren't causal, will take that into account a lot
50// better.
51
52// This class takes the initial parameters and biases, and computes the error
53// between the measured and expected camera readings. When optimized, this
54// gives us a cost function to minimize.
55template <typename Scalar>
56class CeresPoseFilter : public CalibrationDataObserver {
57 public:
58 typedef Eigen::Transform<Scalar, 3, Eigen::Affine> Affine3s;
59
60 CeresPoseFilter(Eigen::Quaternion<Scalar> initial_orientation,
Austin Schuh2895f4c2022-02-26 16:38:46 -080061 Eigen::Quaternion<Scalar> pivot_to_camera,
62 Eigen::Quaternion<Scalar> pivot_to_imu,
Austin Schuhdcb6b362022-02-25 18:06:21 -080063 Eigen::Matrix<Scalar, 3, 1> gyro_bias,
64 Eigen::Matrix<Scalar, 6, 1> initial_state,
65 Eigen::Quaternion<Scalar> board_to_world,
Austin Schuh2895f4c2022-02-26 16:38:46 -080066 Eigen::Matrix<Scalar, 3, 1> pivot_to_camera_translation,
67 Eigen::Matrix<Scalar, 3, 1> pivot_to_imu_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -080068 Scalar gravity_scalar,
69 Eigen::Matrix<Scalar, 3, 1> accelerometer_bias)
70 : accel_(Eigen::Matrix<double, 3, 1>::Zero()),
71 omega_(Eigen::Matrix<double, 3, 1>::Zero()),
72 imu_bias_(gyro_bias),
73 orientation_(initial_orientation),
74 x_hat_(initial_state),
75 p_(Eigen::Matrix<Scalar, 6, 6>::Zero()),
Austin Schuh2895f4c2022-02-26 16:38:46 -080076 pivot_to_camera_rotation_(pivot_to_camera),
77 pivot_to_camera_translation_(pivot_to_camera_translation),
78 pivot_to_imu_rotation_(pivot_to_imu),
79 pivot_to_imu_translation_(pivot_to_imu_translation),
Austin Schuhdcb6b362022-02-25 18:06:21 -080080 board_to_world_(board_to_world),
81 gravity_scalar_(gravity_scalar),
82 accelerometer_bias_(accelerometer_bias) {}
83
84 Scalar gravity_scalar() { return gravity_scalar_; }
85
86 virtual void ObserveCameraUpdate(
87 distributed_clock::time_point /*t*/,
88 Eigen::Vector3d /*board_to_camera_rotation*/,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080089 Eigen::Vector3d /*board_to_camera_translation*/,
Austin Schuhdcb6b362022-02-25 18:06:21 -080090 Eigen::Quaternion<Scalar> /*imu_to_world_rotation*/,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080091 Affine3s /*imu_to_world*/, double /*turret_angle*/) {}
Austin Schuh2895f4c2022-02-26 16:38:46 -080092
Austin Schuhdcb6b362022-02-25 18:06:21 -080093 // Observes a camera measurement by applying a kalman filter correction and
94 // accumulating up the error associated with the step.
95 void UpdateCamera(distributed_clock::time_point t,
96 std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) override {
97 Integrate(t);
98
Austin Schuh2895f4c2022-02-26 16:38:46 -080099 const double pivot_angle =
100 state_time_ == distributed_clock::min_time
101 ? 0.0
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800102 : turret_state_(0) +
103 turret_state_(1) *
104 chrono::duration<double>(t - state_time_).count();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800105
Austin Schuhdcb6b362022-02-25 18:06:21 -0800106 const Eigen::Quaternion<Scalar> board_to_camera_rotation(
107 frc971::controls::ToQuaternionFromRotationVector(rt.first)
108 .cast<Scalar>());
109 const Affine3s board_to_camera =
110 Eigen::Translation3d(rt.second).cast<Scalar>() *
111 board_to_camera_rotation;
112
Austin Schuh2895f4c2022-02-26 16:38:46 -0800113 const Affine3s pivot_to_camera =
114 pivot_to_camera_translation_ * pivot_to_camera_rotation_;
115 const Affine3s pivot_to_imu =
116 pivot_to_imu_translation_ * pivot_to_imu_rotation_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800117
118 // This converts us from (facing the board),
119 // x right, y up, z towards us -> x right, y away, z up.
120 // Confirmed to be right.
121
122 // Want world -> imu rotation.
123 // world <- board <- camera <- imu.
124 const Eigen::Quaternion<Scalar> imu_to_world_rotation =
125 board_to_world_ * board_to_camera_rotation.inverse() *
Austin Schuh2895f4c2022-02-26 16:38:46 -0800126 pivot_to_camera_rotation_ *
127 Eigen::AngleAxis<Scalar>(static_cast<Scalar>(-pivot_angle),
128 Eigen::Vector3d::UnitZ().cast<Scalar>()) *
129 pivot_to_imu_rotation_.inverse();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800130
131 const Affine3s imu_to_world =
Austin Schuh2895f4c2022-02-26 16:38:46 -0800132 board_to_world_ * board_to_camera.inverse() * pivot_to_camera *
133 Eigen::AngleAxis<Scalar>(static_cast<Scalar>(-pivot_angle),
134 Eigen::Vector3d::UnitZ().cast<Scalar>()) *
135 pivot_to_imu.inverse();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800136
137 const Eigen::Matrix<Scalar, 3, 1> z =
138 imu_to_world * Eigen::Matrix<Scalar, 3, 1>::Zero();
139
140 Eigen::Matrix<Scalar, 3, 6> H = Eigen::Matrix<Scalar, 3, 6>::Zero();
141 H(0, 0) = static_cast<Scalar>(1.0);
142 H(1, 1) = static_cast<Scalar>(1.0);
143 H(2, 2) = static_cast<Scalar>(1.0);
144 const Eigen::Matrix<Scalar, 3, 1> y = z - H * x_hat_;
145
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800146 // TODO<Jim>: Need to understand dependence on this-- solutions vary by 20cm
147 // when changing from 0.01 -> 0.1
148 double obs_noise_var = ::std::pow(0.01, 2);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800149 const Eigen::Matrix<double, 3, 3> R =
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800150 (::Eigen::DiagonalMatrix<double, 3>().diagonal() << obs_noise_var,
151 obs_noise_var, obs_noise_var)
Austin Schuhdcb6b362022-02-25 18:06:21 -0800152 .finished()
153 .asDiagonal();
154
155 const Eigen::Matrix<Scalar, 3, 3> S =
156 H * p_ * H.transpose() + R.cast<Scalar>();
157 const Eigen::Matrix<Scalar, 6, 3> K = p_ * H.transpose() * S.inverse();
158
159 x_hat_ += K * y;
160 p_ = (Eigen::Matrix<Scalar, 6, 6>::Identity() - K * H) * p_;
161
162 const Eigen::Quaternion<Scalar> error(imu_to_world_rotation.inverse() *
163 orientation());
164
165 errors_.emplace_back(
166 Eigen::Matrix<Scalar, 3, 1>(error.x(), error.y(), error.z()));
167 position_errors_.emplace_back(y);
168
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800169 ObserveCameraUpdate(t, rt.first, rt.second, imu_to_world_rotation,
170 imu_to_world, pivot_angle);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800171 }
172
173 virtual void ObserveIMUUpdate(
174 distributed_clock::time_point /*t*/,
175 std::pair<Eigen::Vector3d, Eigen::Vector3d> /*wa*/) {}
176
177 void UpdateIMU(distributed_clock::time_point t,
178 std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override {
179 Integrate(t);
180 omega_ = wa.first;
181 accel_ = wa.second;
182
183 ObserveIMUUpdate(t, wa);
184 }
185
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800186 virtual void ObserveTurretUpdate(distributed_clock::time_point /*t*/,
187 Eigen::Vector2d /*turret_state*/) {}
188
189 void UpdateTurret(distributed_clock::time_point t,
190 Eigen::Vector2d state) override {
191 turret_state_ = state;
192 state_time_ = t;
193
194 ObserveTurretUpdate(t, state);
195 }
196
197 Eigen::Vector2d turret_state_ = Eigen::Vector2d::Zero();
198 distributed_clock::time_point state_time_ = distributed_clock::min_time;
199
Austin Schuhdcb6b362022-02-25 18:06:21 -0800200 const Eigen::Quaternion<Scalar> &orientation() const { return orientation_; }
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800201 const Eigen::Matrix<Scalar, 6, 1> &get_x_hat() const { return x_hat_; }
Austin Schuhdcb6b362022-02-25 18:06:21 -0800202
203 size_t num_errors() const { return errors_.size(); }
204 Scalar errorx(size_t i) const { return errors_[i].x(); }
205 Scalar errory(size_t i) const { return errors_[i].y(); }
206 Scalar errorz(size_t i) const { return errors_[i].z(); }
207
208 size_t num_perrors() const { return position_errors_.size(); }
209 Scalar errorpx(size_t i) const { return position_errors_[i].x(); }
210 Scalar errorpy(size_t i) const { return position_errors_[i].y(); }
211 Scalar errorpz(size_t i) const { return position_errors_[i].z(); }
212
213 private:
214 Eigen::Matrix<Scalar, 46, 1> Pack(Eigen::Quaternion<Scalar> q,
215 Eigen::Matrix<Scalar, 6, 1> x_hat,
216 Eigen::Matrix<Scalar, 6, 6> p) {
217 Eigen::Matrix<Scalar, 46, 1> result = Eigen::Matrix<Scalar, 46, 1>::Zero();
218 result.template block<4, 1>(0, 0) = q.coeffs();
219 result.template block<6, 1>(4, 0) = x_hat;
220 result.template block<36, 1>(10, 0) =
221 Eigen::Map<Eigen::Matrix<Scalar, 36, 1>>(p.data(), p.size());
222
223 return result;
224 }
225
226 std::tuple<Eigen::Quaternion<Scalar>, Eigen::Matrix<Scalar, 6, 1>,
227 Eigen::Matrix<Scalar, 6, 6>>
228 UnPack(Eigen::Matrix<Scalar, 46, 1> input) {
229 Eigen::Quaternion<Scalar> q(input.template block<4, 1>(0, 0));
230 Eigen::Matrix<Scalar, 6, 1> x_hat(input.template block<6, 1>(4, 0));
231 Eigen::Matrix<Scalar, 6, 6> p =
232 Eigen::Map<Eigen::Matrix<Scalar, 6, 6>>(input.data() + 10, 6, 6);
233 return std::make_tuple(q, x_hat, p);
234 }
235
236 Eigen::Matrix<Scalar, 46, 1> Derivative(
237 const Eigen::Matrix<Scalar, 46, 1> &input) {
238 auto [q, x_hat, p] = UnPack(input);
239
240 Eigen::Quaternion<Scalar> omega_q;
241 omega_q.w() = Scalar(0.0);
242 omega_q.vec() = 0.5 * (omega_.cast<Scalar>() - imu_bias_);
243 Eigen::Matrix<Scalar, 4, 1> q_dot = (q * omega_q).coeffs();
244
245 Eigen::Matrix<double, 6, 6> A = Eigen::Matrix<double, 6, 6>::Zero();
246 A(0, 3) = 1.0;
247 A(1, 4) = 1.0;
248 A(2, 5) = 1.0;
249
250 Eigen::Matrix<Scalar, 6, 1> x_hat_dot = A * x_hat;
251 x_hat_dot.template block<3, 1>(3, 0) =
252 orientation() * (accel_.cast<Scalar>() - accelerometer_bias_) -
253 Eigen::Vector3d(0, 0, kGravity).cast<Scalar>() * gravity_scalar_;
254
255 // Initialize the position noise to 0. If the solver is going to back-solve
256 // for the most likely starting position, let's just say that the noise is
257 // small.
258 constexpr double kPositionNoise = 0.0;
259 constexpr double kAccelerometerNoise = 2.3e-6 * 9.8;
260 constexpr double kIMUdt = 5.0e-4;
261 Eigen::Matrix<double, 6, 6> Q_dot(
262 (::Eigen::DiagonalMatrix<double, 6>().diagonal()
263 << ::std::pow(kPositionNoise, 2) / kIMUdt,
264 ::std::pow(kPositionNoise, 2) / kIMUdt,
265 ::std::pow(kPositionNoise, 2) / kIMUdt,
266 ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
267 ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
268 ::std::pow(kAccelerometerNoise, 2) / kIMUdt)
269 .finished()
270 .asDiagonal());
271 Eigen::Matrix<Scalar, 6, 6> p_dot = A.cast<Scalar>() * p +
272 p * A.transpose().cast<Scalar>() +
273 Q_dot.cast<Scalar>();
274
275 return Pack(Eigen::Quaternion<Scalar>(q_dot), x_hat_dot, p_dot);
276 }
277
278 virtual void ObserveIntegrated(distributed_clock::time_point /*t*/,
279 Eigen::Matrix<Scalar, 6, 1> /*x_hat*/,
280 Eigen::Quaternion<Scalar> /*orientation*/,
281 Eigen::Matrix<Scalar, 6, 6> /*p*/) {}
282
283 void Integrate(distributed_clock::time_point t) {
284 if (last_time_ != distributed_clock::min_time) {
285 Eigen::Matrix<Scalar, 46, 1> next = control_loops::RungeKutta(
286 [this](auto r) { return Derivative(r); },
287 Pack(orientation_, x_hat_, p_),
288 aos::time::DurationInSeconds(t - last_time_));
289
290 std::tie(orientation_, x_hat_, p_) = UnPack(next);
291
292 // Normalize q so it doesn't drift.
293 orientation_.normalize();
294 }
295
296 last_time_ = t;
297 ObserveIntegrated(t, x_hat_, orientation_, p_);
298 }
299
300 Eigen::Matrix<double, 3, 1> accel_;
301 Eigen::Matrix<double, 3, 1> omega_;
302 Eigen::Matrix<Scalar, 3, 1> imu_bias_;
303
304 // IMU -> world quaternion
305 Eigen::Quaternion<Scalar> orientation_;
306 Eigen::Matrix<Scalar, 6, 1> x_hat_;
307 Eigen::Matrix<Scalar, 6, 6> p_;
308 distributed_clock::time_point last_time_ = distributed_clock::min_time;
309
Austin Schuh2895f4c2022-02-26 16:38:46 -0800310 Eigen::Quaternion<Scalar> pivot_to_camera_rotation_;
311 Eigen::Translation<Scalar, 3> pivot_to_camera_translation_ =
312 Eigen::Translation3d(0, 0, 0).cast<Scalar>();
313
314 Eigen::Quaternion<Scalar> pivot_to_imu_rotation_;
315 Eigen::Translation<Scalar, 3> pivot_to_imu_translation_ =
Austin Schuhdcb6b362022-02-25 18:06:21 -0800316 Eigen::Translation3d(0, 0, 0).cast<Scalar>();
317
318 Eigen::Quaternion<Scalar> board_to_world_;
319 Scalar gravity_scalar_;
320 Eigen::Matrix<Scalar, 3, 1> accelerometer_bias_;
321 // States:
322 // xyz position
323 // xyz velocity
324 //
325 // Inputs
326 // xyz accel
327 //
328 // Measurement:
329 // xyz position from camera.
330 //
331 // Since the gyro is so good, we can just solve for the bias and initial
332 // position with the solver and see what it learns.
333
334 // Returns the angular errors for each camera sample.
335 std::vector<Eigen::Matrix<Scalar, 3, 1>> errors_;
336 std::vector<Eigen::Matrix<Scalar, 3, 1>> position_errors_;
337};
338
Austin Schuh2895f4c2022-02-26 16:38:46 -0800339// Drives the Z coordinate of the quaternion to 0.
340struct PenalizeQuaternionZ {
341 template <typename S>
342 bool operator()(const S *const pivot_to_imu_ptr, S *residual) const {
343 Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0],
344 pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]);
345 residual[0] = pivot_to_imu.z();
346 return true;
347 }
348};
349
Austin Schuhdcb6b362022-02-25 18:06:21 -0800350// Subclass of the filter above which has plotting. This keeps debug code and
351// actual code separate.
352class PoseFilter : public CeresPoseFilter<double> {
353 public:
354 PoseFilter(Eigen::Quaternion<double> initial_orientation,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800355 Eigen::Quaternion<double> pivot_to_camera,
356 Eigen::Quaternion<double> pivot_to_imu,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800357 Eigen::Matrix<double, 3, 1> gyro_bias,
358 Eigen::Matrix<double, 6, 1> initial_state,
359 Eigen::Quaternion<double> board_to_world,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800360 Eigen::Matrix<double, 3, 1> pivot_to_camera_translation,
361 Eigen::Matrix<double, 3, 1> pivot_to_imu_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800362 double gravity_scalar,
363 Eigen::Matrix<double, 3, 1> accelerometer_bias)
Austin Schuh2895f4c2022-02-26 16:38:46 -0800364 : CeresPoseFilter<double>(
365 initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias,
366 initial_state, board_to_world, pivot_to_camera_translation,
367 pivot_to_imu_translation, gravity_scalar, accelerometer_bias) {}
Austin Schuhdcb6b362022-02-25 18:06:21 -0800368
369 void Plot() {
370 std::vector<double> rx;
371 std::vector<double> ry;
372 std::vector<double> rz;
373 std::vector<double> x;
374 std::vector<double> y;
375 std::vector<double> z;
376 std::vector<double> vx;
377 std::vector<double> vy;
378 std::vector<double> vz;
379 for (const Eigen::Quaternion<double> &q : orientations_) {
380 Eigen::Matrix<double, 3, 1> rotation_vector =
381 frc971::controls::ToRotationVectorFromQuaternion(q);
382 rx.emplace_back(rotation_vector(0, 0));
383 ry.emplace_back(rotation_vector(1, 0));
384 rz.emplace_back(rotation_vector(2, 0));
385 }
386 for (const Eigen::Matrix<double, 6, 1> &x_hat : x_hats_) {
387 x.emplace_back(x_hat(0));
388 y.emplace_back(x_hat(1));
389 z.emplace_back(x_hat(2));
390 vx.emplace_back(x_hat(3));
391 vy.emplace_back(x_hat(4));
392 vz.emplace_back(x_hat(5));
393 }
394
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800395 // TODO<Jim>: Could probably still do a bit more work on naming
396 // conventions and what is being shown here
Austin Schuhdcb6b362022-02-25 18:06:21 -0800397 frc971::analysis::Plotter plotter;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800398 plotter.AddFigure("bot (imu) position");
399 plotter.AddLine(times_, x, "x_hat(0)");
400 plotter.AddLine(times_, y, "x_hat(1)");
401 plotter.AddLine(times_, z, "x_hat(2)");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800402 plotter.Publish();
403
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800404 plotter.AddFigure("bot (imu) rotation");
405 plotter.AddLine(camera_times_, imu_rot_x_, "bot (imu) rot x");
406 plotter.AddLine(camera_times_, imu_rot_y_, "bot (imu) rot y");
407 plotter.AddLine(camera_times_, imu_rot_z_, "bot (imu) rot z");
408 plotter.Publish();
409
410 plotter.AddFigure("rotation error");
411 plotter.AddLine(camera_times_, rotation_error_x_, "Error x");
412 plotter.AddLine(camera_times_, rotation_error_y_, "Error y");
413 plotter.AddLine(camera_times_, rotation_error_z_, "Error z");
414 plotter.Publish();
415
416 plotter.AddFigure("translation error");
417 plotter.AddLine(camera_times_, translation_error_x_, "Error x");
418 plotter.AddLine(camera_times_, translation_error_y_, "Error y");
419 plotter.AddLine(camera_times_, translation_error_z_, "Error z");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800420 plotter.Publish();
421
422 plotter.AddFigure("imu");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800423 plotter.AddLine(imu_times_, imu_rate_x_, "imu gyro x");
424 plotter.AddLine(imu_times_, imu_rate_y_, "imu gyro y");
425 plotter.AddLine(imu_times_, imu_rate_z_, "imu gyro z");
426 plotter.AddLine(imu_times_, imu_accel_x_, "imu accel x");
427 plotter.AddLine(imu_times_, imu_accel_y_, "imu accel y");
428 plotter.AddLine(imu_times_, imu_accel_z_, "imu accel z");
429 plotter.AddLine(camera_times_, accel_minus_gravity_x_,
430 "accel_minus_gravity(0)");
431 plotter.AddLine(camera_times_, accel_minus_gravity_y_,
432 "accel_minus_gravity(1)");
433 plotter.AddLine(camera_times_, accel_minus_gravity_z_,
434 "accel_minus_gravity(2)");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800435 plotter.Publish();
436
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800437 plotter.AddFigure("raw camera observations");
438 plotter.AddLine(camera_times_, raw_camera_rot_x_, "Camera rot x");
439 plotter.AddLine(camera_times_, raw_camera_rot_y_, "Camera rot y");
440 plotter.AddLine(camera_times_, raw_camera_rot_z_, "Camera rot z");
441 plotter.AddLine(camera_times_, raw_camera_trans_x_, "Camera trans x");
442 plotter.AddLine(camera_times_, raw_camera_trans_y_, "Camera trans y");
443 plotter.AddLine(camera_times_, raw_camera_trans_z_, "Camera trans z");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800444 plotter.Publish();
445
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800446 plotter.AddFigure("xyz pos, vel estimates");
447 plotter.AddLine(times_, x, "x (x_hat(0))");
448 plotter.AddLine(times_, y, "y (x_hat(1))");
449 plotter.AddLine(times_, z, "z (x_hat(2))");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800450 plotter.AddLine(times_, vx, "vx");
451 plotter.AddLine(times_, vy, "vy");
452 plotter.AddLine(times_, vz, "vz");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800453 plotter.AddLine(camera_times_, imu_position_x_, "x pos from board");
454 plotter.AddLine(camera_times_, imu_position_y_, "y pos from board");
455 plotter.AddLine(camera_times_, imu_position_z_, "z pos from board");
Austin Schuhdcb6b362022-02-25 18:06:21 -0800456 plotter.Publish();
457
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800458 // If we've got 'em, plot 'em
459 if (turret_times_.size() > 0) {
460 plotter.AddFigure("Turret angle");
461 plotter.AddLine(turret_times_, turret_angles_, "turret angle");
462 plotter.Publish();
463 }
464
Austin Schuhdcb6b362022-02-25 18:06:21 -0800465 plotter.Spin();
466 }
467
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800468 void Visualize(const CalibrationParameters &calibration_parameters) {
469 // Set up virtual camera for visualization
470 VisualizeRobot vis_robot;
471
472 // Set virtual viewing point 10 meters above the origin, rotated so the
473 // camera faces straight down
474 Eigen::Translation3d camera_trans(0, 0, 10.0);
475 Eigen::AngleAxisd camera_rot(M_PI, Eigen::Vector3d::UnitX());
476 Eigen::Affine3d camera_viewpoint = camera_trans * camera_rot;
477 vis_robot.SetViewpoint(camera_viewpoint);
478
479 // Create camera with origin in center, and focal length suitable to fit
480 // robot visualization fully in view
481 int image_width = 500;
482 double focal_length = 1000.0;
483 double intr[] = {focal_length, 0.0, image_width / 2.0,
484 0.0, focal_length, image_width / 2.0,
485 0.0, 0.0, 1.0};
486 cv::Mat camera_mat = cv::Mat(3, 3, CV_64FC1, intr);
487 cv::Mat dist_coeffs = cv::Mat(1, 5, CV_64F, 0.0);
488 vis_robot.SetCameraParameters(camera_mat);
489 vis_robot.SetDistortionCoefficients(dist_coeffs);
490
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800491 uint current_state_index = 0;
492 uint current_turret_index = 0;
493 for (uint i = 0; i < camera_times_.size() - 1; i++) {
494 // reset image each frame
495 cv::Mat image_mat =
496 cv::Mat::zeros(cv::Size(image_width, image_width), CV_8UC3);
497 vis_robot.SetImage(image_mat);
498
499 // Jump to state closest to current camera_time
500 while (camera_times_[i] > times_[current_state_index] &&
501 current_state_index < times_.size()) {
502 current_state_index++;
503 }
504
505 // H_world_imu: map from world origin to imu (robot) frame
506 Eigen::Vector3d T_world_imu_vec =
507 x_hats_[current_state_index].block<3, 1>(0, 0);
508 Eigen::Translation3d T_world_imu(T_world_imu_vec);
509 Eigen::Affine3d H_world_imu =
510 T_world_imu * orientations_[current_state_index];
511
512 vis_robot.DrawFrameAxes(H_world_imu, "imu_kf");
513
514 // H_world_pivot: map from world origin to pivot point
515 // Do this via the imu (using H_world_pivot = H_world_imu * H_imu_pivot)
516 Eigen::Quaterniond R_imu_pivot(calibration_parameters.pivot_to_imu);
517 Eigen::Translation3d T_imu_pivot(
518 calibration_parameters.pivot_to_imu_translation);
519 Eigen::Affine3d H_imu_pivot = T_imu_pivot * R_imu_pivot;
520 Eigen::Affine3d H_world_pivot = H_world_imu * H_imu_pivot;
521 vis_robot.DrawFrameAxes(H_world_pivot, "pivot");
522
523 // Jump to turret sample closest to current camera_time
524 while (turret_times_.size() > 0 &&
525 camera_times_[i] > turret_times_[current_turret_index] &&
526 current_turret_index < turret_times_.size()) {
527 current_turret_index++;
528 }
529
530 // Draw the camera frame
531
532 Eigen::Affine3d H_imupivot_camerapivot(Eigen::Matrix4d::Identity());
533 if (turret_angles_.size() > 0) {
534 // Need to rotate by the turret angle in the middle of all this
535 H_imupivot_camerapivot = Eigen::Affine3d(Eigen::AngleAxisd(
536 turret_angles_[current_turret_index], Eigen::Vector3d::UnitZ()));
537 }
538
539 // H_world_camera: map from world origin to camera frame
540 // Via imu->pivot->pivot rotation
541 Eigen::Quaterniond R_camera_pivot(calibration_parameters.pivot_to_camera);
542 Eigen::Translation3d T_camera_pivot(
543 calibration_parameters.pivot_to_camera_translation);
544 Eigen::Affine3d H_camera_pivot = T_camera_pivot * R_camera_pivot;
545 Eigen::Affine3d H_world_camera = H_world_imu * H_imu_pivot *
546 H_imupivot_camerapivot *
547 H_camera_pivot.inverse();
548 vis_robot.DrawFrameAxes(H_world_camera, "camera");
549
550 // H_world_board: board location from world reference frame
551 // Uses the estimate from camera-> board, on top of H_world_camera
552 Eigen::Quaterniond R_camera_board(
553 frc971::controls::ToQuaternionFromRotationVector(
554 board_to_camera_rotations_[i]));
555 Eigen::Translation3d T_camera_board(board_to_camera_translations_[i]);
556 Eigen::Affine3d H_camera_board = T_camera_board * R_camera_board;
557 Eigen::Affine3d H_world_board = H_world_camera * H_camera_board;
558
559 vis_robot.DrawFrameAxes(H_world_board, "board est");
560
561 // H_world_board_solve: board in world frame based on solver
562 // Find world -> board via solved parameter of H_world_board
563 // (parameter "board_to_world" and assuming origin of board frame is
564 // coincident with origin of world frame, i.e., T_world_board == 0)
565 Eigen::Quaterniond R_world_board_solve(
566 calibration_parameters.board_to_world);
567 Eigen::Translation3d T_world_board_solve(Eigen::Vector3d(0, 0, 0));
568 Eigen::Affine3d H_world_board_solve =
569 T_world_board_solve * R_world_board_solve;
570
571 vis_robot.DrawFrameAxes(H_world_board_solve, "board_solve");
572
573 // H_world_imu_from_board: imu location in world frame, via the board
574 // Determine the imu location via the board_to_world solved
575 // transformation
576 Eigen::Affine3d H_world_imu_from_board =
577 H_world_board_solve * H_camera_board.inverse() * H_camera_pivot *
578 H_imupivot_camerapivot.inverse() * H_imu_pivot.inverse();
579
580 vis_robot.DrawFrameAxes(H_world_imu_from_board, "imu_board");
581
582 // These errors should match up with the residuals in the optimizer
583 // (Note: rotation seems to differ by sign, but that's OK in residual)
584 Eigen::Affine3d error = H_world_imu_from_board.inverse() * H_world_imu;
585 Eigen::Vector3d trans_error =
586 H_world_imu_from_board.translation() - H_world_imu.translation();
587 Eigen::Quaterniond error_rot(error.rotation());
588 VLOG(1) << "Error: \n"
589 << "Rotation: " << error_rot.coeffs().transpose() << "\n"
590 << "Translation: " << trans_error.transpose();
591
592 cv::imshow("Live", image_mat);
593 cv::waitKey(50);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800594 }
595 LOG(INFO) << "Finished visualizing robot. Press any key to continue";
596 cv::waitKey();
597 }
598
Austin Schuhdcb6b362022-02-25 18:06:21 -0800599 void ObserveIntegrated(distributed_clock::time_point t,
600 Eigen::Matrix<double, 6, 1> x_hat,
601 Eigen::Quaternion<double> orientation,
602 Eigen::Matrix<double, 6, 6> p) override {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800603 VLOG(2) << t << " -> " << p;
604 VLOG(2) << t << " xhat -> " << x_hat.transpose();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800605 times_.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
606 x_hats_.emplace_back(x_hat);
607 orientations_.emplace_back(orientation);
608 }
609
610 void ObserveIMUUpdate(
611 distributed_clock::time_point t,
612 std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800613 imu_times_.emplace_back(
614 chrono::duration<double>(t.time_since_epoch()).count());
615 imu_rate_x_.emplace_back(wa.first.x());
616 imu_rate_y_.emplace_back(wa.first.y());
617 imu_rate_z_.emplace_back(wa.first.z());
618 imu_accel_x_.emplace_back(wa.second.x());
619 imu_accel_y_.emplace_back(wa.second.y());
620 imu_accel_z_.emplace_back(wa.second.z());
Austin Schuhdcb6b362022-02-25 18:06:21 -0800621
622 last_accel_ = wa.second;
623 }
624
625 void ObserveCameraUpdate(distributed_clock::time_point t,
626 Eigen::Vector3d board_to_camera_rotation,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800627 Eigen::Vector3d board_to_camera_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800628 Eigen::Quaternion<double> imu_to_world_rotation,
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800629 Eigen::Affine3d imu_to_world,
630 double turret_angle) override {
631 board_to_camera_rotations_.emplace_back(board_to_camera_rotation);
632 board_to_camera_translations_.emplace_back(board_to_camera_translation);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800633
Austin Schuhcf848fc2022-02-25 21:34:18 -0800634 camera_times_.emplace_back(
635 chrono::duration<double>(t.time_since_epoch()).count());
Austin Schuhdcb6b362022-02-25 18:06:21 -0800636
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800637 raw_camera_rot_x_.emplace_back(board_to_camera_rotation(0, 0));
638 raw_camera_rot_y_.emplace_back(board_to_camera_rotation(1, 0));
639 raw_camera_rot_z_.emplace_back(board_to_camera_rotation(2, 0));
640
641 raw_camera_trans_x_.emplace_back(board_to_camera_translation(0, 0));
642 raw_camera_trans_y_.emplace_back(board_to_camera_translation(1, 0));
643 raw_camera_trans_z_.emplace_back(board_to_camera_translation(2, 0));
644
645 Eigen::Matrix<double, 3, 1> rotation_vector =
646 frc971::controls::ToRotationVectorFromQuaternion(imu_to_world_rotation);
647 imu_rot_x_.emplace_back(rotation_vector(0, 0));
648 imu_rot_y_.emplace_back(rotation_vector(1, 0));
649 imu_rot_z_.emplace_back(rotation_vector(2, 0));
650
651 Eigen::Matrix<double, 3, 1> rotation_error =
Austin Schuhdcb6b362022-02-25 18:06:21 -0800652 frc971::controls::ToRotationVectorFromQuaternion(
653 imu_to_world_rotation.inverse() * orientation());
654
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800655 rotation_error_x_.emplace_back(rotation_error(0, 0));
656 rotation_error_y_.emplace_back(rotation_error(1, 0));
657 rotation_error_z_.emplace_back(rotation_error(2, 0));
Austin Schuhdcb6b362022-02-25 18:06:21 -0800658
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800659 Eigen::Matrix<double, 3, 1> imu_pos = get_x_hat().block<3, 1>(0, 0);
660 Eigen::Translation3d T_world_imu(imu_pos);
661 Eigen::Affine3d H_world_imu = T_world_imu * orientation();
662 Eigen::Affine3d H_error = imu_to_world.inverse() * H_world_imu;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800663
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800664 Eigen::Matrix<double, 3, 1> translation_error = H_error.translation();
665 translation_error_x_.emplace_back(translation_error(0, 0));
666 translation_error_y_.emplace_back(translation_error(1, 0));
667 translation_error_z_.emplace_back(translation_error(2, 0));
668
669 const Eigen::Vector3d accel_minus_gravity =
Austin Schuhdcb6b362022-02-25 18:06:21 -0800670 imu_to_world_rotation * last_accel_ -
671 Eigen::Vector3d(0, 0, kGravity) * gravity_scalar();
672
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800673 accel_minus_gravity_x_.emplace_back(accel_minus_gravity.x());
674 accel_minus_gravity_y_.emplace_back(accel_minus_gravity.y());
675 accel_minus_gravity_z_.emplace_back(accel_minus_gravity.z());
Austin Schuhdcb6b362022-02-25 18:06:21 -0800676
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800677 const Eigen::Vector3d imu_position = imu_to_world * Eigen::Vector3d::Zero();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800678
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800679 imu_position_x_.emplace_back(imu_position.x());
680 imu_position_y_.emplace_back(imu_position.y());
681 imu_position_z_.emplace_back(imu_position.z());
682
683 turret_angles_from_camera_.emplace_back(turret_angle);
684 imu_to_world_save_.emplace_back(imu_to_world);
685 }
686
687 void ObserveTurretUpdate(distributed_clock::time_point t,
688 Eigen::Vector2d turret_state) override {
689 turret_times_.emplace_back(
690 chrono::duration<double>(t.time_since_epoch()).count());
691 turret_angles_.emplace_back(turret_state(0));
Austin Schuhdcb6b362022-02-25 18:06:21 -0800692 }
693
Austin Schuhcf848fc2022-02-25 21:34:18 -0800694 std::vector<double> camera_times_;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800695 std::vector<double> imu_rot_x_;
696 std::vector<double> imu_rot_y_;
697 std::vector<double> imu_rot_z_;
698 std::vector<double> raw_camera_rot_x_;
699 std::vector<double> raw_camera_rot_y_;
700 std::vector<double> raw_camera_rot_z_;
701 std::vector<double> raw_camera_trans_x_;
702 std::vector<double> raw_camera_trans_y_;
703 std::vector<double> raw_camera_trans_z_;
704 std::vector<double> rotation_error_x_;
705 std::vector<double> rotation_error_y_;
706 std::vector<double> rotation_error_z_;
707 std::vector<double> translation_error_x_;
708 std::vector<double> translation_error_y_;
709 std::vector<double> translation_error_z_;
710 std::vector<Eigen::Vector3d> board_to_camera_rotations_;
711 std::vector<Eigen::Vector3d> board_to_camera_translations_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800712
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800713 std::vector<double> turret_angles_from_camera_;
714 std::vector<Eigen::Affine3d> imu_to_world_save_;
715
716 std::vector<double> imu_position_x_;
717 std::vector<double> imu_position_y_;
718 std::vector<double> imu_position_z_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800719
Austin Schuhcf848fc2022-02-25 21:34:18 -0800720 std::vector<double> imu_times_;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800721 std::vector<double> imu_rate_x_;
722 std::vector<double> imu_rate_y_;
723 std::vector<double> imu_rate_z_;
724 std::vector<double> accel_minus_gravity_x_;
725 std::vector<double> accel_minus_gravity_y_;
726 std::vector<double> accel_minus_gravity_z_;
727 std::vector<double> imu_accel_x_;
728 std::vector<double> imu_accel_y_;
729 std::vector<double> imu_accel_z_;
730
731 std::vector<double> turret_times_;
732 std::vector<double> turret_angles_;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800733
734 std::vector<double> times_;
735 std::vector<Eigen::Matrix<double, 6, 1>> x_hats_;
736 std::vector<Eigen::Quaternion<double>> orientations_;
737
738 Eigen::Matrix<double, 3, 1> last_accel_ = Eigen::Matrix<double, 3, 1>::Zero();
739};
740
741// Adapter class from the KF above to a Ceres cost function.
742struct CostFunctor {
743 CostFunctor(const CalibrationData *d) : data(d) {}
744
745 const CalibrationData *data;
746
747 template <typename S>
Austin Schuh2895f4c2022-02-26 16:38:46 -0800748 bool operator()(const S *const initial_orientation_ptr,
749 const S *const pivot_to_camera_ptr,
750 const S *const pivot_to_imu_ptr, const S *const gyro_bias_ptr,
751 const S *const initial_state_ptr,
752 const S *const board_to_world_ptr,
753 const S *const pivot_to_camera_translation_ptr,
754 const S *const pivot_to_imu_translation_ptr,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800755 const S *const gravity_scalar_ptr,
756 const S *const accelerometer_bias_ptr, S *residual) const {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800757 const aos::monotonic_clock::time_point start_time =
758 aos::monotonic_clock::now();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800759 Eigen::Quaternion<S> initial_orientation(
760 initial_orientation_ptr[3], initial_orientation_ptr[0],
761 initial_orientation_ptr[1], initial_orientation_ptr[2]);
762 Eigen::Quaternion<S> pivot_to_camera(
763 pivot_to_camera_ptr[3], pivot_to_camera_ptr[0], pivot_to_camera_ptr[1],
764 pivot_to_camera_ptr[2]);
765 Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0],
766 pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]);
767 Eigen::Quaternion<S> board_to_world(
768 board_to_world_ptr[3], board_to_world_ptr[0], board_to_world_ptr[1],
769 board_to_world_ptr[2]);
770 Eigen::Matrix<S, 3, 1> gyro_bias(gyro_bias_ptr[0], gyro_bias_ptr[1],
771 gyro_bias_ptr[2]);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800772 Eigen::Matrix<S, 6, 1> initial_state;
Austin Schuh2895f4c2022-02-26 16:38:46 -0800773 initial_state(0) = initial_state_ptr[0];
774 initial_state(1) = initial_state_ptr[1];
775 initial_state(2) = initial_state_ptr[2];
776 initial_state(3) = initial_state_ptr[3];
777 initial_state(4) = initial_state_ptr[4];
778 initial_state(5) = initial_state_ptr[5];
779 Eigen::Matrix<S, 3, 1> pivot_to_camera_translation(
780 pivot_to_camera_translation_ptr[0], pivot_to_camera_translation_ptr[1],
781 pivot_to_camera_translation_ptr[2]);
782 Eigen::Matrix<S, 3, 1> pivot_to_imu_translation(
783 pivot_to_imu_translation_ptr[0], pivot_to_imu_translation_ptr[1],
784 pivot_to_imu_translation_ptr[2]);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800785 Eigen::Matrix<S, 3, 1> accelerometer_bias(accelerometer_bias_ptr[0],
786 accelerometer_bias_ptr[1],
787 accelerometer_bias_ptr[2]);
788
Austin Schuh2895f4c2022-02-26 16:38:46 -0800789 CeresPoseFilter<S> filter(
790 initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias,
791 initial_state, board_to_world, pivot_to_camera_translation,
792 pivot_to_imu_translation, *gravity_scalar_ptr, accelerometer_bias);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800793 data->ReviewData(&filter);
794
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800795 // Since the angular error scale is bounded by 1 (quaternion, so unit
796 // vector, scaled by sin(alpha)), I found it necessary to scale the
797 // angular error to have it properly balance with the translational error
798 double ang_error_scale = 5.0;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800799 for (size_t i = 0; i < filter.num_errors(); ++i) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800800 residual[3 * i + 0] = ang_error_scale * filter.errorx(i);
801 residual[3 * i + 1] = ang_error_scale * filter.errory(i);
802 residual[3 * i + 2] = ang_error_scale * filter.errorz(i);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800803 }
804
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800805 double trans_error_scale = 1.0;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800806 for (size_t i = 0; i < filter.num_perrors(); ++i) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800807 residual[3 * filter.num_errors() + 3 * i + 0] =
808 trans_error_scale * filter.errorpx(i);
809 residual[3 * filter.num_errors() + 3 * i + 1] =
810 trans_error_scale * filter.errorpy(i);
811 residual[3 * filter.num_errors() + 3 * i + 2] =
812 trans_error_scale * filter.errorpz(i);
Austin Schuhdcb6b362022-02-25 18:06:21 -0800813 }
814
Jim Ostrowski86203682023-02-22 19:43:10 -0800815 VLOG(2) << "Cost function calc took "
816 << chrono::duration<double>(aos::monotonic_clock::now() -
817 start_time)
818 .count()
819 << " seconds";
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800820
Austin Schuhdcb6b362022-02-25 18:06:21 -0800821 return true;
822 }
823};
824
James Kuszmaul086d0192023-02-11 15:35:03 -0800825std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H) {
826 std::vector<float> data;
827 for (int row = 0; row < 4; ++row) {
828 for (int col = 0; col < 4; ++col) {
829 data.push_back(H(row, col));
830 }
831 }
832 return data;
833}
834
835aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> Solve(
836 const CalibrationData &data,
837 CalibrationParameters *calibration_parameters) {
Austin Schuhdcb6b362022-02-25 18:06:21 -0800838 ceres::Problem problem;
839
840 ceres::EigenQuaternionParameterization *quaternion_local_parameterization =
841 new ceres::EigenQuaternionParameterization();
842 // Set up the only cost function (also known as residual). This uses
843 // auto-differentiation to obtain the derivative (jacobian).
844
Austin Schuh2895f4c2022-02-26 16:38:46 -0800845 {
846 ceres::CostFunction *cost_function =
847 new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 4, 3,
848 6, 4, 3, 3, 1, 3>(
849 new CostFunctor(&data), data.camera_samples_size() * 6);
850 problem.AddResidualBlock(
851 cost_function, new ceres::HuberLoss(1.0),
852 calibration_parameters->initial_orientation.coeffs().data(),
853 calibration_parameters->pivot_to_camera.coeffs().data(),
854 calibration_parameters->pivot_to_imu.coeffs().data(),
855 calibration_parameters->gyro_bias.data(),
856 calibration_parameters->initial_state.data(),
857 calibration_parameters->board_to_world.coeffs().data(),
858 calibration_parameters->pivot_to_camera_translation.data(),
859 calibration_parameters->pivot_to_imu_translation.data(),
860 &calibration_parameters->gravity_scalar,
861 calibration_parameters->accelerometer_bias.data());
862 }
863
Jim Ostrowski86203682023-02-22 19:43:10 -0800864 if (calibration_parameters->has_pivot) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800865 // The turret's Z rotation is redundant with the camera's mounting z
866 // rotation since it's along the rotation axis.
Austin Schuh2895f4c2022-02-26 16:38:46 -0800867 ceres::CostFunction *turret_z_cost_function =
868 new ceres::AutoDiffCostFunction<PenalizeQuaternionZ, 1, 4>(
869 new PenalizeQuaternionZ());
870 problem.AddResidualBlock(
871 turret_z_cost_function, nullptr,
872 calibration_parameters->pivot_to_imu.coeffs().data());
873 }
874
875 if (calibration_parameters->has_pivot) {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800876 // Constrain Z since it's along the rotation axis and therefore
877 // redundant.
Austin Schuh2895f4c2022-02-26 16:38:46 -0800878 problem.SetParameterization(
879 calibration_parameters->pivot_to_imu_translation.data(),
880 new ceres::SubsetParameterization(3, {2}));
881 } else {
882 problem.SetParameterBlockConstant(
883 calibration_parameters->pivot_to_imu.coeffs().data());
884 problem.SetParameterBlockConstant(
885 calibration_parameters->pivot_to_imu_translation.data());
886 }
887
Jim Ostrowski86203682023-02-22 19:43:10 -0800888 {
889 // The board rotation in z is a bit arbitrary, so hoping to limit it to
890 // increase repeatability
891 ceres::CostFunction *board_z_cost_function =
892 new ceres::AutoDiffCostFunction<PenalizeQuaternionZ, 1, 4>(
893 new PenalizeQuaternionZ());
894 problem.AddResidualBlock(
895 board_z_cost_function, nullptr,
896 calibration_parameters->board_to_world.coeffs().data());
897 }
898
Austin Schuhdcb6b362022-02-25 18:06:21 -0800899 problem.SetParameterization(
900 calibration_parameters->initial_orientation.coeffs().data(),
901 quaternion_local_parameterization);
902 problem.SetParameterization(
Austin Schuh2895f4c2022-02-26 16:38:46 -0800903 calibration_parameters->pivot_to_camera.coeffs().data(),
Austin Schuhdcb6b362022-02-25 18:06:21 -0800904 quaternion_local_parameterization);
905 problem.SetParameterization(
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800906 calibration_parameters->pivot_to_imu.coeffs().data(),
907 quaternion_local_parameterization);
908 problem.SetParameterization(
Austin Schuhdcb6b362022-02-25 18:06:21 -0800909 calibration_parameters->board_to_world.coeffs().data(),
910 quaternion_local_parameterization);
911 for (int i = 0; i < 3; ++i) {
912 problem.SetParameterLowerBound(calibration_parameters->gyro_bias.data(), i,
913 -0.05);
914 problem.SetParameterUpperBound(calibration_parameters->gyro_bias.data(), i,
915 0.05);
916 problem.SetParameterLowerBound(
917 calibration_parameters->accelerometer_bias.data(), i, -0.05);
918 problem.SetParameterUpperBound(
919 calibration_parameters->accelerometer_bias.data(), i, 0.05);
920 }
921 problem.SetParameterLowerBound(&calibration_parameters->gravity_scalar, 0,
922 0.95);
923 problem.SetParameterUpperBound(&calibration_parameters->gravity_scalar, 0,
924 1.05);
925
926 // Run the solver!
927 ceres::Solver::Options options;
928 options.minimizer_progress_to_stdout = true;
Jim Ostrowski86203682023-02-22 19:43:10 -0800929 options.gradient_tolerance = 1e-6;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800930 options.function_tolerance = 1e-6;
Jim Ostrowski86203682023-02-22 19:43:10 -0800931 options.parameter_tolerance = 1e-6;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800932 ceres::Solver::Summary summary;
933 Solve(options, &problem, &summary);
934 LOG(INFO) << summary.FullReport();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800935 LOG(INFO) << "Solution is " << (summary.IsSolutionUsable() ? "" : "NOT ")
936 << "usable";
James Kuszmaul086d0192023-02-11 15:35:03 -0800937
938 {
939 flatbuffers::FlatBufferBuilder fbb;
940 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
941 fbb.CreateVector(MatrixToVector(
942 (Eigen::Translation3d(
943 calibration_parameters->pivot_to_camera_translation) *
944 Eigen::Quaterniond(calibration_parameters->pivot_to_camera))
945 .inverse()
946 .matrix()));
947 calibration::TransformationMatrix::Builder matrix_builder(fbb);
948 matrix_builder.add_data(data_offset);
949 flatbuffers::Offset<calibration::TransformationMatrix>
950 camera_to_pivot_offset = matrix_builder.Finish();
951
952 flatbuffers::Offset<calibration::TransformationMatrix> pivot_to_imu_offset;
953 if (calibration_parameters->has_pivot) {
954 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
955 fbb.CreateVector(MatrixToVector(
956 (Eigen::Translation3d(
957 calibration_parameters->pivot_to_imu_translation) *
958 Eigen::Quaterniond(calibration_parameters->pivot_to_imu))
959 .matrix()));
960 calibration::TransformationMatrix::Builder matrix_builder(fbb);
961 matrix_builder.add_data(data_offset);
962 pivot_to_imu_offset = matrix_builder.Finish();
963 }
964
965 calibration::CameraCalibration::Builder calibration_builder(fbb);
966 if (calibration_parameters->has_pivot) {
967 calibration_builder.add_fixed_extrinsics(pivot_to_imu_offset);
968 calibration_builder.add_turret_extrinsics(camera_to_pivot_offset);
969 } else {
970 calibration_builder.add_fixed_extrinsics(camera_to_pivot_offset);
971 }
972 fbb.Finish(calibration_builder.Finish());
973 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> extrinsics =
974 fbb.Release();
975 return extrinsics;
976 }
Austin Schuhdcb6b362022-02-25 18:06:21 -0800977}
978
979void Plot(const CalibrationData &data,
980 const CalibrationParameters &calibration_parameters) {
981 PoseFilter filter(calibration_parameters.initial_orientation,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800982 calibration_parameters.pivot_to_camera,
983 calibration_parameters.pivot_to_imu,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800984 calibration_parameters.gyro_bias,
985 calibration_parameters.initial_state,
986 calibration_parameters.board_to_world,
Austin Schuh2895f4c2022-02-26 16:38:46 -0800987 calibration_parameters.pivot_to_camera_translation,
988 calibration_parameters.pivot_to_imu_translation,
Austin Schuhdcb6b362022-02-25 18:06:21 -0800989 calibration_parameters.gravity_scalar,
990 calibration_parameters.accelerometer_bias);
991 data.ReviewData(&filter);
992 filter.Plot();
993}
994
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800995void Visualize(const CalibrationData &data,
996 const CalibrationParameters &calibration_parameters) {
997 PoseFilter filter(calibration_parameters.initial_orientation,
998 calibration_parameters.pivot_to_camera,
999 calibration_parameters.pivot_to_imu,
1000 calibration_parameters.gyro_bias,
1001 calibration_parameters.initial_state,
1002 calibration_parameters.board_to_world,
1003 calibration_parameters.pivot_to_camera_translation,
1004 calibration_parameters.pivot_to_imu_translation,
1005 calibration_parameters.gravity_scalar,
1006 calibration_parameters.accelerometer_bias);
1007 data.ReviewData(&filter);
1008 filter.Visualize(calibration_parameters);
1009}
1010
Austin Schuhdcb6b362022-02-25 18:06:21 -08001011} // namespace vision
1012} // namespace frc971