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