blob: 5f08527e818ebcb217a6cb102e89357e9589be06 [file] [log] [blame]
Austin Schuhbb4aae72021-10-08 22:12:25 -07001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3
Austin Schuhbb4aae72021-10-08 22:12:25 -07004#include "absl/strings/str_format.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07005#include "aos/events/logging/log_reader.h"
6#include "aos/events/shm_event_loop.h"
7#include "aos/init.h"
8#include "aos/network/team_number.h"
9#include "aos/time/time.h"
10#include "aos/util/file.h"
milind-ue53bf552021-12-11 14:42:00 -080011#include "ceres/ceres.h"
12#include "frc971/analysis/in_process_plotter.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070013#include "frc971/control_loops/drivetrain/improved_down_estimator.h"
milind-u8c72d532021-12-11 15:02:42 -080014#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080015#include "frc971/vision/vision_generated.h"
milind-u8c72d532021-12-11 15:02:42 -080016#include "frc971/wpilib/imu_batch_generated.h"
17#include "y2020/vision/calibration_accumulator.h"
18#include "y2020/vision/charuco_lib.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070019#include "y2020/vision/sift/sift_generated.h"
20#include "y2020/vision/sift/sift_training_generated.h"
21#include "y2020/vision/tools/python_code/sift_training_data.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070022
Austin Schuhc5fa6d92022-02-25 14:36:28 -080023DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070024DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
milind-u0084be62021-12-27 12:29:38 +053025DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070026
27namespace frc971 {
28namespace vision {
29namespace chrono = std::chrono;
30using aos::distributed_clock;
31using aos::monotonic_clock;
32
Austin Schuh5b379072021-12-26 16:01:04 -080033constexpr double kGravity = 9.8;
34
milind-ue53bf552021-12-11 14:42:00 -080035// The basic ideas here are taken from Kalibr.
36// (https://github.com/ethz-asl/kalibr), but adapted to work with AOS, and to be
37// simpler.
38//
39// Camera readings and IMU readings come in at different times, on different
40// time scales. Our first problem is to align them in time so we can actually
41// compute an error. This is done in the calibration accumulator code. The
42// kalibr paper uses splines, while this uses kalman filters to solve the same
43// interpolation problem so we can get the expected vs actual pose at the time
44// each image arrives.
45//
46// The cost function is then fed the computed angular and positional error for
47// each camera sample before the kalman filter update. Intuitively, the smaller
48// the corrections to the kalman filter each step, the better the estimate
49// should be.
50//
51// We don't actually implement the angular kalman filter because the IMU is so
52// good. We give the solver an initial position and bias, and let it solve from
53// there. This lets us represent drift that is linear in time, which should be
54// good enough for ~1 minute calibration.
55//
56// TODO(austin): Kalman smoother ala
57// https://stanford.edu/~boyd/papers/pdf/auto_ks.pdf should allow for better
58// parallelism, and since we aren't causal, will take that into account a lot
59// better.
60
61// This class takes the initial parameters and biases, and computes the error
62// between the measured and expected camera readings. When optimized, this
63// gives us a cost function to minimize.
64template <typename Scalar>
65class CeresPoseFilter : public CalibrationDataObserver {
Austin Schuhbb4aae72021-10-08 22:12:25 -070066 public:
Austin Schuh5b379072021-12-26 16:01:04 -080067 typedef Eigen::Transform<Scalar, 3, Eigen::Affine> Affine3s;
68
milind-ue53bf552021-12-11 14:42:00 -080069 CeresPoseFilter(Eigen::Quaternion<Scalar> initial_orientation,
70 Eigen::Quaternion<Scalar> imu_to_camera,
Austin Schuh5b379072021-12-26 16:01:04 -080071 Eigen::Matrix<Scalar, 3, 1> gyro_bias,
72 Eigen::Matrix<Scalar, 6, 1> initial_state,
73 Eigen::Quaternion<Scalar> board_to_world,
74 Eigen::Matrix<Scalar, 3, 1> imu_to_camera_translation,
75 Scalar gravity_scalar,
76 Eigen::Matrix<Scalar, 3, 1> accelerometer_bias)
milind-u8c72d532021-12-11 15:02:42 -080077 : accel_(Eigen::Matrix<double, 3, 1>::Zero()),
78 omega_(Eigen::Matrix<double, 3, 1>::Zero()),
Austin Schuh5b379072021-12-26 16:01:04 -080079 imu_bias_(gyro_bias),
milind-ue53bf552021-12-11 14:42:00 -080080 orientation_(initial_orientation),
Austin Schuh5b379072021-12-26 16:01:04 -080081 x_hat_(initial_state),
milind-ue53bf552021-12-11 14:42:00 -080082 p_(Eigen::Matrix<Scalar, 6, 6>::Zero()),
Austin Schuh5b379072021-12-26 16:01:04 -080083 imu_to_camera_rotation_(imu_to_camera),
84 imu_to_camera_translation_(imu_to_camera_translation),
85 board_to_world_(board_to_world),
86 gravity_scalar_(gravity_scalar),
87 accelerometer_bias_(accelerometer_bias) {}
milind-ue53bf552021-12-11 14:42:00 -080088
Austin Schuh5b379072021-12-26 16:01:04 -080089 Scalar gravity_scalar() { return gravity_scalar_; }
Austin Schuhbb4aae72021-10-08 22:12:25 -070090
Austin Schuh5b379072021-12-26 16:01:04 -080091 virtual void ObserveCameraUpdate(
92 distributed_clock::time_point /*t*/,
93 Eigen::Vector3d /*board_to_camera_rotation*/,
94 Eigen::Quaternion<Scalar> /*imu_to_world_rotation*/,
95 Affine3s /*imu_to_world*/) {}
96
97 // Observes a camera measurement by applying a kalman filter correction and
98 // accumulating up the error associated with the step.
Austin Schuhbb4aae72021-10-08 22:12:25 -070099 void UpdateCamera(distributed_clock::time_point t,
milind-u8c72d532021-12-11 15:02:42 -0800100 std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) override {
101 Integrate(t);
milind-ue53bf552021-12-11 14:42:00 -0800102
Austin Schuh5b379072021-12-26 16:01:04 -0800103 const Eigen::Quaternion<Scalar> board_to_camera_rotation(
milind-ue53bf552021-12-11 14:42:00 -0800104 frc971::controls::ToQuaternionFromRotationVector(rt.first)
105 .cast<Scalar>());
Austin Schuh5b379072021-12-26 16:01:04 -0800106 const Affine3s board_to_camera =
107 Eigen::Translation3d(rt.second).cast<Scalar>() *
108 board_to_camera_rotation;
109
110 const Affine3s imu_to_camera =
111 imu_to_camera_translation_ * imu_to_camera_rotation_;
milind-ue53bf552021-12-11 14:42:00 -0800112
113 // This converts us from (facing the board),
114 // x right, y up, z towards us -> x right, y away, z up.
115 // Confirmed to be right.
milind-ue53bf552021-12-11 14:42:00 -0800116
117 // Want world -> imu rotation.
118 // world <- board <- camera <- imu.
Austin Schuh5b379072021-12-26 16:01:04 -0800119 const Eigen::Quaternion<Scalar> imu_to_world_rotation =
120 board_to_world_ * board_to_camera_rotation.inverse() *
121 imu_to_camera_rotation_;
milind-ue53bf552021-12-11 14:42:00 -0800122
Austin Schuh5b379072021-12-26 16:01:04 -0800123 const Affine3s imu_to_world =
124 board_to_world_ * board_to_camera.inverse() * imu_to_camera;
125
126 const Eigen::Matrix<Scalar, 3, 1> z =
127 imu_to_world * Eigen::Matrix<Scalar, 3, 1>::Zero();
128
129 Eigen::Matrix<Scalar, 3, 6> H = Eigen::Matrix<Scalar, 3, 6>::Zero();
130 H(0, 0) = static_cast<Scalar>(1.0);
131 H(1, 1) = static_cast<Scalar>(1.0);
132 H(2, 2) = static_cast<Scalar>(1.0);
133 const Eigen::Matrix<Scalar, 3, 1> y = z - H * x_hat_;
134
135 const Eigen::Matrix<double, 3, 3> R =
136 (::Eigen::DiagonalMatrix<double, 3>().diagonal() << ::std::pow(0.01, 2),
137 ::std::pow(0.01, 2), ::std::pow(0.01, 2))
138 .finished()
139 .asDiagonal();
140
141 const Eigen::Matrix<Scalar, 3, 3> S =
142 H * p_ * H.transpose() + R.cast<Scalar>();
143 const Eigen::Matrix<Scalar, 6, 3> K = p_ * H.transpose() * S.inverse();
144
145 x_hat_ += K * y;
146 p_ = (Eigen::Matrix<Scalar, 6, 6>::Identity() - K * H) * p_;
147
148 const Eigen::Quaternion<Scalar> error(imu_to_world_rotation.inverse() *
milind-ue53bf552021-12-11 14:42:00 -0800149 orientation());
150
151 errors_.emplace_back(
152 Eigen::Matrix<Scalar, 3, 1>(error.x(), error.y(), error.z()));
Austin Schuh5b379072021-12-26 16:01:04 -0800153 position_errors_.emplace_back(y);
milind-ue53bf552021-12-11 14:42:00 -0800154
Austin Schuh5b379072021-12-26 16:01:04 -0800155 ObserveCameraUpdate(t, rt.first, imu_to_world_rotation, imu_to_world);
Austin Schuhbb4aae72021-10-08 22:12:25 -0700156 }
157
milind-ue53bf552021-12-11 14:42:00 -0800158 virtual void ObserveIMUUpdate(
159 distributed_clock::time_point /*t*/,
160 std::pair<Eigen::Vector3d, Eigen::Vector3d> /*wa*/) {}
161
Austin Schuhbb4aae72021-10-08 22:12:25 -0700162 void UpdateIMU(distributed_clock::time_point t,
milind-u8c72d532021-12-11 15:02:42 -0800163 std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override {
164 Integrate(t);
165 omega_ = wa.first;
166 accel_ = wa.second;
milind-ue53bf552021-12-11 14:42:00 -0800167
168 ObserveIMUUpdate(t, wa);
Austin Schuhbb4aae72021-10-08 22:12:25 -0700169 }
170
milind-ue53bf552021-12-11 14:42:00 -0800171 const Eigen::Quaternion<Scalar> &orientation() const { return orientation_; }
172
milind-ue53bf552021-12-11 14:42:00 -0800173 size_t num_errors() const { return errors_.size(); }
174 Scalar errorx(size_t i) const { return errors_[i].x(); }
175 Scalar errory(size_t i) const { return errors_[i].y(); }
176 Scalar errorz(size_t i) const { return errors_[i].z(); }
177
Austin Schuh5b379072021-12-26 16:01:04 -0800178 size_t num_perrors() const { return position_errors_.size(); }
179 Scalar errorpx(size_t i) const { return position_errors_[i].x(); }
180 Scalar errorpy(size_t i) const { return position_errors_[i].y(); }
181 Scalar errorpz(size_t i) const { return position_errors_[i].z(); }
182
Austin Schuhbb4aae72021-10-08 22:12:25 -0700183 private:
milind-ue53bf552021-12-11 14:42:00 -0800184 Eigen::Matrix<Scalar, 46, 1> Pack(Eigen::Quaternion<Scalar> q,
185 Eigen::Matrix<Scalar, 6, 1> x_hat,
186 Eigen::Matrix<Scalar, 6, 6> p) {
187 Eigen::Matrix<Scalar, 46, 1> result = Eigen::Matrix<Scalar, 46, 1>::Zero();
188 result.template block<4, 1>(0, 0) = q.coeffs();
189 result.template block<6, 1>(4, 0) = x_hat;
190 result.template block<36, 1>(10, 0) =
Jim Ostrowski977850f2022-01-22 21:04:22 -0800191 Eigen::Map<Eigen::Matrix<Scalar, 36, 1>>(p.data(), p.size());
milind-ue53bf552021-12-11 14:42:00 -0800192
193 return result;
194 }
195
196 std::tuple<Eigen::Quaternion<Scalar>, Eigen::Matrix<Scalar, 6, 1>,
Jim Ostrowski977850f2022-01-22 21:04:22 -0800197 Eigen::Matrix<Scalar, 6, 6>>
milind-ue53bf552021-12-11 14:42:00 -0800198 UnPack(Eigen::Matrix<Scalar, 46, 1> input) {
199 Eigen::Quaternion<Scalar> q(input.template block<4, 1>(0, 0));
200 Eigen::Matrix<Scalar, 6, 1> x_hat(input.template block<6, 1>(4, 0));
201 Eigen::Matrix<Scalar, 6, 6> p =
Jim Ostrowski977850f2022-01-22 21:04:22 -0800202 Eigen::Map<Eigen::Matrix<Scalar, 6, 6>>(input.data() + 10, 6, 6);
milind-ue53bf552021-12-11 14:42:00 -0800203 return std::make_tuple(q, x_hat, p);
204 }
205
Austin Schuh5b379072021-12-26 16:01:04 -0800206 Eigen::Matrix<Scalar, 46, 1> Derivative(
milind-ue53bf552021-12-11 14:42:00 -0800207 const Eigen::Matrix<Scalar, 46, 1> &input) {
208 auto [q, x_hat, p] = UnPack(input);
209
210 Eigen::Quaternion<Scalar> omega_q;
211 omega_q.w() = Scalar(0.0);
212 omega_q.vec() = 0.5 * (omega_.cast<Scalar>() - imu_bias_);
213 Eigen::Matrix<Scalar, 4, 1> q_dot = (q * omega_q).coeffs();
214
Austin Schuh5b379072021-12-26 16:01:04 -0800215 Eigen::Matrix<double, 6, 6> A = Eigen::Matrix<double, 6, 6>::Zero();
216 A(0, 3) = 1.0;
217 A(1, 4) = 1.0;
218 A(2, 5) = 1.0;
milind-ue53bf552021-12-11 14:42:00 -0800219
Austin Schuh5b379072021-12-26 16:01:04 -0800220 Eigen::Matrix<Scalar, 6, 1> x_hat_dot = A * x_hat;
221 x_hat_dot.template block<3, 1>(3, 0) =
222 orientation() * (accel_.cast<Scalar>() - accelerometer_bias_) -
223 Eigen::Vector3d(0, 0, kGravity).cast<Scalar>() * gravity_scalar_;
224
225 // Initialize the position noise to 0. If the solver is going to back-solve
226 // for the most likely starting position, let's just say that the noise is
227 // small.
228 constexpr double kPositionNoise = 0.0;
229 constexpr double kAccelerometerNoise = 2.3e-6 * 9.8;
230 constexpr double kIMUdt = 5.0e-4;
231 Eigen::Matrix<double, 6, 6> Q_dot(
232 (::Eigen::DiagonalMatrix<double, 6>().diagonal()
233 << ::std::pow(kPositionNoise, 2) / kIMUdt,
234 ::std::pow(kPositionNoise, 2) / kIMUdt,
235 ::std::pow(kPositionNoise, 2) / kIMUdt,
236 ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
237 ::std::pow(kAccelerometerNoise, 2) / kIMUdt,
238 ::std::pow(kAccelerometerNoise, 2) / kIMUdt)
239 .finished()
240 .asDiagonal());
241 Eigen::Matrix<Scalar, 6, 6> p_dot = A.cast<Scalar>() * p +
242 p * A.transpose().cast<Scalar>() +
243 Q_dot.cast<Scalar>();
milind-ue53bf552021-12-11 14:42:00 -0800244
245 return Pack(Eigen::Quaternion<Scalar>(q_dot), x_hat_dot, p_dot);
246 }
247
248 virtual void ObserveIntegrated(distributed_clock::time_point /*t*/,
249 Eigen::Matrix<Scalar, 6, 1> /*x_hat*/,
Austin Schuh5b379072021-12-26 16:01:04 -0800250 Eigen::Quaternion<Scalar> /*orientation*/,
251 Eigen::Matrix<Scalar, 6, 6> /*p*/) {}
milind-ue53bf552021-12-11 14:42:00 -0800252
253 void Integrate(distributed_clock::time_point t) {
254 if (last_time_ != distributed_clock::min_time) {
255 Eigen::Matrix<Scalar, 46, 1> next = control_loops::RungeKutta(
Austin Schuh5b379072021-12-26 16:01:04 -0800256 [this](auto r) { return Derivative(r); },
milind-ue53bf552021-12-11 14:42:00 -0800257 Pack(orientation_, x_hat_, p_),
258 aos::time::DurationInSeconds(t - last_time_));
259
260 std::tie(orientation_, x_hat_, p_) = UnPack(next);
261
262 // Normalize q so it doesn't drift.
263 orientation_.normalize();
264 }
265
266 last_time_ = t;
Austin Schuh5b379072021-12-26 16:01:04 -0800267 ObserveIntegrated(t, x_hat_, orientation_, p_);
milind-ue53bf552021-12-11 14:42:00 -0800268 }
milind-u8c72d532021-12-11 15:02:42 -0800269
270 Eigen::Matrix<double, 3, 1> accel_;
271 Eigen::Matrix<double, 3, 1> omega_;
milind-ue53bf552021-12-11 14:42:00 -0800272 Eigen::Matrix<Scalar, 3, 1> imu_bias_;
milind-u8c72d532021-12-11 15:02:42 -0800273
Austin Schuh5b379072021-12-26 16:01:04 -0800274 // IMU -> world quaternion
milind-ue53bf552021-12-11 14:42:00 -0800275 Eigen::Quaternion<Scalar> orientation_;
276 Eigen::Matrix<Scalar, 6, 1> x_hat_;
277 Eigen::Matrix<Scalar, 6, 6> p_;
278 distributed_clock::time_point last_time_ = distributed_clock::min_time;
Austin Schuhbb4aae72021-10-08 22:12:25 -0700279
Austin Schuh5b379072021-12-26 16:01:04 -0800280 Eigen::Quaternion<Scalar> imu_to_camera_rotation_;
281 Eigen::Translation<Scalar, 3> imu_to_camera_translation_ =
282 Eigen::Translation3d(0, 0, 0).cast<Scalar>();
milind-ue53bf552021-12-11 14:42:00 -0800283
Austin Schuh5b379072021-12-26 16:01:04 -0800284 Eigen::Quaternion<Scalar> board_to_world_;
285 Scalar gravity_scalar_;
286 Eigen::Matrix<Scalar, 3, 1> accelerometer_bias_;
Austin Schuhbb4aae72021-10-08 22:12:25 -0700287 // States:
288 // xyz position
289 // xyz velocity
Austin Schuhbb4aae72021-10-08 22:12:25 -0700290 //
291 // Inputs
292 // xyz accel
Austin Schuhbb4aae72021-10-08 22:12:25 -0700293 //
294 // Measurement:
Austin Schuh5b379072021-12-26 16:01:04 -0800295 // xyz position from camera.
296 //
297 // Since the gyro is so good, we can just solve for the bias and initial
298 // position with the solver and see what it learns.
299
300 // Returns the angular errors for each camera sample.
301 std::vector<Eigen::Matrix<Scalar, 3, 1>> errors_;
302 std::vector<Eigen::Matrix<Scalar, 3, 1>> position_errors_;
Austin Schuhbb4aae72021-10-08 22:12:25 -0700303};
304
milind-ue53bf552021-12-11 14:42:00 -0800305// Subclass of the filter above which has plotting. This keeps debug code and
306// actual code separate.
307class PoseFilter : public CeresPoseFilter<double> {
308 public:
309 PoseFilter(Eigen::Quaternion<double> initial_orientation,
310 Eigen::Quaternion<double> imu_to_camera,
Austin Schuh5b379072021-12-26 16:01:04 -0800311 Eigen::Matrix<double, 3, 1> gyro_bias,
312 Eigen::Matrix<double, 6, 1> initial_state,
313 Eigen::Quaternion<double> board_to_world,
314 Eigen::Matrix<double, 3, 1> imu_to_camera_translation,
315 double gravity_scalar,
316 Eigen::Matrix<double, 3, 1> accelerometer_bias)
317 : CeresPoseFilter<double>(initial_orientation, imu_to_camera, gyro_bias,
318 initial_state, board_to_world,
319 imu_to_camera_translation, gravity_scalar,
320 accelerometer_bias) {}
milind-ue53bf552021-12-11 14:42:00 -0800321
322 void Plot() {
Austin Schuh5b379072021-12-26 16:01:04 -0800323 std::vector<double> rx;
324 std::vector<double> ry;
325 std::vector<double> rz;
milind-ue53bf552021-12-11 14:42:00 -0800326 std::vector<double> x;
327 std::vector<double> y;
328 std::vector<double> z;
Austin Schuh5b379072021-12-26 16:01:04 -0800329 std::vector<double> vx;
330 std::vector<double> vy;
331 std::vector<double> vz;
milind-ue53bf552021-12-11 14:42:00 -0800332 for (const Eigen::Quaternion<double> &q : orientations_) {
333 Eigen::Matrix<double, 3, 1> rotation_vector =
334 frc971::controls::ToRotationVectorFromQuaternion(q);
Austin Schuh5b379072021-12-26 16:01:04 -0800335 rx.emplace_back(rotation_vector(0, 0));
336 ry.emplace_back(rotation_vector(1, 0));
337 rz.emplace_back(rotation_vector(2, 0));
milind-ue53bf552021-12-11 14:42:00 -0800338 }
Austin Schuh5b379072021-12-26 16:01:04 -0800339 for (const Eigen::Matrix<double, 6, 1> &x_hat : x_hats_) {
340 x.emplace_back(x_hat(0));
341 y.emplace_back(x_hat(1));
342 z.emplace_back(x_hat(2));
343 vx.emplace_back(x_hat(3));
344 vy.emplace_back(x_hat(4));
345 vz.emplace_back(x_hat(5));
346 }
347
milind-ue53bf552021-12-11 14:42:00 -0800348 frc971::analysis::Plotter plotter;
349 plotter.AddFigure("position");
Austin Schuh5b379072021-12-26 16:01:04 -0800350 plotter.AddLine(times_, rx, "x_hat(0)");
351 plotter.AddLine(times_, ry, "x_hat(1)");
352 plotter.AddLine(times_, rz, "x_hat(2)");
milind-ue53bf552021-12-11 14:42:00 -0800353 plotter.AddLine(ct, cx, "Camera x");
354 plotter.AddLine(ct, cy, "Camera y");
355 plotter.AddLine(ct, cz, "Camera z");
356 plotter.AddLine(ct, cerrx, "Camera error x");
357 plotter.AddLine(ct, cerry, "Camera error y");
358 plotter.AddLine(ct, cerrz, "Camera error z");
359 plotter.Publish();
360
361 plotter.AddFigure("error");
Austin Schuh5b379072021-12-26 16:01:04 -0800362 plotter.AddLine(times_, rx, "x_hat(0)");
363 plotter.AddLine(times_, ry, "x_hat(1)");
364 plotter.AddLine(times_, rz, "x_hat(2)");
milind-ue53bf552021-12-11 14:42:00 -0800365 plotter.AddLine(ct, cerrx, "Camera error x");
366 plotter.AddLine(ct, cerry, "Camera error y");
367 plotter.AddLine(ct, cerrz, "Camera error z");
368 plotter.Publish();
369
370 plotter.AddFigure("imu");
371 plotter.AddLine(ct, world_gravity_x, "world_gravity(0)");
372 plotter.AddLine(ct, world_gravity_y, "world_gravity(1)");
373 plotter.AddLine(ct, world_gravity_z, "world_gravity(2)");
374 plotter.AddLine(imut, imu_x, "imu x");
375 plotter.AddLine(imut, imu_y, "imu y");
376 plotter.AddLine(imut, imu_z, "imu z");
Austin Schuh5b379072021-12-26 16:01:04 -0800377 plotter.AddLine(times_, rx, "rotation x");
378 plotter.AddLine(times_, ry, "rotation y");
379 plotter.AddLine(times_, rz, "rotation z");
milind-ue53bf552021-12-11 14:42:00 -0800380 plotter.Publish();
381
382 plotter.AddFigure("raw");
383 plotter.AddLine(imut, imu_x, "imu x");
384 plotter.AddLine(imut, imu_y, "imu y");
385 plotter.AddLine(imut, imu_z, "imu z");
386 plotter.AddLine(imut, imu_ratex, "omega x");
387 plotter.AddLine(imut, imu_ratey, "omega y");
388 plotter.AddLine(imut, imu_ratez, "omega z");
389 plotter.AddLine(ct, raw_cx, "Camera x");
390 plotter.AddLine(ct, raw_cy, "Camera y");
391 plotter.AddLine(ct, raw_cz, "Camera z");
392 plotter.Publish();
393
Austin Schuh5b379072021-12-26 16:01:04 -0800394 plotter.AddFigure("xyz vel");
395 plotter.AddLine(times_, x, "x");
396 plotter.AddLine(times_, y, "y");
397 plotter.AddLine(times_, z, "z");
398 plotter.AddLine(times_, vx, "vx");
399 plotter.AddLine(times_, vy, "vy");
400 plotter.AddLine(times_, vz, "vz");
401 plotter.AddLine(ct, camera_position_x, "Camera x");
402 plotter.AddLine(ct, camera_position_y, "Camera y");
403 plotter.AddLine(ct, camera_position_z, "Camera z");
404 plotter.Publish();
405
milind-ue53bf552021-12-11 14:42:00 -0800406 plotter.Spin();
407 }
408
409 void ObserveIntegrated(distributed_clock::time_point t,
410 Eigen::Matrix<double, 6, 1> x_hat,
Austin Schuh5b379072021-12-26 16:01:04 -0800411 Eigen::Quaternion<double> orientation,
412 Eigen::Matrix<double, 6, 6> p) override {
413 VLOG(1) << t << " -> " << p;
414 VLOG(1) << t << " xhat -> " << x_hat.transpose();
milind-ue53bf552021-12-11 14:42:00 -0800415 times_.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
416 x_hats_.emplace_back(x_hat);
417 orientations_.emplace_back(orientation);
418 }
419
420 void ObserveIMUUpdate(
421 distributed_clock::time_point t,
422 std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override {
423 imut.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
424 imu_ratex.emplace_back(wa.first.x());
425 imu_ratey.emplace_back(wa.first.y());
426 imu_ratez.emplace_back(wa.first.z());
427 imu_x.emplace_back(wa.second.x());
428 imu_y.emplace_back(wa.second.y());
429 imu_z.emplace_back(wa.second.z());
430
431 last_accel_ = wa.second;
432 }
433
434 void ObserveCameraUpdate(distributed_clock::time_point t,
435 Eigen::Vector3d board_to_camera_rotation,
Austin Schuh5b379072021-12-26 16:01:04 -0800436 Eigen::Quaternion<double> imu_to_world_rotation,
437 Eigen::Affine3d imu_to_world) override {
milind-ue53bf552021-12-11 14:42:00 -0800438 raw_cx.emplace_back(board_to_camera_rotation(0, 0));
439 raw_cy.emplace_back(board_to_camera_rotation(1, 0));
440 raw_cz.emplace_back(board_to_camera_rotation(2, 0));
441
442 Eigen::Matrix<double, 3, 1> rotation_vector =
Austin Schuh5b379072021-12-26 16:01:04 -0800443 frc971::controls::ToRotationVectorFromQuaternion(imu_to_world_rotation);
milind-ue53bf552021-12-11 14:42:00 -0800444 ct.emplace_back(chrono::duration<double>(t.time_since_epoch()).count());
445
446 Eigen::Matrix<double, 3, 1> cerr =
447 frc971::controls::ToRotationVectorFromQuaternion(
Austin Schuh5b379072021-12-26 16:01:04 -0800448 imu_to_world_rotation.inverse() * orientation());
milind-ue53bf552021-12-11 14:42:00 -0800449
450 cx.emplace_back(rotation_vector(0, 0));
451 cy.emplace_back(rotation_vector(1, 0));
452 cz.emplace_back(rotation_vector(2, 0));
453
454 cerrx.emplace_back(cerr(0, 0));
455 cerry.emplace_back(cerr(1, 0));
456 cerrz.emplace_back(cerr(2, 0));
457
Austin Schuh5b379072021-12-26 16:01:04 -0800458 const Eigen::Vector3d world_gravity =
459 imu_to_world_rotation * last_accel_ -
460 Eigen::Vector3d(0, 0, kGravity) * gravity_scalar();
461
462 const Eigen::Vector3d camera_position =
463 imu_to_world * Eigen::Vector3d::Zero();
milind-ue53bf552021-12-11 14:42:00 -0800464
465 world_gravity_x.emplace_back(world_gravity.x());
466 world_gravity_y.emplace_back(world_gravity.y());
467 world_gravity_z.emplace_back(world_gravity.z());
Austin Schuh5b379072021-12-26 16:01:04 -0800468
469 camera_position_x.emplace_back(camera_position.x());
470 camera_position_y.emplace_back(camera_position.y());
471 camera_position_z.emplace_back(camera_position.z());
milind-ue53bf552021-12-11 14:42:00 -0800472 }
473
474 std::vector<double> ct;
475 std::vector<double> cx;
476 std::vector<double> cy;
477 std::vector<double> cz;
478 std::vector<double> raw_cx;
479 std::vector<double> raw_cy;
480 std::vector<double> raw_cz;
481 std::vector<double> cerrx;
482 std::vector<double> cerry;
483 std::vector<double> cerrz;
484
485 std::vector<double> world_gravity_x;
486 std::vector<double> world_gravity_y;
487 std::vector<double> world_gravity_z;
488 std::vector<double> imu_x;
489 std::vector<double> imu_y;
490 std::vector<double> imu_z;
Austin Schuh5b379072021-12-26 16:01:04 -0800491 std::vector<double> camera_position_x;
492 std::vector<double> camera_position_y;
493 std::vector<double> camera_position_z;
milind-ue53bf552021-12-11 14:42:00 -0800494
495 std::vector<double> imut;
496 std::vector<double> imu_ratex;
497 std::vector<double> imu_ratey;
498 std::vector<double> imu_ratez;
499
500 std::vector<double> times_;
Jim Ostrowski977850f2022-01-22 21:04:22 -0800501 std::vector<Eigen::Matrix<double, 6, 1>> x_hats_;
502 std::vector<Eigen::Quaternion<double>> orientations_;
milind-ue53bf552021-12-11 14:42:00 -0800503
504 Eigen::Matrix<double, 3, 1> last_accel_ = Eigen::Matrix<double, 3, 1>::Zero();
505};
506
507// Adapter class from the KF above to a Ceres cost function.
508struct CostFunctor {
509 CostFunctor(CalibrationData *d) : data(d) {}
510
511 CalibrationData *data;
512
513 template <typename S>
514 bool operator()(const S *const q1, const S *const q2, const S *const v,
Austin Schuh5b379072021-12-26 16:01:04 -0800515 const S *const p, const S *const btw, const S *const itc,
516 const S *const gravity_scalar_ptr,
517 const S *const accelerometer_bias_ptr, S *residual) const {
milind-ue53bf552021-12-11 14:42:00 -0800518 Eigen::Quaternion<S> initial_orientation(q1[3], q1[0], q1[1], q1[2]);
519 Eigen::Quaternion<S> mounting_orientation(q2[3], q2[0], q2[1], q2[2]);
Austin Schuh5b379072021-12-26 16:01:04 -0800520 Eigen::Quaternion<S> board_to_world(btw[3], btw[0], btw[1], btw[2]);
521 Eigen::Matrix<S, 3, 1> gyro_bias(v[0], v[1], v[2]);
522 Eigen::Matrix<S, 6, 1> initial_state;
523 initial_state(0) = p[0];
524 initial_state(1) = p[1];
525 initial_state(2) = p[2];
526 initial_state(3) = p[3];
527 initial_state(4) = p[4];
528 initial_state(5) = p[5];
529 Eigen::Matrix<S, 3, 1> imu_to_camera_translation(itc[0], itc[1], itc[2]);
530 Eigen::Matrix<S, 3, 1> accelerometer_bias(accelerometer_bias_ptr[0],
531 accelerometer_bias_ptr[1],
532 accelerometer_bias_ptr[2]);
milind-ue53bf552021-12-11 14:42:00 -0800533
534 CeresPoseFilter<S> filter(initial_orientation, mounting_orientation,
Austin Schuh5b379072021-12-26 16:01:04 -0800535 gyro_bias, initial_state, board_to_world,
536 imu_to_camera_translation, *gravity_scalar_ptr,
537 accelerometer_bias);
milind-ue53bf552021-12-11 14:42:00 -0800538 data->ReviewData(&filter);
539
540 for (size_t i = 0; i < filter.num_errors(); ++i) {
541 residual[3 * i + 0] = filter.errorx(i);
542 residual[3 * i + 1] = filter.errory(i);
543 residual[3 * i + 2] = filter.errorz(i);
544 }
545
Austin Schuh5b379072021-12-26 16:01:04 -0800546 for (size_t i = 0; i < filter.num_perrors(); ++i) {
547 residual[3 * filter.num_errors() + 3 * i + 0] = filter.errorpx(i);
548 residual[3 * filter.num_errors() + 3 * i + 1] = filter.errorpy(i);
549 residual[3 * filter.num_errors() + 3 * i + 2] = filter.errorpz(i);
550 }
551
milind-ue53bf552021-12-11 14:42:00 -0800552 return true;
553 }
554};
555
Austin Schuhbb4aae72021-10-08 22:12:25 -0700556void Main(int argc, char **argv) {
557 CalibrationData data;
558
559 {
560 // Now, accumulate all the data into the data object.
561 aos::logger::LogReader reader(
562 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
563
564 aos::SimulatedEventLoopFactory factory(reader.configuration());
565 reader.Register(&factory);
566
567 CHECK(aos::configuration::MultiNode(reader.configuration()));
568
569 // Find the nodes we care about.
570 const aos::Node *const roborio_node =
571 aos::configuration::GetNode(factory.configuration(), "roborio");
572
573 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
574 CHECK(pi_number);
575 LOG(INFO) << "Pi " << *pi_number;
576 const aos::Node *const pi_node = aos::configuration::GetNode(
577 factory.configuration(), absl::StrCat("pi", *pi_number));
578
579 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
580 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
581
582 std::unique_ptr<aos::EventLoop> roborio_event_loop =
583 factory.MakeEventLoop("calibration", roborio_node);
584 std::unique_ptr<aos::EventLoop> pi_event_loop =
585 factory.MakeEventLoop("calibration", pi_node);
586
587 // Now, hook Calibration up to everything.
588 Calibration extractor(&factory, pi_event_loop.get(),
589 roborio_event_loop.get(), FLAGS_pi, &data);
590
591 factory.Run();
592
593 reader.Deregister();
594 }
595
596 LOG(INFO) << "Done with event_loop running";
597 // And now we have it, we can start processing it.
milind-u8c72d532021-12-11 15:02:42 -0800598
Austin Schuh5b379072021-12-26 16:01:04 -0800599 const Eigen::Quaternion<double> nominal_initial_orientation(
milind-ue53bf552021-12-11 14:42:00 -0800600 frc971::controls::ToQuaternionFromRotationVector(
601 Eigen::Vector3d(0.0, 0.0, M_PI)));
Austin Schuh5b379072021-12-26 16:01:04 -0800602 const Eigen::Quaternion<double> nominal_imu_to_camera(
milind-ue53bf552021-12-11 14:42:00 -0800603 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
Austin Schuh5b379072021-12-26 16:01:04 -0800604 const Eigen::Quaternion<double> nominal_board_to_world(
605 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
milind-ue53bf552021-12-11 14:42:00 -0800606
Austin Schuh5b379072021-12-26 16:01:04 -0800607 Eigen::Quaternion<double> initial_orientation = nominal_initial_orientation;
608 // Eigen::Quaternion<double>::Identity();
609 Eigen::Quaternion<double> imu_to_camera = nominal_imu_to_camera;
610 // Eigen::Quaternion<double>::Identity();
611 Eigen::Quaternion<double> board_to_world = nominal_board_to_world;
612 // Eigen::Quaternion<double>::Identity();
613 Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();
614 Eigen::Matrix<double, 6, 1> initial_state =
615 Eigen::Matrix<double, 6, 1>::Zero();
616 Eigen::Matrix<double, 3, 1> imu_to_camera_translation =
617 Eigen::Matrix<double, 3, 1>::Zero();
618
619 double gravity_scalar = 1.0;
620 Eigen::Matrix<double, 3, 1> accelerometer_bias =
621 Eigen::Matrix<double, 3, 1>::Zero();
milind-ue53bf552021-12-11 14:42:00 -0800622
milind-u8c72d532021-12-11 15:02:42 -0800623 {
milind-ue53bf552021-12-11 14:42:00 -0800624 ceres::Problem problem;
625
626 ceres::EigenQuaternionParameterization *quaternion_local_parameterization =
627 new ceres::EigenQuaternionParameterization();
628 // Set up the only cost function (also known as residual). This uses
629 // auto-differentiation to obtain the derivative (jacobian).
630
631 ceres::CostFunction *cost_function =
Austin Schuh5b379072021-12-26 16:01:04 -0800632 new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 3, 6,
633 4, 3, 1, 3>(
634 new CostFunctor(&data), data.camera_samples_size() * 6);
635 problem.AddResidualBlock(
milind-u0084be62021-12-27 12:29:38 +0530636 cost_function, new ceres::HuberLoss(1.0),
637 initial_orientation.coeffs().data(), imu_to_camera.coeffs().data(),
638 gyro_bias.data(), initial_state.data(), board_to_world.coeffs().data(),
639 imu_to_camera_translation.data(), &gravity_scalar,
640 accelerometer_bias.data());
milind-ue53bf552021-12-11 14:42:00 -0800641 problem.SetParameterization(initial_orientation.coeffs().data(),
642 quaternion_local_parameterization);
643 problem.SetParameterization(imu_to_camera.coeffs().data(),
644 quaternion_local_parameterization);
Austin Schuh5b379072021-12-26 16:01:04 -0800645 problem.SetParameterization(board_to_world.coeffs().data(),
646 quaternion_local_parameterization);
milind-ue53bf552021-12-11 14:42:00 -0800647 for (int i = 0; i < 3; ++i) {
Austin Schuh5b379072021-12-26 16:01:04 -0800648 problem.SetParameterLowerBound(gyro_bias.data(), i, -0.05);
649 problem.SetParameterUpperBound(gyro_bias.data(), i, 0.05);
650 problem.SetParameterLowerBound(accelerometer_bias.data(), i, -0.05);
651 problem.SetParameterUpperBound(accelerometer_bias.data(), i, 0.05);
milind-ue53bf552021-12-11 14:42:00 -0800652 }
Austin Schuh5b379072021-12-26 16:01:04 -0800653 problem.SetParameterLowerBound(&gravity_scalar, 0, 0.95);
654 problem.SetParameterUpperBound(&gravity_scalar, 0, 1.05);
milind-ue53bf552021-12-11 14:42:00 -0800655
656 // Run the solver!
657 ceres::Solver::Options options;
658 options.minimizer_progress_to_stdout = true;
659 options.gradient_tolerance = 1e-12;
660 options.function_tolerance = 1e-16;
661 options.parameter_tolerance = 1e-12;
662 ceres::Solver::Summary summary;
663 Solve(options, &problem, &summary);
664 LOG(INFO) << summary.FullReport();
665
666 LOG(INFO) << "Nominal initial_orientation "
667 << nominal_initial_orientation.coeffs().transpose();
668 LOG(INFO) << "Nominal imu_to_camera "
669 << nominal_imu_to_camera.coeffs().transpose();
670
671 LOG(INFO) << "initial_orientation "
672 << initial_orientation.coeffs().transpose();
673 LOG(INFO) << "imu_to_camera " << imu_to_camera.coeffs().transpose();
674 LOG(INFO) << "imu_to_camera(rotation) "
675 << frc971::controls::ToRotationVectorFromQuaternion(imu_to_camera)
676 .transpose();
677 LOG(INFO) << "imu_to_camera delta "
678 << frc971::controls::ToRotationVectorFromQuaternion(
679 imu_to_camera * nominal_imu_to_camera.inverse())
680 .transpose();
Austin Schuh5b379072021-12-26 16:01:04 -0800681 LOG(INFO) << "gyro_bias " << gyro_bias.transpose();
682 LOG(INFO) << "board_to_world " << board_to_world.coeffs().transpose();
683 LOG(INFO) << "board_to_world(rotation) "
684 << frc971::controls::ToRotationVectorFromQuaternion(
685 board_to_world)
686 .transpose();
687 LOG(INFO) << "board_to_world delta "
688 << frc971::controls::ToRotationVectorFromQuaternion(
689 board_to_world * nominal_board_to_world.inverse())
690 .transpose();
691 LOG(INFO) << "imu_to_camera_translation "
692 << imu_to_camera_translation.transpose();
693 LOG(INFO) << "gravity " << kGravity * gravity_scalar;
694 LOG(INFO) << "accelerometer bias " << accelerometer_bias.transpose();
milind-ue53bf552021-12-11 14:42:00 -0800695 }
696
697 {
Austin Schuh5b379072021-12-26 16:01:04 -0800698 PoseFilter filter(initial_orientation, imu_to_camera, gyro_bias,
699 initial_state, board_to_world, imu_to_camera_translation,
700 gravity_scalar, accelerometer_bias);
milind-u8c72d532021-12-11 15:02:42 -0800701 data.ReviewData(&filter);
milind-u0084be62021-12-27 12:29:38 +0530702 if (FLAGS_plot) {
703 filter.Plot();
704 }
milind-u8c72d532021-12-11 15:02:42 -0800705 }
Austin Schuhbb4aae72021-10-08 22:12:25 -0700706}
707
708} // namespace vision
709} // namespace frc971
710
711int main(int argc, char **argv) {
712 aos::InitGoogle(&argc, &argv);
713
714 frc971::vision::Main(argc, argv);
715}