blob: 6f242f476f81642f78a5b0551d3a9902bd861d63 [file] [log] [blame]
James Kuszmaul7e958812023-02-11 15:34:31 -08001#include "frc971/vision/intrinsics_calibration_lib.h"
2
Jim Ostrowskib974cca2024-01-28 15:07:50 -08003DECLARE_bool(visualize);
4
Stephan Pleinesf63bde82024-01-13 15:59:33 -08005namespace frc971::vision {
James Kuszmaul7e958812023-02-11 15:34:31 -08006
Jim Ostrowskib974cca2024-01-28 15:07:50 -08007// Found that under 50 ms would fail image too often on intrinsics with
8// visualize on
9constexpr aos::monotonic_clock::duration kMaxImageAge =
10 aos::monotonic_clock::duration(std::chrono::milliseconds(50));
11
James Kuszmaul7e958812023-02-11 15:34:31 -080012IntrinsicsCalibration::IntrinsicsCalibration(
Jim Ostrowski3dc21642024-01-22 16:08:40 -080013 aos::EventLoop *event_loop, std::string_view hostname,
Jim Ostrowskib974cca2024-01-28 15:07:50 -080014 std::string_view camera_channel, std::string_view camera_id,
15 std::string_view base_intrinsics_file, bool display_undistorted,
16 std::string_view calibration_folder, aos::ExitHandle *exit_handle)
Jim Ostrowski3dc21642024-01-22 16:08:40 -080017 : hostname_(hostname),
18 cpu_type_(aos::network::ParsePiOrOrin(hostname_)),
19 cpu_number_(aos::network::ParsePiOrOrinNumber(hostname_)),
Jim Ostrowskib974cca2024-01-28 15:07:50 -080020 camera_channel_(camera_channel),
James Kuszmaul7e958812023-02-11 15:34:31 -080021 camera_id_(camera_id),
22 prev_H_camera_board_(Eigen::Affine3d()),
23 prev_image_H_camera_board_(Eigen::Affine3d()),
24 base_intrinsics_(
25 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
26 base_intrinsics_file)),
27 charuco_extractor_(
28 event_loop, &base_intrinsics_.message(), TargetType::kCharuco,
Jim Ostrowskib974cca2024-01-28 15:07:50 -080029 camera_channel_,
James Kuszmaul7e958812023-02-11 15:34:31 -080030 [this](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof,
31 std::vector<cv::Vec4i> charuco_ids,
32 std::vector<std::vector<cv::Point2f>> charuco_corners,
33 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
34 std::vector<Eigen::Vector3d> tvecs_eigen) {
35 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
36 rvecs_eigen, tvecs_eigen);
37 }),
38 image_callback_(
39 event_loop,
Jim Ostrowski3dc21642024-01-22 16:08:40 -080040 absl::StrCat("/", aos::network::ParsePiOrOrin(hostname_).value(),
Jim Ostrowskib974cca2024-01-28 15:07:50 -080041 std::to_string(cpu_number_.value()), camera_channel_),
James Kuszmaul7e958812023-02-11 15:34:31 -080042 [this](cv::Mat rgb_image,
43 const aos::monotonic_clock::time_point eof) {
44 charuco_extractor_.HandleImage(rgb_image, eof);
45 },
Jim Ostrowskib974cca2024-01-28 15:07:50 -080046 kMaxImageAge),
James Kuszmaul7e958812023-02-11 15:34:31 -080047 display_undistorted_(display_undistorted),
48 calibration_folder_(calibration_folder),
49 exit_handle_(exit_handle) {
Jim Ostrowskib974cca2024-01-28 15:07:50 -080050 LOG(INFO) << "Hostname is: " << hostname_ << " and camera channel is "
51 << camera_channel_;
52
Jim Ostrowski3dc21642024-01-22 16:08:40 -080053 CHECK(cpu_number_) << ": Invalid cpu number " << hostname_
54 << ", failed to parse cpu number";
James Kuszmaul7e958812023-02-11 15:34:31 -080055 std::regex re{"^[0-9][0-9]-[0-9][0-9]"};
56 CHECK(std::regex_match(camera_id_, re))
57 << ": Invalid camera_id '" << camera_id_ << "', should be of form YY-NN";
58}
59
60void IntrinsicsCalibration::HandleCharuco(
61 cv::Mat rgb_image, const aos::monotonic_clock::time_point /*eof*/,
62 std::vector<cv::Vec4i> charuco_ids,
63 std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
64 std::vector<Eigen::Vector3d> rvecs_eigen,
65 std::vector<Eigen::Vector3d> tvecs_eigen) {
Jim Ostrowskib974cca2024-01-28 15:07:50 -080066 if (FLAGS_visualize) {
67 // Reduce resolution displayed on remote viewer to prevent lag
68 cv::resize(rgb_image, rgb_image,
69 cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
70 cv::imshow("Display", rgb_image);
James Kuszmaul7e958812023-02-11 15:34:31 -080071
Jim Ostrowskib974cca2024-01-28 15:07:50 -080072 if (display_undistorted_) {
73 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
74 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
75 cv::undistort(rgb_image, undistorted_rgb_image,
76 charuco_extractor_.camera_matrix(),
77 charuco_extractor_.dist_coeffs());
James Kuszmaul7e958812023-02-11 15:34:31 -080078
Jim Ostrowskib974cca2024-01-28 15:07:50 -080079 cv::imshow("Display undist", undistorted_rgb_image);
80 }
James Kuszmaul7e958812023-02-11 15:34:31 -080081 }
82
83 int keystroke = cv::waitKey(1);
84
85 // If we haven't got a valid pose estimate, don't use these points
86 if (!valid) {
Jim Ostrowskib974cca2024-01-28 15:07:50 -080087 LOG(INFO) << "Skipping because pose is not valid";
James Kuszmaul7e958812023-02-11 15:34:31 -080088 return;
89 }
90 CHECK(tvecs_eigen.size() == 1)
91 << "Charuco board should only return one translational pose";
92 CHECK(rvecs_eigen.size() == 1)
93 << "Charuco board should only return one rotational pose";
94 // Calibration calculates rotation and translation delta from last image
95 // stored to automatically capture next image
96
97 Eigen::Affine3d H_board_camera =
98 Eigen::Translation3d(tvecs_eigen[0]) *
99 Eigen::AngleAxisd(rvecs_eigen[0].norm(),
100 rvecs_eigen[0] / rvecs_eigen[0].norm());
101 Eigen::Affine3d H_camera_board_ = H_board_camera.inverse();
102 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
103
104 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
105
106 Eigen::Vector3d delta_t = H_delta.translation();
107
108 double r_norm = std::abs(delta_r.angle());
109 double t_norm = delta_t.norm();
110
111 bool store_image = false;
112 double percent_motion =
113 std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold);
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800114 LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; \nMoved "
115 << static_cast<int>(percent_motion * 100) << "% of what's needed";
James Kuszmaul7e958812023-02-11 15:34:31 -0800116 // Verify that camera has moved enough from last stored image
117 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
118 // frame_ refers to deltas between current and last captured image
119 Eigen::Affine3d frame_H_delta = H_board_camera * prev_image_H_camera_board_;
120
121 Eigen::AngleAxisd frame_delta_r =
122 Eigen::AngleAxisd(frame_H_delta.rotation());
123
124 Eigen::Vector3d frame_delta_t = frame_H_delta.translation();
125
126 double frame_r_norm = std::abs(frame_delta_r.angle());
127 double frame_t_norm = frame_delta_t.norm();
128
129 // Make sure camera has stopped moving before storing image
130 store_image =
131 frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit;
132 double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit,
133 frame_t_norm / kFrameDeltaTLimit);
134 LOG(INFO) << "Captured: " << all_charuco_ids_.size()
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800135 << "points; \nMoved enough ("
136 << static_cast<int>(percent_motion * 100)
137 << "%); Need to stop (last motion was "
138 << static_cast<int>(percent_stop * 100)
139 << "% of limit; needs to be < 1% to capture)";
James Kuszmaul7e958812023-02-11 15:34:31 -0800140 }
141 prev_image_H_camera_board_ = H_camera_board_;
142
143 if (store_image) {
144 if (valid) {
145 prev_H_camera_board_ = H_camera_board_;
146
147 // Unpack the Charuco ids from Vec4i
148 std::vector<int> charuco_ids_int;
149 for (cv::Vec4i charuco_id : charuco_ids) {
150 charuco_ids_int.emplace_back(charuco_id[0]);
151 }
152 all_charuco_ids_.emplace_back(std::move(charuco_ids_int));
153 all_charuco_corners_.emplace_back(std::move(charuco_corners[0]));
154
155 if (r_norm > kDeltaRThreshold) {
156 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
157 << kDeltaRThreshold;
158 }
159 if (t_norm > kDeltaTThreshold) {
160 LOG(INFO) << "Triggered by translation delta = " << t_norm << " > "
161 << kDeltaTThreshold;
162 }
163 }
164
165 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
166 exit_handle_->Exit();
167 }
168}
169
170aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
171IntrinsicsCalibration::BuildCalibration(
172 cv::Mat camera_matrix, cv::Mat dist_coeffs,
Jim Ostrowski3dc21642024-01-22 16:08:40 -0800173 aos::realtime_clock::time_point realtime_now, std::string_view cpu_type,
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800174 uint16_t cpu_number, std::string_view camera_channel,
175 std::string_view camera_id, uint16_t team_number) {
James Kuszmaul7e958812023-02-11 15:34:31 -0800176 flatbuffers::FlatBufferBuilder fbb;
177 flatbuffers::Offset<flatbuffers::String> name_offset =
Jim Ostrowski3dc21642024-01-22 16:08:40 -0800178 fbb.CreateString(absl::StrFormat("%s%d", cpu_type, cpu_number));
James Kuszmaul7e958812023-02-11 15:34:31 -0800179 flatbuffers::Offset<flatbuffers::String> camera_id_offset =
180 fbb.CreateString(camera_id);
181 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
182 fbb.CreateVector<float>(9u, [&camera_matrix](size_t i) {
183 return static_cast<float>(
184 reinterpret_cast<double *>(camera_matrix.data)[i]);
185 });
186
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800187 std::optional<uint16_t> camera_number =
188 frc971::vision::CameraNumberFromChannel(std::string(camera_channel));
189
James Kuszmaul7e958812023-02-11 15:34:31 -0800190 flatbuffers::Offset<flatbuffers::Vector<float>>
191 distortion_coefficients_offset =
192 fbb.CreateVector<float>(5u, [&dist_coeffs](size_t i) {
193 return static_cast<float>(
194 reinterpret_cast<double *>(dist_coeffs.data)[i]);
195 });
196
197 calibration::CameraCalibration::Builder camera_calibration_builder(fbb);
198
199 camera_calibration_builder.add_node_name(name_offset);
200 camera_calibration_builder.add_team_number(team_number);
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800201 camera_calibration_builder.add_camera_number(camera_number.value());
James Kuszmaul7e958812023-02-11 15:34:31 -0800202 camera_calibration_builder.add_camera_id(camera_id_offset);
203 camera_calibration_builder.add_calibration_timestamp(
204 realtime_now.time_since_epoch().count());
205 camera_calibration_builder.add_intrinsics(intrinsics_offset);
206 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
207 fbb.Finish(camera_calibration_builder.Finish());
208
209 return fbb.Release();
210}
211
212void IntrinsicsCalibration::MaybeCalibrate() {
213 // TODO: This number should depend on coarse vs. fine pattern
214 // Maybe just on total # of ids found, not just images
215 if (all_charuco_ids_.size() >= 50) {
216 LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
217 << " images";
218 cv::Mat camera_matrix, dist_coeffs;
219 std::vector<cv::Mat> rvecs, tvecs;
220 cv::Mat std_deviations_intrinsics, std_deviations_extrinsics,
221 per_view_errors;
222
223 // Set calibration flags (same as in calibrateCamera() function)
224 int calibration_flags = 0;
225 cv::Size img_size(640, 480);
226 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
227 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
228 img_size, camera_matrix, dist_coeffs, rvecs, tvecs,
229 std_deviations_intrinsics, std_deviations_extrinsics, per_view_errors,
230 calibration_flags);
231 CHECK_LE(reprojection_error, 1.0)
232 << ": Reproduction error is bad-- greater than 1 pixel.";
233 LOG(INFO) << "Reprojection Error is " << reprojection_error;
234
235 const aos::realtime_clock::time_point realtime_now =
236 aos::realtime_clock::now();
237 std::optional<uint16_t> team_number =
Jim Ostrowski3dc21642024-01-22 16:08:40 -0800238 aos::network::team_number_internal::ParsePiOrOrinTeamNumber(hostname_);
239 CHECK(team_number) << ": Invalid hostname " << hostname_
James Kuszmaul7e958812023-02-11 15:34:31 -0800240 << ", failed to parse team number";
241 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800242 camera_calibration =
243 BuildCalibration(camera_matrix, dist_coeffs, realtime_now,
244 cpu_type_.value(), cpu_number_.value(),
245 camera_channel_, camera_id_, team_number.value());
James Kuszmaul7e958812023-02-11 15:34:31 -0800246 std::stringstream time_ss;
247 time_ss << realtime_now;
248
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800249 std::string camera_number_optional = "";
250 std::optional<uint16_t> camera_number =
251 frc971::vision::CameraNumberFromChannel(camera_channel_);
252 if (camera_number != std::nullopt) {
253 camera_number_optional = "-" + std::to_string(camera_number.value());
254 }
James Kuszmaul7e958812023-02-11 15:34:31 -0800255 const std::string calibration_filename =
256 calibration_folder_ +
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800257 absl::StrFormat("/calibration_%s-%d-%d%s_cam-%s_%s.json",
Jim Ostrowski3dc21642024-01-22 16:08:40 -0800258 cpu_type_.value(), team_number.value(),
Jim Ostrowskib974cca2024-01-28 15:07:50 -0800259 cpu_number_.value(), camera_number_optional, camera_id_,
260 time_ss.str());
James Kuszmaul7e958812023-02-11 15:34:31 -0800261
262 LOG(INFO) << calibration_filename << " -> "
263 << aos::FlatbufferToJson(camera_calibration,
264 {.multi_line = true});
265
266 aos::util::WriteStringToFileOrDie(
267 calibration_filename,
268 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
269 } else {
270 LOG(INFO) << "Skipping calibration due to not enough images.";
271 }
272}
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800273} // namespace frc971::vision