Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1 | #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 Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 9 | #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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 16 | |
| 17 | namespace frc971 { |
| 18 | namespace vision { |
| 19 | |
| 20 | namespace chrono = std::chrono; |
| 21 | using aos::distributed_clock; |
| 22 | using aos::monotonic_clock; |
| 23 | |
| 24 | constexpr 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. |
| 55 | template <typename Scalar> |
| 56 | class CeresPoseFilter : public CalibrationDataObserver { |
| 57 | public: |
| 58 | typedef Eigen::Transform<Scalar, 3, Eigen::Affine> Affine3s; |
| 59 | |
| 60 | CeresPoseFilter(Eigen::Quaternion<Scalar> initial_orientation, |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 61 | Eigen::Quaternion<Scalar> pivot_to_camera, |
| 62 | Eigen::Quaternion<Scalar> pivot_to_imu, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 63 | Eigen::Matrix<Scalar, 3, 1> gyro_bias, |
| 64 | Eigen::Matrix<Scalar, 6, 1> initial_state, |
| 65 | Eigen::Quaternion<Scalar> board_to_world, |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 66 | Eigen::Matrix<Scalar, 3, 1> pivot_to_camera_translation, |
| 67 | Eigen::Matrix<Scalar, 3, 1> pivot_to_imu_translation, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 68 | 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 76 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 80 | 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 Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 89 | Eigen::Vector3d /*board_to_camera_translation*/, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 90 | Eigen::Quaternion<Scalar> /*imu_to_world_rotation*/, |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 91 | Affine3s /*imu_to_world*/, double /*turret_angle*/) {} |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 92 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 93 | // 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 99 | const double pivot_angle = |
| 100 | state_time_ == distributed_clock::min_time |
| 101 | ? 0.0 |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 102 | : turret_state_(0) + |
| 103 | turret_state_(1) * |
| 104 | chrono::duration<double>(t - state_time_).count(); |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 105 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 106 | 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 113 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 117 | |
| 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 126 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 130 | |
| 131 | const Affine3s imu_to_world = |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 132 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 136 | |
| 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 Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 146 | // 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 149 | const Eigen::Matrix<double, 3, 3> R = |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 150 | (::Eigen::DiagonalMatrix<double, 3>().diagonal() << obs_noise_var, |
| 151 | obs_noise_var, obs_noise_var) |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 152 | .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 Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 169 | ObserveCameraUpdate(t, rt.first, rt.second, imu_to_world_rotation, |
| 170 | imu_to_world, pivot_angle); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 171 | } |
| 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 Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 186 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 200 | const Eigen::Quaternion<Scalar> &orientation() const { return orientation_; } |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 201 | const Eigen::Matrix<Scalar, 6, 1> &get_x_hat() const { return x_hat_; } |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 202 | |
| 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 310 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 316 | 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 339 | // Drives the Z coordinate of the quaternion to 0. |
| 340 | struct 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 350 | // Subclass of the filter above which has plotting. This keeps debug code and |
| 351 | // actual code separate. |
| 352 | class PoseFilter : public CeresPoseFilter<double> { |
| 353 | public: |
| 354 | PoseFilter(Eigen::Quaternion<double> initial_orientation, |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 355 | Eigen::Quaternion<double> pivot_to_camera, |
| 356 | Eigen::Quaternion<double> pivot_to_imu, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 357 | Eigen::Matrix<double, 3, 1> gyro_bias, |
| 358 | Eigen::Matrix<double, 6, 1> initial_state, |
| 359 | Eigen::Quaternion<double> board_to_world, |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 360 | Eigen::Matrix<double, 3, 1> pivot_to_camera_translation, |
| 361 | Eigen::Matrix<double, 3, 1> pivot_to_imu_translation, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 362 | double gravity_scalar, |
| 363 | Eigen::Matrix<double, 3, 1> accelerometer_bias) |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 364 | : 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 368 | |
| 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 Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 395 | // TODO<Jim>: Could probably still do a bit more work on naming |
| 396 | // conventions and what is being shown here |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 397 | frc971::analysis::Plotter plotter; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 398 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 402 | plotter.Publish(); |
| 403 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 404 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 420 | plotter.Publish(); |
| 421 | |
| 422 | plotter.AddFigure("imu"); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 423 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 435 | plotter.Publish(); |
| 436 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 437 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 444 | plotter.Publish(); |
| 445 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 446 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 450 | plotter.AddLine(times_, vx, "vx"); |
| 451 | plotter.AddLine(times_, vy, "vy"); |
| 452 | plotter.AddLine(times_, vz, "vz"); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 453 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 456 | plotter.Publish(); |
| 457 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 458 | // 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 465 | plotter.Spin(); |
| 466 | } |
| 467 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 468 | 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 | |
| 491 | /* |
| 492 | // Draw an initial visualization |
| 493 | Eigen::Vector3d T_world_imu_vec = |
| 494 | calibration_parameters.initial_state.block<3, 1>(0, 0); |
| 495 | Eigen::Translation3d T_world_imu(T_world_imu_vec); |
| 496 | Eigen::Affine3d H_world_imu = |
| 497 | T_world_imu * calibration_parameters.initial_orientation; |
| 498 | |
| 499 | vis_robot.DrawFrameAxes(H_world_imu, "imu"); |
| 500 | |
| 501 | Eigen::Quaterniond R_imu_pivot(calibration_parameters.pivot_to_imu); |
| 502 | Eigen::Translation3d T_imu_pivot( |
| 503 | calibration_parameters.pivot_to_imu_translation); |
| 504 | Eigen::Affine3d H_imu_pivot = T_imu_pivot * R_imu_pivot; |
| 505 | Eigen::Affine3d H_world_pivot = H_world_imu * H_imu_pivot; |
| 506 | vis_robot.DrawFrameAxes(H_world_pivot, "pivot"); |
| 507 | |
| 508 | Eigen::Affine3d H_imupivot_camerapivot( |
| 509 | Eigen::AngleAxisd(1.5, Eigen::Vector3d::UnitZ())); |
| 510 | Eigen::Quaterniond R_camera_pivot(calibration_parameters.pivot_to_camera); |
| 511 | Eigen::Translation3d T_camera_pivot( |
| 512 | calibration_parameters.pivot_to_camera_translation); |
| 513 | Eigen::Affine3d H_camera_pivot = T_camera_pivot * R_camera_pivot; |
| 514 | Eigen::Affine3d H_world_camera = H_world_imu * H_imu_pivot * |
| 515 | H_imupivot_camerapivot * |
| 516 | H_camera_pivot.inverse(); |
| 517 | vis_robot.DrawFrameAxes(H_world_camera, "camera"); |
| 518 | |
| 519 | cv::imshow("Original poses", image_mat); |
| 520 | cv::waitKey(); |
| 521 | */ |
| 522 | |
| 523 | uint current_state_index = 0; |
| 524 | uint current_turret_index = 0; |
| 525 | for (uint i = 0; i < camera_times_.size() - 1; i++) { |
| 526 | // reset image each frame |
| 527 | cv::Mat image_mat = |
| 528 | cv::Mat::zeros(cv::Size(image_width, image_width), CV_8UC3); |
| 529 | vis_robot.SetImage(image_mat); |
| 530 | |
| 531 | // Jump to state closest to current camera_time |
| 532 | while (camera_times_[i] > times_[current_state_index] && |
| 533 | current_state_index < times_.size()) { |
| 534 | current_state_index++; |
| 535 | } |
| 536 | |
| 537 | // H_world_imu: map from world origin to imu (robot) frame |
| 538 | Eigen::Vector3d T_world_imu_vec = |
| 539 | x_hats_[current_state_index].block<3, 1>(0, 0); |
| 540 | Eigen::Translation3d T_world_imu(T_world_imu_vec); |
| 541 | Eigen::Affine3d H_world_imu = |
| 542 | T_world_imu * orientations_[current_state_index]; |
| 543 | |
| 544 | vis_robot.DrawFrameAxes(H_world_imu, "imu_kf"); |
| 545 | |
| 546 | // H_world_pivot: map from world origin to pivot point |
| 547 | // Do this via the imu (using H_world_pivot = H_world_imu * H_imu_pivot) |
| 548 | Eigen::Quaterniond R_imu_pivot(calibration_parameters.pivot_to_imu); |
| 549 | Eigen::Translation3d T_imu_pivot( |
| 550 | calibration_parameters.pivot_to_imu_translation); |
| 551 | Eigen::Affine3d H_imu_pivot = T_imu_pivot * R_imu_pivot; |
| 552 | Eigen::Affine3d H_world_pivot = H_world_imu * H_imu_pivot; |
| 553 | vis_robot.DrawFrameAxes(H_world_pivot, "pivot"); |
| 554 | |
| 555 | // Jump to turret sample closest to current camera_time |
| 556 | while (turret_times_.size() > 0 && |
| 557 | camera_times_[i] > turret_times_[current_turret_index] && |
| 558 | current_turret_index < turret_times_.size()) { |
| 559 | current_turret_index++; |
| 560 | } |
| 561 | |
| 562 | // Draw the camera frame |
| 563 | |
| 564 | Eigen::Affine3d H_imupivot_camerapivot(Eigen::Matrix4d::Identity()); |
| 565 | if (turret_angles_.size() > 0) { |
| 566 | // Need to rotate by the turret angle in the middle of all this |
| 567 | H_imupivot_camerapivot = Eigen::Affine3d(Eigen::AngleAxisd( |
| 568 | turret_angles_[current_turret_index], Eigen::Vector3d::UnitZ())); |
| 569 | } |
| 570 | |
| 571 | // H_world_camera: map from world origin to camera frame |
| 572 | // Via imu->pivot->pivot rotation |
| 573 | Eigen::Quaterniond R_camera_pivot(calibration_parameters.pivot_to_camera); |
| 574 | Eigen::Translation3d T_camera_pivot( |
| 575 | calibration_parameters.pivot_to_camera_translation); |
| 576 | Eigen::Affine3d H_camera_pivot = T_camera_pivot * R_camera_pivot; |
| 577 | Eigen::Affine3d H_world_camera = H_world_imu * H_imu_pivot * |
| 578 | H_imupivot_camerapivot * |
| 579 | H_camera_pivot.inverse(); |
| 580 | vis_robot.DrawFrameAxes(H_world_camera, "camera"); |
| 581 | |
| 582 | // H_world_board: board location from world reference frame |
| 583 | // Uses the estimate from camera-> board, on top of H_world_camera |
| 584 | Eigen::Quaterniond R_camera_board( |
| 585 | frc971::controls::ToQuaternionFromRotationVector( |
| 586 | board_to_camera_rotations_[i])); |
| 587 | Eigen::Translation3d T_camera_board(board_to_camera_translations_[i]); |
| 588 | Eigen::Affine3d H_camera_board = T_camera_board * R_camera_board; |
| 589 | Eigen::Affine3d H_world_board = H_world_camera * H_camera_board; |
| 590 | |
| 591 | vis_robot.DrawFrameAxes(H_world_board, "board est"); |
| 592 | |
| 593 | // H_world_board_solve: board in world frame based on solver |
| 594 | // Find world -> board via solved parameter of H_world_board |
| 595 | // (parameter "board_to_world" and assuming origin of board frame is |
| 596 | // coincident with origin of world frame, i.e., T_world_board == 0) |
| 597 | Eigen::Quaterniond R_world_board_solve( |
| 598 | calibration_parameters.board_to_world); |
| 599 | Eigen::Translation3d T_world_board_solve(Eigen::Vector3d(0, 0, 0)); |
| 600 | Eigen::Affine3d H_world_board_solve = |
| 601 | T_world_board_solve * R_world_board_solve; |
| 602 | |
| 603 | vis_robot.DrawFrameAxes(H_world_board_solve, "board_solve"); |
| 604 | |
| 605 | // H_world_imu_from_board: imu location in world frame, via the board |
| 606 | // Determine the imu location via the board_to_world solved |
| 607 | // transformation |
| 608 | Eigen::Affine3d H_world_imu_from_board = |
| 609 | H_world_board_solve * H_camera_board.inverse() * H_camera_pivot * |
| 610 | H_imupivot_camerapivot.inverse() * H_imu_pivot.inverse(); |
| 611 | |
| 612 | vis_robot.DrawFrameAxes(H_world_imu_from_board, "imu_board"); |
| 613 | |
| 614 | // These errors should match up with the residuals in the optimizer |
| 615 | // (Note: rotation seems to differ by sign, but that's OK in residual) |
| 616 | Eigen::Affine3d error = H_world_imu_from_board.inverse() * H_world_imu; |
| 617 | Eigen::Vector3d trans_error = |
| 618 | H_world_imu_from_board.translation() - H_world_imu.translation(); |
| 619 | Eigen::Quaterniond error_rot(error.rotation()); |
| 620 | VLOG(1) << "Error: \n" |
| 621 | << "Rotation: " << error_rot.coeffs().transpose() << "\n" |
| 622 | << "Translation: " << trans_error.transpose(); |
| 623 | |
| 624 | cv::imshow("Live", image_mat); |
| 625 | cv::waitKey(50); |
| 626 | |
| 627 | if (i % 200 == 0) { |
| 628 | LOG(INFO) << "Pausing at step " << i; |
| 629 | cv::waitKey(); |
| 630 | } |
| 631 | } |
| 632 | LOG(INFO) << "Finished visualizing robot. Press any key to continue"; |
| 633 | cv::waitKey(); |
| 634 | } |
| 635 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 636 | void ObserveIntegrated(distributed_clock::time_point t, |
| 637 | Eigen::Matrix<double, 6, 1> x_hat, |
| 638 | Eigen::Quaternion<double> orientation, |
| 639 | Eigen::Matrix<double, 6, 6> p) override { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 640 | VLOG(2) << t << " -> " << p; |
| 641 | VLOG(2) << t << " xhat -> " << x_hat.transpose(); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 642 | times_.emplace_back(chrono::duration<double>(t.time_since_epoch()).count()); |
| 643 | x_hats_.emplace_back(x_hat); |
| 644 | orientations_.emplace_back(orientation); |
| 645 | } |
| 646 | |
| 647 | void ObserveIMUUpdate( |
| 648 | distributed_clock::time_point t, |
| 649 | std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) override { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 650 | imu_times_.emplace_back( |
| 651 | chrono::duration<double>(t.time_since_epoch()).count()); |
| 652 | imu_rate_x_.emplace_back(wa.first.x()); |
| 653 | imu_rate_y_.emplace_back(wa.first.y()); |
| 654 | imu_rate_z_.emplace_back(wa.first.z()); |
| 655 | imu_accel_x_.emplace_back(wa.second.x()); |
| 656 | imu_accel_y_.emplace_back(wa.second.y()); |
| 657 | imu_accel_z_.emplace_back(wa.second.z()); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 658 | |
| 659 | last_accel_ = wa.second; |
| 660 | } |
| 661 | |
| 662 | void ObserveCameraUpdate(distributed_clock::time_point t, |
| 663 | Eigen::Vector3d board_to_camera_rotation, |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 664 | Eigen::Vector3d board_to_camera_translation, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 665 | Eigen::Quaternion<double> imu_to_world_rotation, |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 666 | Eigen::Affine3d imu_to_world, |
| 667 | double turret_angle) override { |
| 668 | board_to_camera_rotations_.emplace_back(board_to_camera_rotation); |
| 669 | board_to_camera_translations_.emplace_back(board_to_camera_translation); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 670 | |
Austin Schuh | cf848fc | 2022-02-25 21:34:18 -0800 | [diff] [blame] | 671 | camera_times_.emplace_back( |
| 672 | chrono::duration<double>(t.time_since_epoch()).count()); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 673 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 674 | raw_camera_rot_x_.emplace_back(board_to_camera_rotation(0, 0)); |
| 675 | raw_camera_rot_y_.emplace_back(board_to_camera_rotation(1, 0)); |
| 676 | raw_camera_rot_z_.emplace_back(board_to_camera_rotation(2, 0)); |
| 677 | |
| 678 | raw_camera_trans_x_.emplace_back(board_to_camera_translation(0, 0)); |
| 679 | raw_camera_trans_y_.emplace_back(board_to_camera_translation(1, 0)); |
| 680 | raw_camera_trans_z_.emplace_back(board_to_camera_translation(2, 0)); |
| 681 | |
| 682 | Eigen::Matrix<double, 3, 1> rotation_vector = |
| 683 | frc971::controls::ToRotationVectorFromQuaternion(imu_to_world_rotation); |
| 684 | imu_rot_x_.emplace_back(rotation_vector(0, 0)); |
| 685 | imu_rot_y_.emplace_back(rotation_vector(1, 0)); |
| 686 | imu_rot_z_.emplace_back(rotation_vector(2, 0)); |
| 687 | |
| 688 | Eigen::Matrix<double, 3, 1> rotation_error = |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 689 | frc971::controls::ToRotationVectorFromQuaternion( |
| 690 | imu_to_world_rotation.inverse() * orientation()); |
| 691 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 692 | rotation_error_x_.emplace_back(rotation_error(0, 0)); |
| 693 | rotation_error_y_.emplace_back(rotation_error(1, 0)); |
| 694 | rotation_error_z_.emplace_back(rotation_error(2, 0)); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 695 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 696 | Eigen::Matrix<double, 3, 1> imu_pos = get_x_hat().block<3, 1>(0, 0); |
| 697 | Eigen::Translation3d T_world_imu(imu_pos); |
| 698 | Eigen::Affine3d H_world_imu = T_world_imu * orientation(); |
| 699 | Eigen::Affine3d H_error = imu_to_world.inverse() * H_world_imu; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 700 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 701 | Eigen::Matrix<double, 3, 1> translation_error = H_error.translation(); |
| 702 | translation_error_x_.emplace_back(translation_error(0, 0)); |
| 703 | translation_error_y_.emplace_back(translation_error(1, 0)); |
| 704 | translation_error_z_.emplace_back(translation_error(2, 0)); |
| 705 | |
| 706 | const Eigen::Vector3d accel_minus_gravity = |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 707 | imu_to_world_rotation * last_accel_ - |
| 708 | Eigen::Vector3d(0, 0, kGravity) * gravity_scalar(); |
| 709 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 710 | accel_minus_gravity_x_.emplace_back(accel_minus_gravity.x()); |
| 711 | accel_minus_gravity_y_.emplace_back(accel_minus_gravity.y()); |
| 712 | accel_minus_gravity_z_.emplace_back(accel_minus_gravity.z()); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 713 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 714 | const Eigen::Vector3d imu_position = imu_to_world * Eigen::Vector3d::Zero(); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 715 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 716 | imu_position_x_.emplace_back(imu_position.x()); |
| 717 | imu_position_y_.emplace_back(imu_position.y()); |
| 718 | imu_position_z_.emplace_back(imu_position.z()); |
| 719 | |
| 720 | turret_angles_from_camera_.emplace_back(turret_angle); |
| 721 | imu_to_world_save_.emplace_back(imu_to_world); |
| 722 | } |
| 723 | |
| 724 | void ObserveTurretUpdate(distributed_clock::time_point t, |
| 725 | Eigen::Vector2d turret_state) override { |
| 726 | turret_times_.emplace_back( |
| 727 | chrono::duration<double>(t.time_since_epoch()).count()); |
| 728 | turret_angles_.emplace_back(turret_state(0)); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 729 | } |
| 730 | |
Austin Schuh | cf848fc | 2022-02-25 21:34:18 -0800 | [diff] [blame] | 731 | std::vector<double> camera_times_; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 732 | std::vector<double> imu_rot_x_; |
| 733 | std::vector<double> imu_rot_y_; |
| 734 | std::vector<double> imu_rot_z_; |
| 735 | std::vector<double> raw_camera_rot_x_; |
| 736 | std::vector<double> raw_camera_rot_y_; |
| 737 | std::vector<double> raw_camera_rot_z_; |
| 738 | std::vector<double> raw_camera_trans_x_; |
| 739 | std::vector<double> raw_camera_trans_y_; |
| 740 | std::vector<double> raw_camera_trans_z_; |
| 741 | std::vector<double> rotation_error_x_; |
| 742 | std::vector<double> rotation_error_y_; |
| 743 | std::vector<double> rotation_error_z_; |
| 744 | std::vector<double> translation_error_x_; |
| 745 | std::vector<double> translation_error_y_; |
| 746 | std::vector<double> translation_error_z_; |
| 747 | std::vector<Eigen::Vector3d> board_to_camera_rotations_; |
| 748 | std::vector<Eigen::Vector3d> board_to_camera_translations_; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 749 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 750 | std::vector<double> turret_angles_from_camera_; |
| 751 | std::vector<Eigen::Affine3d> imu_to_world_save_; |
| 752 | |
| 753 | std::vector<double> imu_position_x_; |
| 754 | std::vector<double> imu_position_y_; |
| 755 | std::vector<double> imu_position_z_; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 756 | |
Austin Schuh | cf848fc | 2022-02-25 21:34:18 -0800 | [diff] [blame] | 757 | std::vector<double> imu_times_; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 758 | std::vector<double> imu_rate_x_; |
| 759 | std::vector<double> imu_rate_y_; |
| 760 | std::vector<double> imu_rate_z_; |
| 761 | std::vector<double> accel_minus_gravity_x_; |
| 762 | std::vector<double> accel_minus_gravity_y_; |
| 763 | std::vector<double> accel_minus_gravity_z_; |
| 764 | std::vector<double> imu_accel_x_; |
| 765 | std::vector<double> imu_accel_y_; |
| 766 | std::vector<double> imu_accel_z_; |
| 767 | |
| 768 | std::vector<double> turret_times_; |
| 769 | std::vector<double> turret_angles_; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 770 | |
| 771 | std::vector<double> times_; |
| 772 | std::vector<Eigen::Matrix<double, 6, 1>> x_hats_; |
| 773 | std::vector<Eigen::Quaternion<double>> orientations_; |
| 774 | |
| 775 | Eigen::Matrix<double, 3, 1> last_accel_ = Eigen::Matrix<double, 3, 1>::Zero(); |
| 776 | }; |
| 777 | |
| 778 | // Adapter class from the KF above to a Ceres cost function. |
| 779 | struct CostFunctor { |
| 780 | CostFunctor(const CalibrationData *d) : data(d) {} |
| 781 | |
| 782 | const CalibrationData *data; |
| 783 | |
| 784 | template <typename S> |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 785 | bool operator()(const S *const initial_orientation_ptr, |
| 786 | const S *const pivot_to_camera_ptr, |
| 787 | const S *const pivot_to_imu_ptr, const S *const gyro_bias_ptr, |
| 788 | const S *const initial_state_ptr, |
| 789 | const S *const board_to_world_ptr, |
| 790 | const S *const pivot_to_camera_translation_ptr, |
| 791 | const S *const pivot_to_imu_translation_ptr, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 792 | const S *const gravity_scalar_ptr, |
| 793 | const S *const accelerometer_bias_ptr, S *residual) const { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 794 | const aos::monotonic_clock::time_point start_time = |
| 795 | aos::monotonic_clock::now(); |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 796 | Eigen::Quaternion<S> initial_orientation( |
| 797 | initial_orientation_ptr[3], initial_orientation_ptr[0], |
| 798 | initial_orientation_ptr[1], initial_orientation_ptr[2]); |
| 799 | Eigen::Quaternion<S> pivot_to_camera( |
| 800 | pivot_to_camera_ptr[3], pivot_to_camera_ptr[0], pivot_to_camera_ptr[1], |
| 801 | pivot_to_camera_ptr[2]); |
| 802 | Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0], |
| 803 | pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]); |
| 804 | Eigen::Quaternion<S> board_to_world( |
| 805 | board_to_world_ptr[3], board_to_world_ptr[0], board_to_world_ptr[1], |
| 806 | board_to_world_ptr[2]); |
| 807 | Eigen::Matrix<S, 3, 1> gyro_bias(gyro_bias_ptr[0], gyro_bias_ptr[1], |
| 808 | gyro_bias_ptr[2]); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 809 | Eigen::Matrix<S, 6, 1> initial_state; |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 810 | initial_state(0) = initial_state_ptr[0]; |
| 811 | initial_state(1) = initial_state_ptr[1]; |
| 812 | initial_state(2) = initial_state_ptr[2]; |
| 813 | initial_state(3) = initial_state_ptr[3]; |
| 814 | initial_state(4) = initial_state_ptr[4]; |
| 815 | initial_state(5) = initial_state_ptr[5]; |
| 816 | Eigen::Matrix<S, 3, 1> pivot_to_camera_translation( |
| 817 | pivot_to_camera_translation_ptr[0], pivot_to_camera_translation_ptr[1], |
| 818 | pivot_to_camera_translation_ptr[2]); |
| 819 | Eigen::Matrix<S, 3, 1> pivot_to_imu_translation( |
| 820 | pivot_to_imu_translation_ptr[0], pivot_to_imu_translation_ptr[1], |
| 821 | pivot_to_imu_translation_ptr[2]); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 822 | Eigen::Matrix<S, 3, 1> accelerometer_bias(accelerometer_bias_ptr[0], |
| 823 | accelerometer_bias_ptr[1], |
| 824 | accelerometer_bias_ptr[2]); |
| 825 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 826 | CeresPoseFilter<S> filter( |
| 827 | initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias, |
| 828 | initial_state, board_to_world, pivot_to_camera_translation, |
| 829 | pivot_to_imu_translation, *gravity_scalar_ptr, accelerometer_bias); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 830 | data->ReviewData(&filter); |
| 831 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 832 | // Since the angular error scale is bounded by 1 (quaternion, so unit |
| 833 | // vector, scaled by sin(alpha)), I found it necessary to scale the |
| 834 | // angular error to have it properly balance with the translational error |
| 835 | double ang_error_scale = 5.0; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 836 | for (size_t i = 0; i < filter.num_errors(); ++i) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 837 | residual[3 * i + 0] = ang_error_scale * filter.errorx(i); |
| 838 | residual[3 * i + 1] = ang_error_scale * filter.errory(i); |
| 839 | residual[3 * i + 2] = ang_error_scale * filter.errorz(i); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 840 | } |
| 841 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 842 | double trans_error_scale = 1.0; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 843 | for (size_t i = 0; i < filter.num_perrors(); ++i) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 844 | residual[3 * filter.num_errors() + 3 * i + 0] = |
| 845 | trans_error_scale * filter.errorpx(i); |
| 846 | residual[3 * filter.num_errors() + 3 * i + 1] = |
| 847 | trans_error_scale * filter.errorpy(i); |
| 848 | residual[3 * filter.num_errors() + 3 * i + 2] = |
| 849 | trans_error_scale * filter.errorpz(i); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 850 | } |
| 851 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 852 | LOG(INFO) << "Cost function calc took " |
| 853 | << chrono::duration<double>(aos::monotonic_clock::now() - |
| 854 | start_time) |
| 855 | .count() |
| 856 | << " seconds"; |
| 857 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 858 | return true; |
| 859 | } |
| 860 | }; |
| 861 | |
James Kuszmaul | 086d019 | 2023-02-11 15:35:03 -0800 | [diff] [blame^] | 862 | std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H) { |
| 863 | std::vector<float> data; |
| 864 | for (int row = 0; row < 4; ++row) { |
| 865 | for (int col = 0; col < 4; ++col) { |
| 866 | data.push_back(H(row, col)); |
| 867 | } |
| 868 | } |
| 869 | return data; |
| 870 | } |
| 871 | |
| 872 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> Solve( |
| 873 | const CalibrationData &data, |
| 874 | CalibrationParameters *calibration_parameters) { |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 875 | ceres::Problem problem; |
| 876 | |
| 877 | ceres::EigenQuaternionParameterization *quaternion_local_parameterization = |
| 878 | new ceres::EigenQuaternionParameterization(); |
| 879 | // Set up the only cost function (also known as residual). This uses |
| 880 | // auto-differentiation to obtain the derivative (jacobian). |
| 881 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 882 | { |
| 883 | ceres::CostFunction *cost_function = |
| 884 | new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 4, 3, |
| 885 | 6, 4, 3, 3, 1, 3>( |
| 886 | new CostFunctor(&data), data.camera_samples_size() * 6); |
| 887 | problem.AddResidualBlock( |
| 888 | cost_function, new ceres::HuberLoss(1.0), |
| 889 | calibration_parameters->initial_orientation.coeffs().data(), |
| 890 | calibration_parameters->pivot_to_camera.coeffs().data(), |
| 891 | calibration_parameters->pivot_to_imu.coeffs().data(), |
| 892 | calibration_parameters->gyro_bias.data(), |
| 893 | calibration_parameters->initial_state.data(), |
| 894 | calibration_parameters->board_to_world.coeffs().data(), |
| 895 | calibration_parameters->pivot_to_camera_translation.data(), |
| 896 | calibration_parameters->pivot_to_imu_translation.data(), |
| 897 | &calibration_parameters->gravity_scalar, |
| 898 | calibration_parameters->accelerometer_bias.data()); |
| 899 | } |
| 900 | |
| 901 | { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 902 | // The turret's Z rotation is redundant with the camera's mounting z |
| 903 | // rotation since it's along the rotation axis. |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 904 | ceres::CostFunction *turret_z_cost_function = |
| 905 | new ceres::AutoDiffCostFunction<PenalizeQuaternionZ, 1, 4>( |
| 906 | new PenalizeQuaternionZ()); |
| 907 | problem.AddResidualBlock( |
| 908 | turret_z_cost_function, nullptr, |
| 909 | calibration_parameters->pivot_to_imu.coeffs().data()); |
| 910 | } |
| 911 | |
| 912 | if (calibration_parameters->has_pivot) { |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 913 | // Constrain Z since it's along the rotation axis and therefore |
| 914 | // redundant. |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 915 | problem.SetParameterization( |
| 916 | calibration_parameters->pivot_to_imu_translation.data(), |
| 917 | new ceres::SubsetParameterization(3, {2})); |
| 918 | } else { |
| 919 | problem.SetParameterBlockConstant( |
| 920 | calibration_parameters->pivot_to_imu.coeffs().data()); |
| 921 | problem.SetParameterBlockConstant( |
| 922 | calibration_parameters->pivot_to_imu_translation.data()); |
| 923 | } |
| 924 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 925 | problem.SetParameterization( |
| 926 | calibration_parameters->initial_orientation.coeffs().data(), |
| 927 | quaternion_local_parameterization); |
| 928 | problem.SetParameterization( |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 929 | calibration_parameters->pivot_to_camera.coeffs().data(), |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 930 | quaternion_local_parameterization); |
| 931 | problem.SetParameterization( |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 932 | calibration_parameters->pivot_to_imu.coeffs().data(), |
| 933 | quaternion_local_parameterization); |
| 934 | problem.SetParameterization( |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 935 | calibration_parameters->board_to_world.coeffs().data(), |
| 936 | quaternion_local_parameterization); |
| 937 | for (int i = 0; i < 3; ++i) { |
| 938 | problem.SetParameterLowerBound(calibration_parameters->gyro_bias.data(), i, |
| 939 | -0.05); |
| 940 | problem.SetParameterUpperBound(calibration_parameters->gyro_bias.data(), i, |
| 941 | 0.05); |
| 942 | problem.SetParameterLowerBound( |
| 943 | calibration_parameters->accelerometer_bias.data(), i, -0.05); |
| 944 | problem.SetParameterUpperBound( |
| 945 | calibration_parameters->accelerometer_bias.data(), i, 0.05); |
| 946 | } |
| 947 | problem.SetParameterLowerBound(&calibration_parameters->gravity_scalar, 0, |
| 948 | 0.95); |
| 949 | problem.SetParameterUpperBound(&calibration_parameters->gravity_scalar, 0, |
| 950 | 1.05); |
| 951 | |
| 952 | // Run the solver! |
| 953 | ceres::Solver::Options options; |
| 954 | options.minimizer_progress_to_stdout = true; |
| 955 | options.gradient_tolerance = 1e-12; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 956 | options.function_tolerance = 1e-6; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 957 | options.parameter_tolerance = 1e-12; |
| 958 | ceres::Solver::Summary summary; |
| 959 | Solve(options, &problem, &summary); |
| 960 | LOG(INFO) << summary.FullReport(); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 961 | LOG(INFO) << "Solution is " << (summary.IsSolutionUsable() ? "" : "NOT ") |
| 962 | << "usable"; |
James Kuszmaul | 086d019 | 2023-02-11 15:35:03 -0800 | [diff] [blame^] | 963 | |
| 964 | { |
| 965 | flatbuffers::FlatBufferBuilder fbb; |
| 966 | flatbuffers::Offset<flatbuffers::Vector<float>> data_offset = |
| 967 | fbb.CreateVector(MatrixToVector( |
| 968 | (Eigen::Translation3d( |
| 969 | calibration_parameters->pivot_to_camera_translation) * |
| 970 | Eigen::Quaterniond(calibration_parameters->pivot_to_camera)) |
| 971 | .inverse() |
| 972 | .matrix())); |
| 973 | calibration::TransformationMatrix::Builder matrix_builder(fbb); |
| 974 | matrix_builder.add_data(data_offset); |
| 975 | flatbuffers::Offset<calibration::TransformationMatrix> |
| 976 | camera_to_pivot_offset = matrix_builder.Finish(); |
| 977 | |
| 978 | flatbuffers::Offset<calibration::TransformationMatrix> pivot_to_imu_offset; |
| 979 | if (calibration_parameters->has_pivot) { |
| 980 | flatbuffers::Offset<flatbuffers::Vector<float>> data_offset = |
| 981 | fbb.CreateVector(MatrixToVector( |
| 982 | (Eigen::Translation3d( |
| 983 | calibration_parameters->pivot_to_imu_translation) * |
| 984 | Eigen::Quaterniond(calibration_parameters->pivot_to_imu)) |
| 985 | .matrix())); |
| 986 | calibration::TransformationMatrix::Builder matrix_builder(fbb); |
| 987 | matrix_builder.add_data(data_offset); |
| 988 | pivot_to_imu_offset = matrix_builder.Finish(); |
| 989 | } |
| 990 | |
| 991 | calibration::CameraCalibration::Builder calibration_builder(fbb); |
| 992 | if (calibration_parameters->has_pivot) { |
| 993 | calibration_builder.add_fixed_extrinsics(pivot_to_imu_offset); |
| 994 | calibration_builder.add_turret_extrinsics(camera_to_pivot_offset); |
| 995 | } else { |
| 996 | calibration_builder.add_fixed_extrinsics(camera_to_pivot_offset); |
| 997 | } |
| 998 | fbb.Finish(calibration_builder.Finish()); |
| 999 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> extrinsics = |
| 1000 | fbb.Release(); |
| 1001 | return extrinsics; |
| 1002 | } |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1003 | } |
| 1004 | |
| 1005 | void Plot(const CalibrationData &data, |
| 1006 | const CalibrationParameters &calibration_parameters) { |
| 1007 | PoseFilter filter(calibration_parameters.initial_orientation, |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 1008 | calibration_parameters.pivot_to_camera, |
| 1009 | calibration_parameters.pivot_to_imu, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1010 | calibration_parameters.gyro_bias, |
| 1011 | calibration_parameters.initial_state, |
| 1012 | calibration_parameters.board_to_world, |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 1013 | calibration_parameters.pivot_to_camera_translation, |
| 1014 | calibration_parameters.pivot_to_imu_translation, |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1015 | calibration_parameters.gravity_scalar, |
| 1016 | calibration_parameters.accelerometer_bias); |
| 1017 | data.ReviewData(&filter); |
| 1018 | filter.Plot(); |
| 1019 | } |
| 1020 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 1021 | void Visualize(const CalibrationData &data, |
| 1022 | const CalibrationParameters &calibration_parameters) { |
| 1023 | PoseFilter filter(calibration_parameters.initial_orientation, |
| 1024 | calibration_parameters.pivot_to_camera, |
| 1025 | calibration_parameters.pivot_to_imu, |
| 1026 | calibration_parameters.gyro_bias, |
| 1027 | calibration_parameters.initial_state, |
| 1028 | calibration_parameters.board_to_world, |
| 1029 | calibration_parameters.pivot_to_camera_translation, |
| 1030 | calibration_parameters.pivot_to_imu_translation, |
| 1031 | calibration_parameters.gravity_scalar, |
| 1032 | calibration_parameters.accelerometer_bias); |
| 1033 | data.ReviewData(&filter); |
| 1034 | filter.Visualize(calibration_parameters); |
| 1035 | } |
| 1036 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1037 | } // namespace vision |
| 1038 | } // namespace frc971 |