James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 1 | #ifndef FRC971_VISION_CALIBRATION_LIB_H_ |
| 2 | #define FRC971_VISION_CALIBRATION_LIB_H_ |
| 3 | #include <cmath> |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 4 | #include <regex> |
| 5 | |
| 6 | #include "Eigen/Dense" |
| 7 | #include "Eigen/Geometry" |
| 8 | #include "absl/strings/str_format.h" |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 9 | #include <opencv2/calib3d.hpp> |
| 10 | #include <opencv2/highgui/highgui.hpp> |
| 11 | #include <opencv2/imgproc.hpp> |
| 12 | |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 13 | #include "aos/events/event_loop.h" |
| 14 | #include "aos/network/team_number.h" |
| 15 | #include "aos/time/time.h" |
| 16 | #include "aos/util/file.h" |
| 17 | #include "frc971/vision/charuco_lib.h" |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 18 | #include "frc971/vision/vision_util_lib.h" |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 19 | |
Stephan Pleines | d99b1ee | 2024-02-02 20:56:44 -0800 | [diff] [blame] | 20 | namespace frc971::vision { |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 21 | |
| 22 | class IntrinsicsCalibration { |
| 23 | public: |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 24 | IntrinsicsCalibration(aos::EventLoop *event_loop, std::string_view hostname, |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 25 | std::string_view camera_channel, |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 26 | std::string_view camera_id, |
| 27 | std::string_view base_intrinsics_file, |
| 28 | bool display_undistorted, |
| 29 | std::string_view calibration_folder, |
| 30 | aos::ExitHandle *exit_handle); |
| 31 | |
| 32 | void HandleCharuco(cv::Mat rgb_image, |
| 33 | const aos::monotonic_clock::time_point /*eof*/, |
| 34 | std::vector<cv::Vec4i> charuco_ids, |
| 35 | std::vector<std::vector<cv::Point2f>> charuco_corners, |
| 36 | bool valid, std::vector<Eigen::Vector3d> rvecs_eigen, |
| 37 | std::vector<Eigen::Vector3d> tvecs_eigen); |
| 38 | |
| 39 | void MaybeCalibrate(); |
| 40 | |
| 41 | static aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 42 | BuildCalibration(cv::Mat camera_matrix, cv::Mat dist_coeffs, |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 43 | aos::realtime_clock::time_point realtime_now, |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 44 | std::string_view cpu_type, uint16_t cpu_number, |
| 45 | std::string_view camera_channel, std::string_view camera_id, |
Jim Ostrowski | fa71786 | 2024-02-11 21:16:02 -0800 | [diff] [blame] | 46 | uint16_t team_number, double reprojection_error); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 47 | |
| 48 | private: |
| 49 | static constexpr double kDeltaRThreshold = M_PI / 6.0; |
| 50 | static constexpr double kDeltaTThreshold = 0.3; |
| 51 | |
| 52 | static constexpr double kFrameDeltaRLimit = M_PI / 60; |
| 53 | static constexpr double kFrameDeltaTLimit = 0.01; |
| 54 | |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 55 | std::string hostname_; |
| 56 | const std::optional<std::string_view> cpu_type_; |
| 57 | const std::optional<uint16_t> cpu_number_; |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 58 | const std::string camera_channel_; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 59 | const std::string camera_id_; |
| 60 | |
| 61 | std::vector<std::vector<int>> all_charuco_ids_; |
| 62 | std::vector<std::vector<cv::Point2f>> all_charuco_corners_; |
| 63 | |
| 64 | Eigen::Affine3d H_camera_board_; |
| 65 | Eigen::Affine3d prev_H_camera_board_; |
| 66 | Eigen::Affine3d prev_image_H_camera_board_; |
| 67 | |
| 68 | // Camera intrinsics that we will use to bootstrap the intrinsics estimation |
| 69 | // here. We make use of the intrinsics in this calibration to allow us to |
| 70 | // estimate the relative pose of the charuco board and then identify how much |
| 71 | // the board is moving. |
| 72 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 73 | base_intrinsics_; |
| 74 | CharucoExtractor charuco_extractor_; |
| 75 | ImageCallback image_callback_; |
| 76 | |
| 77 | const bool display_undistorted_; |
| 78 | const std::string calibration_folder_; |
| 79 | aos::ExitHandle *exit_handle_; |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 80 | |
| 81 | bool exit_collection_; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 82 | }; |
| 83 | |
Stephan Pleines | d99b1ee | 2024-02-02 20:56:44 -0800 | [diff] [blame] | 84 | } // namespace frc971::vision |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 85 | #endif // FRC971_VISION_CALIBRATION_LIB_H_ |