blob: 97d719fadc7c6814e87c76235048cd5a6e195e47 [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
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -08009namespace frc971::vision {
Austin Schuhdcb6b362022-02-25 18:06:21 -080010
11struct CalibrationParameters {
12 Eigen::Quaternion<double> initial_orientation =
13 Eigen::Quaternion<double>::Identity();
Austin Schuh2895f4c2022-02-26 16:38:46 -080014 Eigen::Quaternion<double> pivot_to_camera =
15 Eigen::Quaternion<double>::Identity();
16 Eigen::Quaternion<double> pivot_to_imu =
Austin Schuhdcb6b362022-02-25 18:06:21 -080017 Eigen::Quaternion<double>::Identity();
18 Eigen::Quaternion<double> board_to_world =
19 Eigen::Quaternion<double>::Identity();
20
21 Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();
22 Eigen::Matrix<double, 6, 1> initial_state =
23 Eigen::Matrix<double, 6, 1>::Zero();
Austin Schuh2895f4c2022-02-26 16:38:46 -080024 Eigen::Matrix<double, 3, 1> pivot_to_camera_translation =
25 Eigen::Matrix<double, 3, 1>::Zero();
26 Eigen::Matrix<double, 3, 1> pivot_to_imu_translation =
Austin Schuhdcb6b362022-02-25 18:06:21 -080027 Eigen::Matrix<double, 3, 1>::Zero();
28
29 double gravity_scalar = 1.0;
30 Eigen::Matrix<double, 3, 1> accelerometer_bias =
31 Eigen::Matrix<double, 3, 1>::Zero();
Austin Schuh2895f4c2022-02-26 16:38:46 -080032
33 bool has_pivot = false;
Austin Schuhdcb6b362022-02-25 18:06:21 -080034};
35
James Kuszmaul086d0192023-02-11 15:35:03 -080036// Copies an Eigen matrix into a row-major vector of the data. Used for
37// converting into the flatbuffer TransformationMatrix type.
38std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H);
39
Austin Schuh2895f4c2022-02-26 16:38:46 -080040// Solves the mounting problem given the calibration data and parameters. The
41// parameters are used as the seed to the solver.
James Kuszmaul086d0192023-02-11 15:35:03 -080042// Produces a CameraCalibration flatbuffer which will have the relevant
43// extrinsics fields populated, so that it can subsequently be merged with the
44// intrinsics portion of the calibration.
45aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> Solve(
46 const CalibrationData &data, CalibrationParameters *calibration_parameters);
Austin Schuhdcb6b362022-02-25 18:06:21 -080047
Austin Schuh2895f4c2022-02-26 16:38:46 -080048// Plots the calibrated results to help visualize the fit.
Austin Schuhdcb6b362022-02-25 18:06:21 -080049void Plot(const CalibrationData &data,
50 const CalibrationParameters &calibration_parameters);
51
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080052// Shows the evolution of the calibration over time by visualizing relevant
53// coordinate frames in a virtual camera view
54void Visualize(const CalibrationData &data,
55 const CalibrationParameters &calibration_parameters);
56
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -080057} // namespace frc971::vision
Austin Schuhdcb6b362022-02-25 18:06:21 -080058
59#endif // FRC971_VISION_EXTRINSICS_CALIBRATION_H_