James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 1 | #include "frc971/vision/intrinsics_calibration_lib.h" |
| 2 | |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 3 | #include "absl/flags/declare.h" |
| 4 | #include "absl/flags/flag.h" |
| 5 | |
| 6 | ABSL_DECLARE_FLAG(bool, visualize); |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 7 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 8 | namespace frc971::vision { |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 9 | |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 10 | // Found that under 50 ms would fail image too often on intrinsics with |
| 11 | // visualize on |
| 12 | constexpr aos::monotonic_clock::duration kMaxImageAge = |
| 13 | aos::monotonic_clock::duration(std::chrono::milliseconds(50)); |
| 14 | |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 15 | IntrinsicsCalibration::IntrinsicsCalibration( |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 16 | aos::EventLoop *event_loop, std::string_view hostname, |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 17 | std::string_view camera_channel, std::string_view camera_id, |
| 18 | std::string_view base_intrinsics_file, bool display_undistorted, |
| 19 | std::string_view calibration_folder, aos::ExitHandle *exit_handle) |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 20 | : hostname_(hostname), |
| 21 | cpu_type_(aos::network::ParsePiOrOrin(hostname_)), |
| 22 | cpu_number_(aos::network::ParsePiOrOrinNumber(hostname_)), |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 23 | camera_channel_(camera_channel), |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 24 | camera_id_(camera_id), |
| 25 | prev_H_camera_board_(Eigen::Affine3d()), |
| 26 | prev_image_H_camera_board_(Eigen::Affine3d()), |
| 27 | base_intrinsics_( |
| 28 | aos::JsonFileToFlatbuffer<calibration::CameraCalibration>( |
| 29 | base_intrinsics_file)), |
| 30 | charuco_extractor_( |
| 31 | event_loop, &base_intrinsics_.message(), TargetType::kCharuco, |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 32 | camera_channel_, |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 33 | [this](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof, |
| 34 | std::vector<cv::Vec4i> charuco_ids, |
| 35 | std::vector<std::vector<cv::Point2f>> charuco_corners, |
| 36 | bool valid, std::vector<Eigen::Vector3d> rvecs_eigen, |
| 37 | std::vector<Eigen::Vector3d> tvecs_eigen) { |
| 38 | HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid, |
| 39 | rvecs_eigen, tvecs_eigen); |
| 40 | }), |
| 41 | image_callback_( |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 42 | event_loop, camera_channel_, |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 43 | [this](cv::Mat rgb_image, |
| 44 | const aos::monotonic_clock::time_point eof) { |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 45 | if (exit_collection_) { |
| 46 | return; |
| 47 | } |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 48 | charuco_extractor_.HandleImage(rgb_image, eof); |
| 49 | }, |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 50 | kMaxImageAge), |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 51 | display_undistorted_(display_undistorted), |
| 52 | calibration_folder_(calibration_folder), |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 53 | exit_handle_(exit_handle), |
| 54 | exit_collection_(false) { |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 55 | if (!absl::GetFlag(FLAGS_visualize)) { |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 56 | // The only way to exit into the calibration routines is by hitting "q" |
| 57 | // while visualization is running. The event_loop doesn't pause enough |
| 58 | // to handle ctrl-c exit requests |
| 59 | LOG(INFO) << "Setting visualize to true, since currently the intrinsics " |
| 60 | "only works this way"; |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 61 | absl::SetFlag(&FLAGS_visualize, true); |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 62 | } |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 63 | LOG(INFO) << "Hostname is: " << hostname_ << " and camera channel is " |
| 64 | << camera_channel_; |
| 65 | |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 66 | CHECK(cpu_number_) << ": Invalid cpu number " << hostname_ |
| 67 | << ", failed to parse cpu number"; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 68 | std::regex re{"^[0-9][0-9]-[0-9][0-9]"}; |
| 69 | CHECK(std::regex_match(camera_id_, re)) |
| 70 | << ": Invalid camera_id '" << camera_id_ << "', should be of form YY-NN"; |
| 71 | } |
| 72 | |
| 73 | void IntrinsicsCalibration::HandleCharuco( |
| 74 | cv::Mat rgb_image, const aos::monotonic_clock::time_point /*eof*/, |
| 75 | std::vector<cv::Vec4i> charuco_ids, |
| 76 | std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid, |
| 77 | std::vector<Eigen::Vector3d> rvecs_eigen, |
| 78 | std::vector<Eigen::Vector3d> tvecs_eigen) { |
Austin Schuh | 99f7c6a | 2024-06-25 22:07:44 -0700 | [diff] [blame] | 79 | if (absl::GetFlag(FLAGS_visualize)) { |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 80 | // Reduce resolution displayed on remote viewer to prevent lag |
| 81 | cv::resize(rgb_image, rgb_image, |
| 82 | cv::Size(rgb_image.cols / 2, rgb_image.rows / 2)); |
| 83 | cv::imshow("Display", rgb_image); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 84 | |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 85 | if (display_undistorted_) { |
| 86 | const cv::Size image_size(rgb_image.cols, rgb_image.rows); |
| 87 | cv::Mat undistorted_rgb_image(image_size, CV_8UC3); |
| 88 | cv::undistort(rgb_image, undistorted_rgb_image, |
| 89 | charuco_extractor_.camera_matrix(), |
| 90 | charuco_extractor_.dist_coeffs()); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 91 | |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 92 | cv::imshow("Display undist", undistorted_rgb_image); |
| 93 | } |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 94 | } |
| 95 | |
| 96 | int keystroke = cv::waitKey(1); |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 97 | if ((keystroke & 0xFF) == static_cast<int>('q')) { |
| 98 | LOG(INFO) << "Going to exit"; |
| 99 | exit_collection_ = true; |
| 100 | exit_handle_->Exit(); |
| 101 | } |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 102 | // If we haven't got a valid pose estimate, don't use these points |
| 103 | if (!valid) { |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 104 | LOG(INFO) << "Skipping because pose is not valid"; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 105 | return; |
| 106 | } |
| 107 | CHECK(tvecs_eigen.size() == 1) |
| 108 | << "Charuco board should only return one translational pose"; |
| 109 | CHECK(rvecs_eigen.size() == 1) |
| 110 | << "Charuco board should only return one rotational pose"; |
| 111 | // Calibration calculates rotation and translation delta from last image |
| 112 | // stored to automatically capture next image |
| 113 | |
| 114 | Eigen::Affine3d H_board_camera = |
| 115 | Eigen::Translation3d(tvecs_eigen[0]) * |
| 116 | Eigen::AngleAxisd(rvecs_eigen[0].norm(), |
| 117 | rvecs_eigen[0] / rvecs_eigen[0].norm()); |
| 118 | Eigen::Affine3d H_camera_board_ = H_board_camera.inverse(); |
| 119 | Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_; |
| 120 | |
| 121 | Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation()); |
| 122 | |
| 123 | Eigen::Vector3d delta_t = H_delta.translation(); |
| 124 | |
| 125 | double r_norm = std::abs(delta_r.angle()); |
| 126 | double t_norm = delta_t.norm(); |
| 127 | |
| 128 | bool store_image = false; |
| 129 | double percent_motion = |
| 130 | std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold); |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 131 | LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; \nMoved " |
| 132 | << static_cast<int>(percent_motion * 100) << "% of what's needed"; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 133 | // Verify that camera has moved enough from last stored image |
| 134 | if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) { |
| 135 | // frame_ refers to deltas between current and last captured image |
| 136 | Eigen::Affine3d frame_H_delta = H_board_camera * prev_image_H_camera_board_; |
| 137 | |
| 138 | Eigen::AngleAxisd frame_delta_r = |
| 139 | Eigen::AngleAxisd(frame_H_delta.rotation()); |
| 140 | |
| 141 | Eigen::Vector3d frame_delta_t = frame_H_delta.translation(); |
| 142 | |
| 143 | double frame_r_norm = std::abs(frame_delta_r.angle()); |
| 144 | double frame_t_norm = frame_delta_t.norm(); |
| 145 | |
| 146 | // Make sure camera has stopped moving before storing image |
| 147 | store_image = |
| 148 | frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit; |
| 149 | double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit, |
| 150 | frame_t_norm / kFrameDeltaTLimit); |
| 151 | LOG(INFO) << "Captured: " << all_charuco_ids_.size() |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 152 | << "points; \nMoved enough (" |
| 153 | << static_cast<int>(percent_motion * 100) |
| 154 | << "%); Need to stop (last motion was " |
| 155 | << static_cast<int>(percent_stop * 100) |
| 156 | << "% of limit; needs to be < 1% to capture)"; |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 157 | } |
| 158 | prev_image_H_camera_board_ = H_camera_board_; |
| 159 | |
| 160 | if (store_image) { |
| 161 | if (valid) { |
| 162 | prev_H_camera_board_ = H_camera_board_; |
| 163 | |
| 164 | // Unpack the Charuco ids from Vec4i |
| 165 | std::vector<int> charuco_ids_int; |
| 166 | for (cv::Vec4i charuco_id : charuco_ids) { |
| 167 | charuco_ids_int.emplace_back(charuco_id[0]); |
| 168 | } |
| 169 | all_charuco_ids_.emplace_back(std::move(charuco_ids_int)); |
| 170 | all_charuco_corners_.emplace_back(std::move(charuco_corners[0])); |
| 171 | |
| 172 | if (r_norm > kDeltaRThreshold) { |
| 173 | LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > " |
| 174 | << kDeltaRThreshold; |
| 175 | } |
| 176 | if (t_norm > kDeltaTThreshold) { |
| 177 | LOG(INFO) << "Triggered by translation delta = " << t_norm << " > " |
| 178 | << kDeltaTThreshold; |
| 179 | } |
| 180 | } |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 181 | } |
| 182 | } |
| 183 | |
| 184 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 185 | IntrinsicsCalibration::BuildCalibration( |
| 186 | cv::Mat camera_matrix, cv::Mat dist_coeffs, |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 187 | aos::realtime_clock::time_point realtime_now, std::string_view cpu_type, |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 188 | uint16_t cpu_number, std::string_view camera_channel, |
Jim Ostrowski | fa71786 | 2024-02-11 21:16:02 -0800 | [diff] [blame] | 189 | std::string_view camera_id, uint16_t team_number, |
| 190 | double reprojection_error) { |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 191 | flatbuffers::FlatBufferBuilder fbb; |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 192 | // THIS IS A HACK FOR 2024, since we call Orin2 "Imu" |
| 193 | std::string cpu_name = absl::StrFormat("%s%d", cpu_type, cpu_number); |
| 194 | if (cpu_type == "orin" && cpu_number == 2) { |
| 195 | LOG(INFO) << "Renaming orin2 to imu"; |
| 196 | cpu_name = "imu"; |
| 197 | } |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 198 | flatbuffers::Offset<flatbuffers::String> name_offset = |
Jim Ostrowski | 144ab39 | 2024-03-17 18:41:49 -0700 | [diff] [blame] | 199 | fbb.CreateString(cpu_name.c_str()); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 200 | flatbuffers::Offset<flatbuffers::String> camera_id_offset = |
| 201 | fbb.CreateString(camera_id); |
| 202 | flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset = |
| 203 | fbb.CreateVector<float>(9u, [&camera_matrix](size_t i) { |
| 204 | return static_cast<float>( |
| 205 | reinterpret_cast<double *>(camera_matrix.data)[i]); |
| 206 | }); |
| 207 | |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 208 | std::optional<uint16_t> camera_number = |
| 209 | frc971::vision::CameraNumberFromChannel(std::string(camera_channel)); |
| 210 | |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 211 | flatbuffers::Offset<flatbuffers::Vector<float>> |
| 212 | distortion_coefficients_offset = |
| 213 | fbb.CreateVector<float>(5u, [&dist_coeffs](size_t i) { |
| 214 | return static_cast<float>( |
| 215 | reinterpret_cast<double *>(dist_coeffs.data)[i]); |
| 216 | }); |
| 217 | |
| 218 | calibration::CameraCalibration::Builder camera_calibration_builder(fbb); |
| 219 | |
| 220 | camera_calibration_builder.add_node_name(name_offset); |
| 221 | camera_calibration_builder.add_team_number(team_number); |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 222 | camera_calibration_builder.add_camera_number(camera_number.value()); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 223 | camera_calibration_builder.add_camera_id(camera_id_offset); |
Jim Ostrowski | fa71786 | 2024-02-11 21:16:02 -0800 | [diff] [blame] | 224 | camera_calibration_builder.add_reprojection_error( |
| 225 | static_cast<float>(reprojection_error)); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 226 | camera_calibration_builder.add_calibration_timestamp( |
| 227 | realtime_now.time_since_epoch().count()); |
| 228 | camera_calibration_builder.add_intrinsics(intrinsics_offset); |
| 229 | camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset); |
| 230 | fbb.Finish(camera_calibration_builder.Finish()); |
| 231 | |
| 232 | return fbb.Release(); |
| 233 | } |
| 234 | |
| 235 | void IntrinsicsCalibration::MaybeCalibrate() { |
| 236 | // TODO: This number should depend on coarse vs. fine pattern |
| 237 | // Maybe just on total # of ids found, not just images |
| 238 | if (all_charuco_ids_.size() >= 50) { |
| 239 | LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size() |
| 240 | << " images"; |
| 241 | cv::Mat camera_matrix, dist_coeffs; |
| 242 | std::vector<cv::Mat> rvecs, tvecs; |
| 243 | cv::Mat std_deviations_intrinsics, std_deviations_extrinsics, |
| 244 | per_view_errors; |
| 245 | |
| 246 | // Set calibration flags (same as in calibrateCamera() function) |
| 247 | int calibration_flags = 0; |
| 248 | cv::Size img_size(640, 480); |
| 249 | const double reprojection_error = cv::aruco::calibrateCameraCharuco( |
| 250 | all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(), |
| 251 | img_size, camera_matrix, dist_coeffs, rvecs, tvecs, |
| 252 | std_deviations_intrinsics, std_deviations_extrinsics, per_view_errors, |
| 253 | calibration_flags); |
Jim Ostrowski | fa71786 | 2024-02-11 21:16:02 -0800 | [diff] [blame] | 254 | CHECK_LE(reprojection_error, 2.0) |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 255 | << ": Reproduction error is bad-- greater than 1 pixel."; |
| 256 | LOG(INFO) << "Reprojection Error is " << reprojection_error; |
| 257 | |
| 258 | const aos::realtime_clock::time_point realtime_now = |
| 259 | aos::realtime_clock::now(); |
| 260 | std::optional<uint16_t> team_number = |
Jim Ostrowski | 3dc2164 | 2024-01-22 16:08:40 -0800 | [diff] [blame] | 261 | aos::network::team_number_internal::ParsePiOrOrinTeamNumber(hostname_); |
| 262 | CHECK(team_number) << ": Invalid hostname " << hostname_ |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 263 | << ", failed to parse team number"; |
| 264 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
Jim Ostrowski | fa71786 | 2024-02-11 21:16:02 -0800 | [diff] [blame] | 265 | camera_calibration = BuildCalibration( |
| 266 | camera_matrix, dist_coeffs, realtime_now, cpu_type_.value(), |
| 267 | cpu_number_.value(), camera_channel_, camera_id_, |
| 268 | team_number.value(), reprojection_error); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 269 | std::stringstream time_ss; |
| 270 | time_ss << realtime_now; |
| 271 | |
Jim Ostrowski | b974cca | 2024-01-28 15:07:50 -0800 | [diff] [blame] | 272 | std::optional<uint16_t> camera_number = |
| 273 | frc971::vision::CameraNumberFromChannel(camera_channel_); |
Jim Ostrowski | 3320898 | 2024-03-02 15:01:45 -0800 | [diff] [blame] | 274 | CHECK(camera_number.has_value()); |
| 275 | std::string calibration_filename = |
| 276 | CalibrationFilename(calibration_folder_, hostname_, team_number.value(), |
| 277 | camera_number.value(), camera_id_, time_ss.str()); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 278 | |
| 279 | LOG(INFO) << calibration_filename << " -> " |
| 280 | << aos::FlatbufferToJson(camera_calibration, |
| 281 | {.multi_line = true}); |
| 282 | |
| 283 | aos::util::WriteStringToFileOrDie( |
| 284 | calibration_filename, |
| 285 | aos::FlatbufferToJson(camera_calibration, {.multi_line = true})); |
| 286 | } else { |
| 287 | LOG(INFO) << "Skipping calibration due to not enough images."; |
| 288 | } |
| 289 | } |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 290 | } // namespace frc971::vision |