blob: f6c3cccded6ff9c88a47a84965265983e359c039 [file] [log] [blame]
Austin Schuhdcb6b362022-02-25 18:06:21 -08001#ifndef FRC971_VISION_EXTRINSICS_CALIBRATION_H_
2#define FRC971_VISION_EXTRINSICS_CALIBRATION_H_
3
4#include "Eigen/Dense"
5#include "Eigen/Geometry"
Philipp Schrader790cb542023-07-05 21:06:52 -07006
Austin Schuhdcb6b362022-02-25 18:06:21 -08007#include "frc971/vision/calibration_accumulator.h"
8
9namespace frc971 {
10namespace vision {
11
12struct CalibrationParameters {
13 Eigen::Quaternion<double> initial_orientation =
14 Eigen::Quaternion<double>::Identity();
Austin Schuh2895f4c2022-02-26 16:38:46 -080015 Eigen::Quaternion<double> pivot_to_camera =
16 Eigen::Quaternion<double>::Identity();
17 Eigen::Quaternion<double> pivot_to_imu =
Austin Schuhdcb6b362022-02-25 18:06:21 -080018 Eigen::Quaternion<double>::Identity();
19 Eigen::Quaternion<double> board_to_world =
20 Eigen::Quaternion<double>::Identity();
21
22 Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();
23 Eigen::Matrix<double, 6, 1> initial_state =
24 Eigen::Matrix<double, 6, 1>::Zero();
Austin Schuh2895f4c2022-02-26 16:38:46 -080025 Eigen::Matrix<double, 3, 1> pivot_to_camera_translation =
26 Eigen::Matrix<double, 3, 1>::Zero();
27 Eigen::Matrix<double, 3, 1> pivot_to_imu_translation =
Austin Schuhdcb6b362022-02-25 18:06:21 -080028 Eigen::Matrix<double, 3, 1>::Zero();
29
30 double gravity_scalar = 1.0;
31 Eigen::Matrix<double, 3, 1> accelerometer_bias =
32 Eigen::Matrix<double, 3, 1>::Zero();
Austin Schuh2895f4c2022-02-26 16:38:46 -080033
34 bool has_pivot = false;
Austin Schuhdcb6b362022-02-25 18:06:21 -080035};
36
James Kuszmaul086d0192023-02-11 15:35:03 -080037// Copies an Eigen matrix into a row-major vector of the data. Used for
38// converting into the flatbuffer TransformationMatrix type.
39std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H);
40
Austin Schuh2895f4c2022-02-26 16:38:46 -080041// Solves the mounting problem given the calibration data and parameters. The
42// parameters are used as the seed to the solver.
James Kuszmaul086d0192023-02-11 15:35:03 -080043// Produces a CameraCalibration flatbuffer which will have the relevant
44// extrinsics fields populated, so that it can subsequently be merged with the
45// intrinsics portion of the calibration.
46aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> Solve(
47 const CalibrationData &data, CalibrationParameters *calibration_parameters);
Austin Schuhdcb6b362022-02-25 18:06:21 -080048
Austin Schuh2895f4c2022-02-26 16:38:46 -080049// Plots the calibrated results to help visualize the fit.
Austin Schuhdcb6b362022-02-25 18:06:21 -080050void Plot(const CalibrationData &data,
51 const CalibrationParameters &calibration_parameters);
52
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080053// Shows the evolution of the calibration over time by visualizing relevant
54// coordinate frames in a virtual camera view
55void Visualize(const CalibrationData &data,
56 const CalibrationParameters &calibration_parameters);
57
Austin Schuhdcb6b362022-02-25 18:06:21 -080058} // namespace vision
59} // namespace frc971
60
61#endif // FRC971_VISION_EXTRINSICS_CALIBRATION_H_