blob: 49224f03062d8cf0f7d875d81bf9e693694bb5e7 [file] [log] [blame]
James Kuszmaul7e958812023-02-11 15:34:31 -08001#include "frc971/vision/intrinsics_calibration_lib.h"
2
Stephan Pleinesf63bde82024-01-13 15:59:33 -08003namespace frc971::vision {
James Kuszmaul7e958812023-02-11 15:34:31 -08004
5IntrinsicsCalibration::IntrinsicsCalibration(
6 aos::EventLoop *event_loop, std::string_view pi, std::string_view camera_id,
7 std::string_view base_intrinsics_file, bool display_undistorted,
8 std::string_view calibration_folder, aos::ExitHandle *exit_handle)
9 : pi_(pi),
Jim Ostrowskicb8b4082024-01-21 02:23:46 -080010 pi_number_(aos::network::ParsePiOrOrinNumber(pi)),
James Kuszmaul7e958812023-02-11 15:34:31 -080011 camera_id_(camera_id),
12 prev_H_camera_board_(Eigen::Affine3d()),
13 prev_image_H_camera_board_(Eigen::Affine3d()),
14 base_intrinsics_(
15 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
16 base_intrinsics_file)),
17 charuco_extractor_(
18 event_loop, &base_intrinsics_.message(), TargetType::kCharuco,
19 "/camera",
20 [this](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof,
21 std::vector<cv::Vec4i> charuco_ids,
22 std::vector<std::vector<cv::Point2f>> charuco_corners,
23 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
24 std::vector<Eigen::Vector3d> tvecs_eigen) {
25 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
26 rvecs_eigen, tvecs_eigen);
27 }),
Jim Ostrowskicb8b4082024-01-21 02:23:46 -080028 // TODO: Need to make this work with /pi or /orin
James Kuszmaul7e958812023-02-11 15:34:31 -080029 image_callback_(
30 event_loop,
Jim Ostrowskicb8b4082024-01-21 02:23:46 -080031 absl::StrCat(
32 "/pi",
33 std::to_string(aos::network::ParsePiOrOrinNumber(pi).value()),
34 "/camera"),
James Kuszmaul7e958812023-02-11 15:34:31 -080035 [this](cv::Mat rgb_image,
36 const aos::monotonic_clock::time_point eof) {
37 charuco_extractor_.HandleImage(rgb_image, eof);
38 },
39 std::chrono::milliseconds(5)),
40 display_undistorted_(display_undistorted),
41 calibration_folder_(calibration_folder),
42 exit_handle_(exit_handle) {
43 CHECK(pi_number_) << ": Invalid pi number " << pi
44 << ", failed to parse pi number";
45 std::regex re{"^[0-9][0-9]-[0-9][0-9]"};
46 CHECK(std::regex_match(camera_id_, re))
47 << ": Invalid camera_id '" << camera_id_ << "', should be of form YY-NN";
48}
49
50void IntrinsicsCalibration::HandleCharuco(
51 cv::Mat rgb_image, const aos::monotonic_clock::time_point /*eof*/,
52 std::vector<cv::Vec4i> charuco_ids,
53 std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
54 std::vector<Eigen::Vector3d> rvecs_eigen,
55 std::vector<Eigen::Vector3d> tvecs_eigen) {
56 // Reduce resolution displayed on remote viewer to prevent lag
57 cv::resize(rgb_image, rgb_image,
58 cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
59 cv::imshow("Display", rgb_image);
60
61 if (display_undistorted_) {
62 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
63 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
64 cv::undistort(rgb_image, undistorted_rgb_image,
65 charuco_extractor_.camera_matrix(),
66 charuco_extractor_.dist_coeffs());
67
68 cv::imshow("Display undist", undistorted_rgb_image);
69 }
70
71 int keystroke = cv::waitKey(1);
72
73 // If we haven't got a valid pose estimate, don't use these points
74 if (!valid) {
75 return;
76 }
77 CHECK(tvecs_eigen.size() == 1)
78 << "Charuco board should only return one translational pose";
79 CHECK(rvecs_eigen.size() == 1)
80 << "Charuco board should only return one rotational pose";
81 // Calibration calculates rotation and translation delta from last image
82 // stored to automatically capture next image
83
84 Eigen::Affine3d H_board_camera =
85 Eigen::Translation3d(tvecs_eigen[0]) *
86 Eigen::AngleAxisd(rvecs_eigen[0].norm(),
87 rvecs_eigen[0] / rvecs_eigen[0].norm());
88 Eigen::Affine3d H_camera_board_ = H_board_camera.inverse();
89 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
90
91 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
92
93 Eigen::Vector3d delta_t = H_delta.translation();
94
95 double r_norm = std::abs(delta_r.angle());
96 double t_norm = delta_t.norm();
97
98 bool store_image = false;
99 double percent_motion =
100 std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold);
101 LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; Moved "
102 << percent_motion << "% of what's needed";
103 // Verify that camera has moved enough from last stored image
104 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
105 // frame_ refers to deltas between current and last captured image
106 Eigen::Affine3d frame_H_delta = H_board_camera * prev_image_H_camera_board_;
107
108 Eigen::AngleAxisd frame_delta_r =
109 Eigen::AngleAxisd(frame_H_delta.rotation());
110
111 Eigen::Vector3d frame_delta_t = frame_H_delta.translation();
112
113 double frame_r_norm = std::abs(frame_delta_r.angle());
114 double frame_t_norm = frame_delta_t.norm();
115
116 // Make sure camera has stopped moving before storing image
117 store_image =
118 frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit;
119 double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit,
120 frame_t_norm / kFrameDeltaTLimit);
121 LOG(INFO) << "Captured: " << all_charuco_ids_.size()
122 << "points; Moved enough (" << percent_motion
123 << "%); Need to stop (last motion was " << percent_stop
124 << "% of limit; needs to be < 1 to capture)";
125 }
126 prev_image_H_camera_board_ = H_camera_board_;
127
128 if (store_image) {
129 if (valid) {
130 prev_H_camera_board_ = H_camera_board_;
131
132 // Unpack the Charuco ids from Vec4i
133 std::vector<int> charuco_ids_int;
134 for (cv::Vec4i charuco_id : charuco_ids) {
135 charuco_ids_int.emplace_back(charuco_id[0]);
136 }
137 all_charuco_ids_.emplace_back(std::move(charuco_ids_int));
138 all_charuco_corners_.emplace_back(std::move(charuco_corners[0]));
139
140 if (r_norm > kDeltaRThreshold) {
141 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
142 << kDeltaRThreshold;
143 }
144 if (t_norm > kDeltaTThreshold) {
145 LOG(INFO) << "Triggered by translation delta = " << t_norm << " > "
146 << kDeltaTThreshold;
147 }
148 }
149
150 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
151 exit_handle_->Exit();
152 }
153}
154
155aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
156IntrinsicsCalibration::BuildCalibration(
157 cv::Mat camera_matrix, cv::Mat dist_coeffs,
158 aos::realtime_clock::time_point realtime_now, int pi_number,
159 std::string_view camera_id, uint16_t team_number) {
160 flatbuffers::FlatBufferBuilder fbb;
161 flatbuffers::Offset<flatbuffers::String> name_offset =
162 fbb.CreateString(absl::StrFormat("pi%d", pi_number));
163 flatbuffers::Offset<flatbuffers::String> camera_id_offset =
164 fbb.CreateString(camera_id);
165 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
166 fbb.CreateVector<float>(9u, [&camera_matrix](size_t i) {
167 return static_cast<float>(
168 reinterpret_cast<double *>(camera_matrix.data)[i]);
169 });
170
171 flatbuffers::Offset<flatbuffers::Vector<float>>
172 distortion_coefficients_offset =
173 fbb.CreateVector<float>(5u, [&dist_coeffs](size_t i) {
174 return static_cast<float>(
175 reinterpret_cast<double *>(dist_coeffs.data)[i]);
176 });
177
178 calibration::CameraCalibration::Builder camera_calibration_builder(fbb);
179
180 camera_calibration_builder.add_node_name(name_offset);
181 camera_calibration_builder.add_team_number(team_number);
182 camera_calibration_builder.add_camera_id(camera_id_offset);
183 camera_calibration_builder.add_calibration_timestamp(
184 realtime_now.time_since_epoch().count());
185 camera_calibration_builder.add_intrinsics(intrinsics_offset);
186 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
187 fbb.Finish(camera_calibration_builder.Finish());
188
189 return fbb.Release();
190}
191
192void IntrinsicsCalibration::MaybeCalibrate() {
193 // TODO: This number should depend on coarse vs. fine pattern
194 // Maybe just on total # of ids found, not just images
195 if (all_charuco_ids_.size() >= 50) {
196 LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
197 << " images";
198 cv::Mat camera_matrix, dist_coeffs;
199 std::vector<cv::Mat> rvecs, tvecs;
200 cv::Mat std_deviations_intrinsics, std_deviations_extrinsics,
201 per_view_errors;
202
203 // Set calibration flags (same as in calibrateCamera() function)
204 int calibration_flags = 0;
205 cv::Size img_size(640, 480);
206 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
207 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
208 img_size, camera_matrix, dist_coeffs, rvecs, tvecs,
209 std_deviations_intrinsics, std_deviations_extrinsics, per_view_errors,
210 calibration_flags);
211 CHECK_LE(reprojection_error, 1.0)
212 << ": Reproduction error is bad-- greater than 1 pixel.";
213 LOG(INFO) << "Reprojection Error is " << reprojection_error;
214
215 const aos::realtime_clock::time_point realtime_now =
216 aos::realtime_clock::now();
217 std::optional<uint16_t> team_number =
Jim Ostrowskicb8b4082024-01-21 02:23:46 -0800218 aos::network::team_number_internal::ParsePiOrOrinTeamNumber(pi_);
James Kuszmaul7e958812023-02-11 15:34:31 -0800219 CHECK(team_number) << ": Invalid pi hostname " << pi_
220 << ", failed to parse team number";
221 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
222 camera_calibration = BuildCalibration(camera_matrix, dist_coeffs,
223 realtime_now, pi_number_.value(),
224 camera_id_, team_number.value());
225 std::stringstream time_ss;
226 time_ss << realtime_now;
227
228 const std::string calibration_filename =
229 calibration_folder_ +
230 absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json",
231 team_number.value(), pi_number_.value(), camera_id_,
232 time_ss.str());
233
234 LOG(INFO) << calibration_filename << " -> "
235 << aos::FlatbufferToJson(camera_calibration,
236 {.multi_line = true});
237
238 aos::util::WriteStringToFileOrDie(
239 calibration_filename,
240 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
241 } else {
242 LOG(INFO) << "Skipping calibration due to not enough images.";
243 }
244}
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800245} // namespace frc971::vision