blob: 7f08138a0f920e0f2f384cc089a0b6f7e0ca4af2 [file] [log] [blame]
James Kuszmaul7e958812023-02-11 15:34:31 -08001#ifndef FRC971_VISION_CALIBRATION_LIB_H_
2#define FRC971_VISION_CALIBRATION_LIB_H_
3#include <cmath>
James Kuszmaul7e958812023-02-11 15:34:31 -08004#include <regex>
5
6#include "Eigen/Dense"
7#include "Eigen/Geometry"
8#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07009#include <opencv2/calib3d.hpp>
10#include <opencv2/highgui/highgui.hpp>
11#include <opencv2/imgproc.hpp>
12
James Kuszmaul7e958812023-02-11 15:34:31 -080013#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"
18
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -080019namespace frc971::vision {
James Kuszmaul7e958812023-02-11 15:34:31 -080020
21class IntrinsicsCalibration {
22 public:
Jim Ostrowski3dc21642024-01-22 16:08:40 -080023 IntrinsicsCalibration(aos::EventLoop *event_loop, std::string_view hostname,
James Kuszmaul7e958812023-02-11 15:34:31 -080024 std::string_view camera_id,
25 std::string_view base_intrinsics_file,
26 bool display_undistorted,
27 std::string_view calibration_folder,
28 aos::ExitHandle *exit_handle);
29
30 void HandleCharuco(cv::Mat rgb_image,
31 const aos::monotonic_clock::time_point /*eof*/,
32 std::vector<cv::Vec4i> charuco_ids,
33 std::vector<std::vector<cv::Point2f>> charuco_corners,
34 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
35 std::vector<Eigen::Vector3d> tvecs_eigen);
36
37 void MaybeCalibrate();
38
39 static aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
40 BuildCalibration(cv::Mat camera_matrix, cv::Mat dist_coeffs,
Jim Ostrowski3dc21642024-01-22 16:08:40 -080041 aos::realtime_clock::time_point realtime_now,
42 std::string_view cpu_type, int cpu_number,
James Kuszmaul7e958812023-02-11 15:34:31 -080043 std::string_view camera_id, uint16_t team_number);
44
45 private:
46 static constexpr double kDeltaRThreshold = M_PI / 6.0;
47 static constexpr double kDeltaTThreshold = 0.3;
48
49 static constexpr double kFrameDeltaRLimit = M_PI / 60;
50 static constexpr double kFrameDeltaTLimit = 0.01;
51
Jim Ostrowski3dc21642024-01-22 16:08:40 -080052 std::string hostname_;
53 const std::optional<std::string_view> cpu_type_;
54 const std::optional<uint16_t> cpu_number_;
James Kuszmaul7e958812023-02-11 15:34:31 -080055 const std::string camera_id_;
56
57 std::vector<std::vector<int>> all_charuco_ids_;
58 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
59
60 Eigen::Affine3d H_camera_board_;
61 Eigen::Affine3d prev_H_camera_board_;
62 Eigen::Affine3d prev_image_H_camera_board_;
63
64 // Camera intrinsics that we will use to bootstrap the intrinsics estimation
65 // here. We make use of the intrinsics in this calibration to allow us to
66 // estimate the relative pose of the charuco board and then identify how much
67 // the board is moving.
68 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
69 base_intrinsics_;
70 CharucoExtractor charuco_extractor_;
71 ImageCallback image_callback_;
72
73 const bool display_undistorted_;
74 const std::string calibration_folder_;
75 aos::ExitHandle *exit_handle_;
76};
77
Stephan Pleinesd99b1ee2024-02-02 20:56:44 -080078} // namespace frc971::vision
James Kuszmaul7e958812023-02-11 15:34:31 -080079#endif // FRC971_VISION_CALIBRATION_LIB_H_