Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 1 | #ifndef FRC971_VISION_EXTRINSICS_CALIBRATION_H_ |
| 2 | #define FRC971_VISION_EXTRINSICS_CALIBRATION_H_ |
| 3 | |
| 4 | #include "Eigen/Dense" |
| 5 | #include "Eigen/Geometry" |
| 6 | #include "frc971/vision/calibration_accumulator.h" |
| 7 | |
| 8 | namespace frc971 { |
| 9 | namespace vision { |
| 10 | |
| 11 | struct CalibrationParameters { |
| 12 | Eigen::Quaternion<double> initial_orientation = |
| 13 | Eigen::Quaternion<double>::Identity(); |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 14 | Eigen::Quaternion<double> pivot_to_camera = |
| 15 | Eigen::Quaternion<double>::Identity(); |
| 16 | Eigen::Quaternion<double> pivot_to_imu = |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 17 | 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 24 | 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 Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 27 | 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 Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 32 | |
| 33 | bool has_pivot = false; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 34 | }; |
| 35 | |
James Kuszmaul | 086d019 | 2023-02-11 15:35:03 -0800 | [diff] [blame^] | 36 | // Copies an Eigen matrix into a row-major vector of the data. Used for |
| 37 | // converting into the flatbuffer TransformationMatrix type. |
| 38 | std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H); |
| 39 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 40 | // Solves the mounting problem given the calibration data and parameters. The |
| 41 | // parameters are used as the seed to the solver. |
James Kuszmaul | 086d019 | 2023-02-11 15:35:03 -0800 | [diff] [blame^] | 42 | // 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. |
| 45 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> Solve( |
| 46 | const CalibrationData &data, CalibrationParameters *calibration_parameters); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 47 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 48 | // Plots the calibrated results to help visualize the fit. |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 49 | void Plot(const CalibrationData &data, |
| 50 | const CalibrationParameters &calibration_parameters); |
| 51 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 52 | // Shows the evolution of the calibration over time by visualizing relevant |
| 53 | // coordinate frames in a virtual camera view |
| 54 | void Visualize(const CalibrationData &data, |
| 55 | const CalibrationParameters &calibration_parameters); |
| 56 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 57 | } // namespace vision |
| 58 | } // namespace frc971 |
| 59 | |
| 60 | #endif // FRC971_VISION_EXTRINSICS_CALIBRATION_H_ |