blob: 3076ed996e5b981be8b25496e5e849afc39c66c2 [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
19namespace frc971 {
20namespace vision {
21
22class IntrinsicsCalibration {
23 public:
Jim Ostrowski3dc21642024-01-22 16:08:40 -080024 IntrinsicsCalibration(aos::EventLoop *event_loop, std::string_view hostname,
James Kuszmaul7e958812023-02-11 15:34:31 -080025 std::string_view camera_id,
26 std::string_view base_intrinsics_file,
27 bool display_undistorted,
28 std::string_view calibration_folder,
29 aos::ExitHandle *exit_handle);
30
31 void HandleCharuco(cv::Mat rgb_image,
32 const aos::monotonic_clock::time_point /*eof*/,
33 std::vector<cv::Vec4i> charuco_ids,
34 std::vector<std::vector<cv::Point2f>> charuco_corners,
35 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
36 std::vector<Eigen::Vector3d> tvecs_eigen);
37
38 void MaybeCalibrate();
39
40 static aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
41 BuildCalibration(cv::Mat camera_matrix, cv::Mat dist_coeffs,
Jim Ostrowski3dc21642024-01-22 16:08:40 -080042 aos::realtime_clock::time_point realtime_now,
43 std::string_view cpu_type, int cpu_number,
James Kuszmaul7e958812023-02-11 15:34:31 -080044 std::string_view camera_id, uint16_t team_number);
45
46 private:
47 static constexpr double kDeltaRThreshold = M_PI / 6.0;
48 static constexpr double kDeltaTThreshold = 0.3;
49
50 static constexpr double kFrameDeltaRLimit = M_PI / 60;
51 static constexpr double kFrameDeltaTLimit = 0.01;
52
Jim Ostrowski3dc21642024-01-22 16:08:40 -080053 std::string hostname_;
54 const std::optional<std::string_view> cpu_type_;
55 const std::optional<uint16_t> cpu_number_;
James Kuszmaul7e958812023-02-11 15:34:31 -080056 const std::string camera_id_;
57
58 std::vector<std::vector<int>> all_charuco_ids_;
59 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
60
61 Eigen::Affine3d H_camera_board_;
62 Eigen::Affine3d prev_H_camera_board_;
63 Eigen::Affine3d prev_image_H_camera_board_;
64
65 // Camera intrinsics that we will use to bootstrap the intrinsics estimation
66 // here. We make use of the intrinsics in this calibration to allow us to
67 // estimate the relative pose of the charuco board and then identify how much
68 // the board is moving.
69 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
70 base_intrinsics_;
71 CharucoExtractor charuco_extractor_;
72 ImageCallback image_callback_;
73
74 const bool display_undistorted_;
75 const std::string calibration_folder_;
76 aos::ExitHandle *exit_handle_;
77};
78
79} // namespace vision
80} // namespace frc971
81#endif // FRC971_VISION_CALIBRATION_LIB_H_