Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 1 | #include <cmath> |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 2 | #include <opencv2/calib3d.hpp> |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 3 | #include <opencv2/highgui/highgui.hpp> |
| 4 | #include <opencv2/imgproc.hpp> |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 5 | #include <regex> |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 6 | |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 7 | #include "Eigen/Dense" |
| 8 | #include "Eigen/Geometry" |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 9 | #include "absl/strings/str_format.h" |
| 10 | #include "aos/events/shm_event_loop.h" |
| 11 | #include "aos/init.h" |
| 12 | #include "aos/network/team_number.h" |
| 13 | #include "aos/time/time.h" |
| 14 | #include "aos/util/file.h" |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 15 | #include "y2020/vision/charuco_lib.h" |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 16 | |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 17 | DEFINE_string(calibration_folder, ".", "Folder to place calibration files."); |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 18 | DEFINE_string(camera_id, "", "Camera ID in format YY-NN-- year and number."); |
| 19 | DEFINE_string(config, "config.json", "Path to the config file to use."); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 20 | DEFINE_bool(display_undistorted, false, |
| 21 | "If true, display the undistorted image."); |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 22 | DEFINE_string(pi, "", "Pi name to calibrate."); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 23 | |
| 24 | namespace frc971 { |
| 25 | namespace vision { |
| 26 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 27 | class Calibration { |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 28 | public: |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 29 | Calibration(aos::ShmEventLoop *event_loop, std::string_view pi, |
| 30 | std::string_view camera_id) |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 31 | : event_loop_(event_loop), |
| 32 | pi_(pi), |
| 33 | pi_number_(aos::network::ParsePiNumber(pi)), |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 34 | camera_id_(camera_id), |
Yash Chainani | 460c9fb | 2022-02-12 18:14:50 -0800 | [diff] [blame] | 35 | H_camera_board_(Eigen::Affine3d()), |
| 36 | prev_H_camera_board_(Eigen::Affine3d()), |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 37 | charuco_extractor_( |
| 38 | event_loop, pi, |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 39 | [this](cv::Mat rgb_image, |
| 40 | const aos::monotonic_clock::time_point eof, |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 41 | std::vector<int> charuco_ids, |
| 42 | std::vector<cv::Point2f> charuco_corners, bool valid, |
| 43 | Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) { |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 44 | HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid, |
| 45 | rvec_eigen, tvec_eigen); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 46 | }) { |
| 47 | CHECK(pi_number_) << ": Invalid pi number " << pi |
| 48 | << ", failed to parse pi number"; |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 49 | std::regex re{"^[0-9][0-9]-[0-9][0-9]"}; |
| 50 | CHECK(std::regex_match(camera_id_, re)) |
| 51 | << ": Invalid camera_id '" << camera_id_ |
| 52 | << "', should be of form YY-NN"; |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 53 | } |
| 54 | |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 55 | void HandleCharuco(cv::Mat rgb_image, |
| 56 | const aos::monotonic_clock::time_point /*eof*/, |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 57 | std::vector<int> charuco_ids, |
| 58 | std::vector<cv::Point2f> charuco_corners, bool valid, |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 59 | Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) { |
| 60 | // Reduce resolution displayed on remote viewer to prevent lag |
| 61 | cv::resize(rgb_image, rgb_image, |
| 62 | cv::Size(rgb_image.cols / 2, rgb_image.rows / 2)); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 63 | cv::imshow("Display", rgb_image); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 64 | |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 65 | if (FLAGS_display_undistorted) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 66 | const cv::Size image_size(rgb_image.cols, rgb_image.rows); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 67 | cv::Mat undistorted_rgb_image(image_size, CV_8UC3); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 68 | cv::undistort(rgb_image, undistorted_rgb_image, |
| 69 | charuco_extractor_.camera_matrix(), |
| 70 | charuco_extractor_.dist_coeffs()); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 71 | |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 72 | cv::imshow("Display undist", undistorted_rgb_image); |
| 73 | } |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 74 | |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 75 | // Calibration calculates rotation and translation delta from last image |
| 76 | // captured to automatically capture next image |
| 77 | |
Yash Chainani | 460c9fb | 2022-02-12 18:14:50 -0800 | [diff] [blame] | 78 | Eigen::Affine3d H_board_camera = |
| 79 | Eigen::Translation3d(tvec_eigen) * |
| 80 | Eigen::AngleAxisd(rvec_eigen.norm(), rvec_eigen / rvec_eigen.norm()); |
| 81 | H_camera_board_ = H_board_camera.inverse(); |
| 82 | Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_; |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 83 | |
Yash Chainani | 460c9fb | 2022-02-12 18:14:50 -0800 | [diff] [blame] | 84 | Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation()); |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 85 | |
Yash Chainani | 460c9fb | 2022-02-12 18:14:50 -0800 | [diff] [blame] | 86 | Eigen::Vector3d delta_t = H_delta.translation(); |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 87 | |
| 88 | double r_norm = std::abs(delta_r.angle()); |
| 89 | double t_norm = delta_t.norm(); |
| 90 | |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 91 | int keystroke = cv::waitKey(1); |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 92 | if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 93 | if (valid) { |
Yash Chainani | 460c9fb | 2022-02-12 18:14:50 -0800 | [diff] [blame] | 94 | prev_H_camera_board_ = H_camera_board_; |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 95 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 96 | all_charuco_ids_.emplace_back(std::move(charuco_ids)); |
| 97 | all_charuco_corners_.emplace_back(std::move(charuco_corners)); |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 98 | |
| 99 | if (r_norm > kDeltaRThreshold) { |
| 100 | LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > " |
| 101 | << kDeltaRThreshold; |
| 102 | } |
| 103 | if (t_norm > kDeltaTThreshold) { |
| 104 | LOG(INFO) << "Trigerred by translation delta = " << t_norm << " > " |
| 105 | << kDeltaTThreshold; |
| 106 | } |
| 107 | |
| 108 | LOG(INFO) << "Image count " << all_charuco_corners_.size(); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 109 | } |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 110 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 111 | if (all_charuco_ids_.size() >= 50) { |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 112 | LOG(INFO) << "Got enough images to calibrate"; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 113 | event_loop_->Exit(); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 114 | } |
| 115 | } else if ((keystroke & 0xFF) == static_cast<int>('q')) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 116 | event_loop_->Exit(); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 117 | } |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 118 | } |
| 119 | |
| 120 | void MaybeCalibrate() { |
| 121 | if (all_charuco_ids_.size() >= 50) { |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 122 | LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size() |
| 123 | << " images"; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 124 | cv::Mat cameraMatrix, distCoeffs; |
| 125 | std::vector<cv::Mat> rvecs, tvecs; |
| 126 | cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors; |
| 127 | |
| 128 | // Set calibration flags (same as in calibrateCamera() function) |
| 129 | int calibration_flags = 0; |
| 130 | cv::Size img_size(640, 480); |
| 131 | const double reprojection_error = cv::aruco::calibrateCameraCharuco( |
| 132 | all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(), |
| 133 | img_size, cameraMatrix, distCoeffs, rvecs, tvecs, |
| 134 | stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors, |
| 135 | calibration_flags); |
| 136 | CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad."; |
| 137 | LOG(INFO) << "Reprojection Error is " << reprojection_error; |
| 138 | |
| 139 | flatbuffers::FlatBufferBuilder fbb; |
| 140 | flatbuffers::Offset<flatbuffers::String> name_offset = |
| 141 | fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value())); |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 142 | flatbuffers::Offset<flatbuffers::String> camera_id_offset = |
| 143 | fbb.CreateString(camera_id_); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 144 | flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset = |
| 145 | fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) { |
| 146 | return static_cast<float>( |
| 147 | reinterpret_cast<double *>(cameraMatrix.data)[i]); |
| 148 | }); |
| 149 | |
| 150 | flatbuffers::Offset<flatbuffers::Vector<float>> |
| 151 | distortion_coefficients_offset = |
| 152 | fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) { |
| 153 | return static_cast<float>( |
| 154 | reinterpret_cast<double *>(distCoeffs.data)[i]); |
| 155 | }); |
| 156 | |
| 157 | sift::CameraCalibration::Builder camera_calibration_builder(fbb); |
| 158 | std::optional<uint16_t> team_number = |
| 159 | aos::network::team_number_internal::ParsePiTeamNumber(pi_); |
| 160 | CHECK(team_number) << ": Invalid pi hostname " << pi_ |
| 161 | << ", failed to parse team number"; |
| 162 | |
| 163 | const aos::realtime_clock::time_point realtime_now = |
| 164 | aos::realtime_clock::now(); |
| 165 | camera_calibration_builder.add_node_name(name_offset); |
| 166 | camera_calibration_builder.add_team_number(team_number.value()); |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 167 | camera_calibration_builder.add_camera_id(camera_id_offset); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 168 | camera_calibration_builder.add_calibration_timestamp( |
| 169 | realtime_now.time_since_epoch().count()); |
| 170 | camera_calibration_builder.add_intrinsics(intrinsics_offset); |
| 171 | camera_calibration_builder.add_dist_coeffs( |
| 172 | distortion_coefficients_offset); |
| 173 | fbb.Finish(camera_calibration_builder.Finish()); |
| 174 | |
| 175 | aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration( |
| 176 | fbb.Release()); |
| 177 | std::stringstream time_ss; |
| 178 | time_ss << realtime_now; |
| 179 | |
| 180 | const std::string calibration_filename = |
| 181 | FLAGS_calibration_folder + |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 182 | absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json", |
| 183 | team_number.value(), pi_number_.value(), camera_id_, |
| 184 | time_ss.str()); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 185 | |
| 186 | LOG(INFO) << calibration_filename << " -> " |
| 187 | << aos::FlatbufferToJson(camera_calibration, |
| 188 | {.multi_line = true}); |
| 189 | |
| 190 | aos::util::WriteStringToFileOrDie( |
| 191 | calibration_filename, |
| 192 | aos::FlatbufferToJson(camera_calibration, {.multi_line = true})); |
| 193 | } else { |
| 194 | LOG(INFO) << "Skipping calibration due to not enough images."; |
| 195 | } |
| 196 | } |
| 197 | |
| 198 | private: |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 199 | static constexpr double kDeltaRThreshold = M_PI / 6.0; |
| 200 | static constexpr double kDeltaTThreshold = 0.3; |
| 201 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 202 | aos::ShmEventLoop *event_loop_; |
| 203 | std::string pi_; |
| 204 | const std::optional<uint16_t> pi_number_; |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 205 | const std::string camera_id_; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 206 | |
| 207 | std::vector<std::vector<int>> all_charuco_ids_; |
| 208 | std::vector<std::vector<cv::Point2f>> all_charuco_corners_; |
| 209 | |
Yash Chainani | 460c9fb | 2022-02-12 18:14:50 -0800 | [diff] [blame] | 210 | Eigen::Affine3d H_camera_board_; |
| 211 | Eigen::Affine3d prev_H_camera_board_; |
Yash Chainani | 5c005da | 2022-01-22 16:51:11 -0800 | [diff] [blame] | 212 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 213 | CharucoExtractor charuco_extractor_; |
| 214 | }; |
| 215 | |
| 216 | namespace { |
| 217 | |
| 218 | void Main() { |
| 219 | aos::FlatbufferDetachedBuffer<aos::Configuration> config = |
| 220 | aos::configuration::ReadConfig(FLAGS_config); |
| 221 | |
| 222 | aos::ShmEventLoop event_loop(&config.message()); |
| 223 | |
Jim Ostrowski | fec0c33 | 2022-02-06 23:28:26 -0800 | [diff] [blame^] | 224 | std::string hostname = FLAGS_pi; |
| 225 | if (hostname == "") { |
| 226 | hostname = aos::network::GetHostname(); |
| 227 | LOG(INFO) << "Using pi name from hostname as " << hostname; |
| 228 | } |
| 229 | Calibration extractor(&event_loop, hostname, FLAGS_camera_id); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 230 | |
| 231 | event_loop.Run(); |
| 232 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 233 | extractor.MaybeCalibrate(); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 234 | } |
| 235 | |
| 236 | } // namespace |
| 237 | } // namespace vision |
| 238 | } // namespace frc971 |
| 239 | |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 240 | int main(int argc, char **argv) { |
| 241 | aos::InitGoogle(&argc, &argv); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 242 | frc971::vision::Main(); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 243 | } |