Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 1 | #include "Eigen/Dense" |
| 2 | #include "Eigen/Geometry" |
Brian Silverman | 36c7f34 | 2021-06-11 15:21:41 -0700 | [diff] [blame] | 3 | |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 4 | #include <opencv2/calib3d.hpp> |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 5 | #include <opencv2/highgui/highgui.hpp> |
| 6 | #include <opencv2/imgproc.hpp> |
| 7 | |
| 8 | #include "absl/strings/str_format.h" |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 9 | #include "y2020/vision/charuco_lib.h" |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 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" |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 15 | |
| 16 | DEFINE_string(config, "config.json", "Path to the config file to use."); |
| 17 | DEFINE_string(pi, "pi-7971-1", "Pi name to calibrate."); |
| 18 | DEFINE_string(calibration_folder, "y2020/vision/tools/python_code/calib_files", |
| 19 | "Folder to place calibration files."); |
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."); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 22 | |
| 23 | namespace frc971 { |
| 24 | namespace vision { |
| 25 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 26 | class Calibration { |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 27 | public: |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 28 | Calibration(aos::ShmEventLoop *event_loop, std::string_view pi) |
| 29 | : event_loop_(event_loop), |
| 30 | pi_(pi), |
| 31 | pi_number_(aos::network::ParsePiNumber(pi)), |
| 32 | charuco_extractor_( |
| 33 | event_loop, pi, |
| 34 | [this](cv::Mat rgb_image, const double age_double, |
| 35 | std::vector<int> charuco_ids, |
| 36 | std::vector<cv::Point2f> charuco_corners, bool valid, |
| 37 | Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) { |
| 38 | HandleCharuco(rgb_image, age_double, charuco_ids, charuco_corners, |
| 39 | valid, rvec_eigen, tvec_eigen); |
| 40 | }) { |
| 41 | CHECK(pi_number_) << ": Invalid pi number " << pi |
| 42 | << ", failed to parse pi number"; |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 43 | } |
| 44 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 45 | void HandleCharuco(cv::Mat rgb_image, const double /*age_double*/, |
| 46 | std::vector<int> charuco_ids, |
| 47 | std::vector<cv::Point2f> charuco_corners, bool valid, |
| 48 | Eigen::Vector3d /*rvec_eigen*/, |
| 49 | Eigen::Vector3d /*tvec_eigen*/) { |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 50 | cv::imshow("Display", rgb_image); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 51 | |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 52 | if (FLAGS_display_undistorted) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 53 | const cv::Size image_size(rgb_image.cols, rgb_image.rows); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 54 | cv::Mat undistorted_rgb_image(image_size, CV_8UC3); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 55 | cv::undistort(rgb_image, undistorted_rgb_image, |
| 56 | charuco_extractor_.camera_matrix(), |
| 57 | charuco_extractor_.dist_coeffs()); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 58 | |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 59 | cv::imshow("Display undist", undistorted_rgb_image); |
| 60 | } |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 61 | |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 62 | int keystroke = cv::waitKey(1); |
| 63 | if ((keystroke & 0xFF) == static_cast<int>('c')) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 64 | if (valid) { |
| 65 | all_charuco_ids_.emplace_back(std::move(charuco_ids)); |
| 66 | all_charuco_corners_.emplace_back(std::move(charuco_corners)); |
| 67 | LOG(INFO) << "Image " << all_charuco_corners_.size(); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 68 | } |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 69 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 70 | if (all_charuco_ids_.size() >= 50) { |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 71 | LOG(INFO) << "Got enough images to calibrate"; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 72 | event_loop_->Exit(); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 73 | } |
| 74 | } else if ((keystroke & 0xFF) == static_cast<int>('q')) { |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 75 | event_loop_->Exit(); |
Ravago Jones | cf453ab | 2020-05-06 21:14:53 -0700 | [diff] [blame] | 76 | } |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 77 | } |
| 78 | |
| 79 | void MaybeCalibrate() { |
| 80 | if (all_charuco_ids_.size() >= 50) { |
| 81 | cv::Mat cameraMatrix, distCoeffs; |
| 82 | std::vector<cv::Mat> rvecs, tvecs; |
| 83 | cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors; |
| 84 | |
| 85 | // Set calibration flags (same as in calibrateCamera() function) |
| 86 | int calibration_flags = 0; |
| 87 | cv::Size img_size(640, 480); |
| 88 | const double reprojection_error = cv::aruco::calibrateCameraCharuco( |
| 89 | all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(), |
| 90 | img_size, cameraMatrix, distCoeffs, rvecs, tvecs, |
| 91 | stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors, |
| 92 | calibration_flags); |
| 93 | CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad."; |
| 94 | LOG(INFO) << "Reprojection Error is " << reprojection_error; |
| 95 | |
| 96 | flatbuffers::FlatBufferBuilder fbb; |
| 97 | flatbuffers::Offset<flatbuffers::String> name_offset = |
| 98 | fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value())); |
| 99 | flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset = |
| 100 | fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) { |
| 101 | return static_cast<float>( |
| 102 | reinterpret_cast<double *>(cameraMatrix.data)[i]); |
| 103 | }); |
| 104 | |
| 105 | flatbuffers::Offset<flatbuffers::Vector<float>> |
| 106 | distortion_coefficients_offset = |
| 107 | fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) { |
| 108 | return static_cast<float>( |
| 109 | reinterpret_cast<double *>(distCoeffs.data)[i]); |
| 110 | }); |
| 111 | |
| 112 | sift::CameraCalibration::Builder camera_calibration_builder(fbb); |
| 113 | std::optional<uint16_t> team_number = |
| 114 | aos::network::team_number_internal::ParsePiTeamNumber(pi_); |
| 115 | CHECK(team_number) << ": Invalid pi hostname " << pi_ |
| 116 | << ", failed to parse team number"; |
| 117 | |
| 118 | const aos::realtime_clock::time_point realtime_now = |
| 119 | aos::realtime_clock::now(); |
| 120 | camera_calibration_builder.add_node_name(name_offset); |
| 121 | camera_calibration_builder.add_team_number(team_number.value()); |
| 122 | camera_calibration_builder.add_calibration_timestamp( |
| 123 | realtime_now.time_since_epoch().count()); |
| 124 | camera_calibration_builder.add_intrinsics(intrinsics_offset); |
| 125 | camera_calibration_builder.add_dist_coeffs( |
| 126 | distortion_coefficients_offset); |
| 127 | fbb.Finish(camera_calibration_builder.Finish()); |
| 128 | |
| 129 | aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration( |
| 130 | fbb.Release()); |
| 131 | std::stringstream time_ss; |
| 132 | time_ss << realtime_now; |
| 133 | |
| 134 | const std::string calibration_filename = |
| 135 | FLAGS_calibration_folder + |
| 136 | absl::StrFormat("/calibration_pi-%d-%d_%s.json", team_number.value(), |
| 137 | pi_number_.value(), time_ss.str()); |
| 138 | |
| 139 | LOG(INFO) << calibration_filename << " -> " |
| 140 | << aos::FlatbufferToJson(camera_calibration, |
| 141 | {.multi_line = true}); |
| 142 | |
| 143 | aos::util::WriteStringToFileOrDie( |
| 144 | calibration_filename, |
| 145 | aos::FlatbufferToJson(camera_calibration, {.multi_line = true})); |
| 146 | } else { |
| 147 | LOG(INFO) << "Skipping calibration due to not enough images."; |
| 148 | } |
| 149 | } |
| 150 | |
| 151 | private: |
| 152 | aos::ShmEventLoop *event_loop_; |
| 153 | std::string pi_; |
| 154 | const std::optional<uint16_t> pi_number_; |
| 155 | |
| 156 | std::vector<std::vector<int>> all_charuco_ids_; |
| 157 | std::vector<std::vector<cv::Point2f>> all_charuco_corners_; |
| 158 | |
| 159 | CharucoExtractor charuco_extractor_; |
| 160 | }; |
| 161 | |
| 162 | namespace { |
| 163 | |
| 164 | void Main() { |
| 165 | aos::FlatbufferDetachedBuffer<aos::Configuration> config = |
| 166 | aos::configuration::ReadConfig(FLAGS_config); |
| 167 | |
| 168 | aos::ShmEventLoop event_loop(&config.message()); |
| 169 | |
| 170 | Calibration extractor(&event_loop, FLAGS_pi); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 171 | |
| 172 | event_loop.Run(); |
| 173 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 174 | extractor.MaybeCalibrate(); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 175 | } |
| 176 | |
| 177 | } // namespace |
| 178 | } // namespace vision |
| 179 | } // namespace frc971 |
| 180 | |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 181 | int main(int argc, char **argv) { |
| 182 | aos::InitGoogle(&argc, &argv); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame^] | 183 | frc971::vision::Main(); |
Austin Schuh | c1f118e | 2020-04-11 15:50:08 -0700 | [diff] [blame] | 184 | } |