blob: b5d1b32524af5510125c125b739c3b2ce0ffd817 [file] [log] [blame]
Yash Chainani5c005da2022-01-22 16:51:11 -08001#include <cmath>
Austin Schuhc1f118e2020-04-11 15:50:08 -07002#include <opencv2/calib3d.hpp>
Austin Schuhc1f118e2020-04-11 15:50:08 -07003#include <opencv2/highgui/highgui.hpp>
4#include <opencv2/imgproc.hpp>
Jim Ostrowskifec0c332022-02-06 23:28:26 -08005#include <regex>
Austin Schuhc1f118e2020-04-11 15:50:08 -07006
Yash Chainani5c005da2022-01-22 16:51:11 -08007#include "Eigen/Dense"
8#include "Eigen/Geometry"
Austin Schuhc1f118e2020-04-11 15:50:08 -07009#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"
Austin Schuhdcb6b362022-02-25 18:06:21 -080015#include "frc971/vision/charuco_lib.h"
Austin Schuhc1f118e2020-04-11 15:50:08 -070016
Yash Chainani5c005da2022-01-22 16:51:11 -080017DEFINE_string(calibration_folder, ".", "Folder to place calibration files.");
Jim Ostrowskifec0c332022-02-06 23:28:26 -080018DEFINE_string(camera_id, "", "Camera ID in format YY-NN-- year and number.");
Austin Schuhc5fa6d92022-02-25 14:36:28 -080019DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
Austin Schuhc1f118e2020-04-11 15:50:08 -070020DEFINE_bool(display_undistorted, false,
21 "If true, display the undistorted image.");
Jim Ostrowskifec0c332022-02-06 23:28:26 -080022DEFINE_string(pi, "", "Pi name to calibrate.");
Austin Schuhc1f118e2020-04-11 15:50:08 -070023
24namespace frc971 {
25namespace vision {
26
Austin Schuh25837f22021-06-27 15:49:14 -070027class Calibration {
Austin Schuhc1f118e2020-04-11 15:50:08 -070028 public:
Jim Ostrowskifec0c332022-02-06 23:28:26 -080029 Calibration(aos::ShmEventLoop *event_loop, std::string_view pi,
30 std::string_view camera_id)
Austin Schuh25837f22021-06-27 15:49:14 -070031 : event_loop_(event_loop),
32 pi_(pi),
33 pi_number_(aos::network::ParsePiNumber(pi)),
Jim Ostrowskifec0c332022-02-06 23:28:26 -080034 camera_id_(camera_id),
Yash Chainani460c9fb2022-02-12 18:14:50 -080035 prev_H_camera_board_(Eigen::Affine3d()),
Yash Chainani24fc2bd2022-02-14 12:43:29 -080036 prev_image_H_camera_board_(Eigen::Affine3d()),
Austin Schuh25837f22021-06-27 15:49:14 -070037 charuco_extractor_(
38 event_loop, pi,
Yash Chainani5c005da2022-01-22 16:51:11 -080039 [this](cv::Mat rgb_image,
40 const aos::monotonic_clock::time_point eof,
Austin Schuh25837f22021-06-27 15:49:14 -070041 std::vector<int> charuco_ids,
42 std::vector<cv::Point2f> charuco_corners, bool valid,
43 Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -080044 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
45 rvec_eigen, tvec_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -070046 }) {
47 CHECK(pi_number_) << ": Invalid pi number " << pi
48 << ", failed to parse pi number";
Jim Ostrowskifec0c332022-02-06 23:28:26 -080049 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 Schuhc1f118e2020-04-11 15:50:08 -070053 }
54
Austin Schuhea7b0142021-10-08 22:04:53 -070055 void HandleCharuco(cv::Mat rgb_image,
56 const aos::monotonic_clock::time_point /*eof*/,
Austin Schuh25837f22021-06-27 15:49:14 -070057 std::vector<int> charuco_ids,
58 std::vector<cv::Point2f> charuco_corners, bool valid,
Yash Chainani5c005da2022-01-22 16:51:11 -080059 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 Jonescf453ab2020-05-06 21:14:53 -070063 cv::imshow("Display", rgb_image);
Austin Schuhc1f118e2020-04-11 15:50:08 -070064
Ravago Jonescf453ab2020-05-06 21:14:53 -070065 if (FLAGS_display_undistorted) {
Austin Schuh25837f22021-06-27 15:49:14 -070066 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
Ravago Jonescf453ab2020-05-06 21:14:53 -070067 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
Austin Schuh25837f22021-06-27 15:49:14 -070068 cv::undistort(rgb_image, undistorted_rgb_image,
69 charuco_extractor_.camera_matrix(),
70 charuco_extractor_.dist_coeffs());
Austin Schuhc1f118e2020-04-11 15:50:08 -070071
Ravago Jonescf453ab2020-05-06 21:14:53 -070072 cv::imshow("Display undist", undistorted_rgb_image);
73 }
Austin Schuhc1f118e2020-04-11 15:50:08 -070074
Jim Ostrowski634b2652022-03-04 02:10:53 -080075 int keystroke = cv::waitKey(1);
76
77 // If we haven't got a valid pose estimate, don't use these points
78 if (!valid) {
79 return;
80 }
Yash Chainani5c005da2022-01-22 16:51:11 -080081 // Calibration calculates rotation and translation delta from last image
Yash Chainani24fc2bd2022-02-14 12:43:29 -080082 // stored to automatically capture next image
Yash Chainani5c005da2022-01-22 16:51:11 -080083
Yash Chainani460c9fb2022-02-12 18:14:50 -080084 Eigen::Affine3d H_board_camera =
85 Eigen::Translation3d(tvec_eigen) *
86 Eigen::AngleAxisd(rvec_eigen.norm(), rvec_eigen / rvec_eigen.norm());
Yash Chainani24fc2bd2022-02-14 12:43:29 -080087 Eigen::Affine3d H_camera_board_ = H_board_camera.inverse();
Yash Chainani460c9fb2022-02-12 18:14:50 -080088 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -080089
Yash Chainani460c9fb2022-02-12 18:14:50 -080090 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
Yash Chainani5c005da2022-01-22 16:51:11 -080091
Yash Chainani460c9fb2022-02-12 18:14:50 -080092 Eigen::Vector3d delta_t = H_delta.translation();
Yash Chainani5c005da2022-01-22 16:51:11 -080093
94 double r_norm = std::abs(delta_r.angle());
95 double t_norm = delta_t.norm();
96
Yash Chainani24fc2bd2022-02-14 12:43:29 -080097 bool store_image = false;
Jim Ostrowski634b2652022-03-04 02:10:53 -080098 double percent_motion =
99 std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold);
100 LOG(INFO) << all_charuco_ids_.size() << ": Moved " << percent_motion
101 << "% of what's needed";
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800102 // Verify that camera has moved enough from last stored image
Yash Chainani5c005da2022-01-22 16:51:11 -0800103 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800104 // frame_ refers to deltas between current and last captured image
105 Eigen::Affine3d frame_H_delta =
106 H_board_camera * prev_image_H_camera_board_;
107
108 Eigen::AngleAxisd frame_delta_r =
109 Eigen::AngleAxisd(frame_H_delta.rotation());
110
111 Eigen::Vector3d frame_delta_t = frame_H_delta.translation();
112
113 double frame_r_norm = std::abs(frame_delta_r.angle());
114 double frame_t_norm = frame_delta_t.norm();
115
116 // Make sure camera has stopped moving before storing image
117 store_image =
118 frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800119 double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit,
120 frame_t_norm / kFrameDeltaTLimit);
121 LOG(INFO) << all_charuco_ids_.size() << ": Moved enough ("
122 << percent_motion << "%); Need to stop (last motion was "
123 << percent_stop << "%";
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800124 }
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800125 prev_image_H_camera_board_ = H_camera_board_;
126
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800127 if (store_image) {
Austin Schuh25837f22021-06-27 15:49:14 -0700128 if (valid) {
Yash Chainani460c9fb2022-02-12 18:14:50 -0800129 prev_H_camera_board_ = H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800130
Austin Schuh25837f22021-06-27 15:49:14 -0700131 all_charuco_ids_.emplace_back(std::move(charuco_ids));
132 all_charuco_corners_.emplace_back(std::move(charuco_corners));
Yash Chainani5c005da2022-01-22 16:51:11 -0800133
134 if (r_norm > kDeltaRThreshold) {
135 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
136 << kDeltaRThreshold;
137 }
138 if (t_norm > kDeltaTThreshold) {
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800139 LOG(INFO) << "Triggered by translation delta = " << t_norm << " > "
Yash Chainani5c005da2022-01-22 16:51:11 -0800140 << kDeltaTThreshold;
141 }
Ravago Jonescf453ab2020-05-06 21:14:53 -0700142 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700143
Ravago Jonescf453ab2020-05-06 21:14:53 -0700144 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
Austin Schuh25837f22021-06-27 15:49:14 -0700145 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700146 }
Austin Schuh25837f22021-06-27 15:49:14 -0700147 }
148
149 void MaybeCalibrate() {
Jim Ostrowski634b2652022-03-04 02:10:53 -0800150 // TODO: This number should depend on coarse vs. fine pattern
151 // Maybe just on total # of ids found, not just images
Austin Schuh25837f22021-06-27 15:49:14 -0700152 if (all_charuco_ids_.size() >= 50) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800153 LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
154 << " images";
Austin Schuh25837f22021-06-27 15:49:14 -0700155 cv::Mat cameraMatrix, distCoeffs;
156 std::vector<cv::Mat> rvecs, tvecs;
157 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
158
159 // Set calibration flags (same as in calibrateCamera() function)
160 int calibration_flags = 0;
161 cv::Size img_size(640, 480);
162 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
163 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
164 img_size, cameraMatrix, distCoeffs, rvecs, tvecs,
165 stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors,
166 calibration_flags);
167 CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad.";
168 LOG(INFO) << "Reprojection Error is " << reprojection_error;
169
170 flatbuffers::FlatBufferBuilder fbb;
171 flatbuffers::Offset<flatbuffers::String> name_offset =
172 fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value()));
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800173 flatbuffers::Offset<flatbuffers::String> camera_id_offset =
174 fbb.CreateString(camera_id_);
Austin Schuh25837f22021-06-27 15:49:14 -0700175 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
176 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
177 return static_cast<float>(
178 reinterpret_cast<double *>(cameraMatrix.data)[i]);
179 });
180
181 flatbuffers::Offset<flatbuffers::Vector<float>>
182 distortion_coefficients_offset =
183 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
184 return static_cast<float>(
185 reinterpret_cast<double *>(distCoeffs.data)[i]);
186 });
187
188 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
189 std::optional<uint16_t> team_number =
190 aos::network::team_number_internal::ParsePiTeamNumber(pi_);
191 CHECK(team_number) << ": Invalid pi hostname " << pi_
192 << ", failed to parse team number";
193
194 const aos::realtime_clock::time_point realtime_now =
195 aos::realtime_clock::now();
196 camera_calibration_builder.add_node_name(name_offset);
197 camera_calibration_builder.add_team_number(team_number.value());
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800198 camera_calibration_builder.add_camera_id(camera_id_offset);
Austin Schuh25837f22021-06-27 15:49:14 -0700199 camera_calibration_builder.add_calibration_timestamp(
200 realtime_now.time_since_epoch().count());
201 camera_calibration_builder.add_intrinsics(intrinsics_offset);
202 camera_calibration_builder.add_dist_coeffs(
203 distortion_coefficients_offset);
204 fbb.Finish(camera_calibration_builder.Finish());
205
206 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
207 fbb.Release());
208 std::stringstream time_ss;
209 time_ss << realtime_now;
210
211 const std::string calibration_filename =
212 FLAGS_calibration_folder +
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800213 absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json",
214 team_number.value(), pi_number_.value(), camera_id_,
215 time_ss.str());
Austin Schuh25837f22021-06-27 15:49:14 -0700216
217 LOG(INFO) << calibration_filename << " -> "
218 << aos::FlatbufferToJson(camera_calibration,
219 {.multi_line = true});
220
221 aos::util::WriteStringToFileOrDie(
222 calibration_filename,
223 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
224 } else {
225 LOG(INFO) << "Skipping calibration due to not enough images.";
226 }
227 }
228
229 private:
Yash Chainani5c005da2022-01-22 16:51:11 -0800230 static constexpr double kDeltaRThreshold = M_PI / 6.0;
231 static constexpr double kDeltaTThreshold = 0.3;
232
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800233 static constexpr double kFrameDeltaRLimit = M_PI / 60;
234 static constexpr double kFrameDeltaTLimit = 0.01;
235
Austin Schuh25837f22021-06-27 15:49:14 -0700236 aos::ShmEventLoop *event_loop_;
237 std::string pi_;
238 const std::optional<uint16_t> pi_number_;
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800239 const std::string camera_id_;
Austin Schuh25837f22021-06-27 15:49:14 -0700240
241 std::vector<std::vector<int>> all_charuco_ids_;
242 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
243
Yash Chainani460c9fb2022-02-12 18:14:50 -0800244 Eigen::Affine3d H_camera_board_;
245 Eigen::Affine3d prev_H_camera_board_;
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800246 Eigen::Affine3d prev_image_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800247
Austin Schuh25837f22021-06-27 15:49:14 -0700248 CharucoExtractor charuco_extractor_;
249};
250
251namespace {
252
253void Main() {
254 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
255 aos::configuration::ReadConfig(FLAGS_config);
256
257 aos::ShmEventLoop event_loop(&config.message());
258
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800259 std::string hostname = FLAGS_pi;
260 if (hostname == "") {
261 hostname = aos::network::GetHostname();
262 LOG(INFO) << "Using pi name from hostname as " << hostname;
263 }
264 Calibration extractor(&event_loop, hostname, FLAGS_camera_id);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700265
266 event_loop.Run();
267
Austin Schuh25837f22021-06-27 15:49:14 -0700268 extractor.MaybeCalibrate();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700269}
270
271} // namespace
272} // namespace vision
273} // namespace frc971
274
Austin Schuhc1f118e2020-04-11 15:50:08 -0700275int main(int argc, char **argv) {
276 aos::InitGoogle(&argc, &argv);
Austin Schuh25837f22021-06-27 15:49:14 -0700277 frc971::vision::Main();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700278}