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