blob: 6145452dec8ca247983edbb99cc3e7a5a9dd0b03 [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_(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080038 event_loop, pi, TargetType::kCharuco, "/camera",
Yash Chainani5c005da2022-01-22 16:51:11 -080039 [this](cv::Mat rgb_image,
40 const aos::monotonic_clock::time_point eof,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080041 std::vector<cv::Vec4i> charuco_ids,
42 std::vector<std::vector<cv::Point2f>> charuco_corners,
43 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
44 std::vector<Eigen::Vector3d> tvecs_eigen) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -080045 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080046 rvecs_eigen, tvecs_eigen);
47 }),
48 image_callback_(
49 event_loop,
50 absl::StrCat(
51 "/pi", std::to_string(aos::network::ParsePiNumber(pi).value()),
52 "/camera"),
53 [this](cv::Mat rgb_image,
54 const aos::monotonic_clock::time_point eof) {
55 charuco_extractor_.HandleImage(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -070056 }) {
57 CHECK(pi_number_) << ": Invalid pi number " << pi
58 << ", failed to parse pi number";
Jim Ostrowskifec0c332022-02-06 23:28:26 -080059 std::regex re{"^[0-9][0-9]-[0-9][0-9]"};
60 CHECK(std::regex_match(camera_id_, re))
61 << ": Invalid camera_id '" << camera_id_
62 << "', should be of form YY-NN";
Austin Schuhc1f118e2020-04-11 15:50:08 -070063 }
64
Austin Schuhea7b0142021-10-08 22:04:53 -070065 void HandleCharuco(cv::Mat rgb_image,
66 const aos::monotonic_clock::time_point /*eof*/,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080067 std::vector<cv::Vec4i> charuco_ids,
68 std::vector<std::vector<cv::Point2f>> charuco_corners,
69 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
70 std::vector<Eigen::Vector3d> tvecs_eigen) {
Yash Chainani5c005da2022-01-22 16:51:11 -080071 // Reduce resolution displayed on remote viewer to prevent lag
72 cv::resize(rgb_image, rgb_image,
73 cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
Ravago Jonescf453ab2020-05-06 21:14:53 -070074 cv::imshow("Display", rgb_image);
Austin Schuhc1f118e2020-04-11 15:50:08 -070075
Ravago Jonescf453ab2020-05-06 21:14:53 -070076 if (FLAGS_display_undistorted) {
Austin Schuh25837f22021-06-27 15:49:14 -070077 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
Ravago Jonescf453ab2020-05-06 21:14:53 -070078 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
Austin Schuh25837f22021-06-27 15:49:14 -070079 cv::undistort(rgb_image, undistorted_rgb_image,
80 charuco_extractor_.camera_matrix(),
81 charuco_extractor_.dist_coeffs());
Austin Schuhc1f118e2020-04-11 15:50:08 -070082
Ravago Jonescf453ab2020-05-06 21:14:53 -070083 cv::imshow("Display undist", undistorted_rgb_image);
84 }
Austin Schuhc1f118e2020-04-11 15:50:08 -070085
Jim Ostrowski634b2652022-03-04 02:10:53 -080086 int keystroke = cv::waitKey(1);
87
88 // If we haven't got a valid pose estimate, don't use these points
89 if (!valid) {
90 return;
91 }
Jim Ostrowskib3cab972022-12-03 15:47:00 -080092 CHECK(tvecs_eigen.size() == 1)
93 << "Charuco board should only return one translational pose";
94 CHECK(rvecs_eigen.size() == 1)
95 << "Charuco board should only return one rotational pose";
Yash Chainani5c005da2022-01-22 16:51:11 -080096 // Calibration calculates rotation and translation delta from last image
Yash Chainani24fc2bd2022-02-14 12:43:29 -080097 // stored to automatically capture next image
Yash Chainani5c005da2022-01-22 16:51:11 -080098
Yash Chainani460c9fb2022-02-12 18:14:50 -080099 Eigen::Affine3d H_board_camera =
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800100 Eigen::Translation3d(tvecs_eigen[0]) *
101 Eigen::AngleAxisd(rvecs_eigen[0].norm(),
102 rvecs_eigen[0] / rvecs_eigen[0].norm());
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800103 Eigen::Affine3d H_camera_board_ = H_board_camera.inverse();
Yash Chainani460c9fb2022-02-12 18:14:50 -0800104 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800105
Yash Chainani460c9fb2022-02-12 18:14:50 -0800106 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
Yash Chainani5c005da2022-01-22 16:51:11 -0800107
Yash Chainani460c9fb2022-02-12 18:14:50 -0800108 Eigen::Vector3d delta_t = H_delta.translation();
Yash Chainani5c005da2022-01-22 16:51:11 -0800109
110 double r_norm = std::abs(delta_r.angle());
111 double t_norm = delta_t.norm();
112
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800113 bool store_image = false;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800114 double percent_motion =
115 std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800116 LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; Moved "
117 << percent_motion << "% of what's needed";
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800118 // Verify that camera has moved enough from last stored image
Yash Chainani5c005da2022-01-22 16:51:11 -0800119 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800120 // frame_ refers to deltas between current and last captured image
121 Eigen::Affine3d frame_H_delta =
122 H_board_camera * prev_image_H_camera_board_;
123
124 Eigen::AngleAxisd frame_delta_r =
125 Eigen::AngleAxisd(frame_H_delta.rotation());
126
127 Eigen::Vector3d frame_delta_t = frame_H_delta.translation();
128
129 double frame_r_norm = std::abs(frame_delta_r.angle());
130 double frame_t_norm = frame_delta_t.norm();
131
132 // Make sure camera has stopped moving before storing image
133 store_image =
134 frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit;
Jim Ostrowski634b2652022-03-04 02:10:53 -0800135 double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit,
136 frame_t_norm / kFrameDeltaTLimit);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800137 LOG(INFO) << "Captured: " << all_charuco_ids_.size()
138 << "points; Moved enough (" << percent_motion
139 << "%); Need to stop (last motion was " << percent_stop
140 << "% of limit; needs to be < 1 to capture)";
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800141 }
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800142 prev_image_H_camera_board_ = H_camera_board_;
143
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800144 if (store_image) {
Austin Schuh25837f22021-06-27 15:49:14 -0700145 if (valid) {
Yash Chainani460c9fb2022-02-12 18:14:50 -0800146 prev_H_camera_board_ = H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800147
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800148 // Unpack the Charuco ids from Vec4i
149 std::vector<int> charuco_ids_int;
150 for (cv::Vec4i charuco_id : charuco_ids) {
151 charuco_ids_int.emplace_back(charuco_id[0]);
152 }
153 all_charuco_ids_.emplace_back(std::move(charuco_ids_int));
154 all_charuco_corners_.emplace_back(std::move(charuco_corners[0]));
Yash Chainani5c005da2022-01-22 16:51:11 -0800155
156 if (r_norm > kDeltaRThreshold) {
157 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
158 << kDeltaRThreshold;
159 }
160 if (t_norm > kDeltaTThreshold) {
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800161 LOG(INFO) << "Triggered by translation delta = " << t_norm << " > "
Yash Chainani5c005da2022-01-22 16:51:11 -0800162 << kDeltaTThreshold;
163 }
Ravago Jonescf453ab2020-05-06 21:14:53 -0700164 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700165
Ravago Jonescf453ab2020-05-06 21:14:53 -0700166 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
Austin Schuh25837f22021-06-27 15:49:14 -0700167 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700168 }
Austin Schuh25837f22021-06-27 15:49:14 -0700169 }
170
171 void MaybeCalibrate() {
Jim Ostrowski634b2652022-03-04 02:10:53 -0800172 // TODO: This number should depend on coarse vs. fine pattern
173 // Maybe just on total # of ids found, not just images
Austin Schuh25837f22021-06-27 15:49:14 -0700174 if (all_charuco_ids_.size() >= 50) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800175 LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
176 << " images";
Austin Schuh25837f22021-06-27 15:49:14 -0700177 cv::Mat cameraMatrix, distCoeffs;
178 std::vector<cv::Mat> rvecs, tvecs;
179 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
180
181 // Set calibration flags (same as in calibrateCamera() function)
182 int calibration_flags = 0;
183 cv::Size img_size(640, 480);
184 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
185 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
186 img_size, cameraMatrix, distCoeffs, rvecs, tvecs,
187 stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors,
188 calibration_flags);
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800189 CHECK_LE(reprojection_error, 1.0)
190 << ": Reproduction error is bad-- greater than 1 pixel.";
Austin Schuh25837f22021-06-27 15:49:14 -0700191 LOG(INFO) << "Reprojection Error is " << reprojection_error;
192
193 flatbuffers::FlatBufferBuilder fbb;
194 flatbuffers::Offset<flatbuffers::String> name_offset =
195 fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value()));
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800196 flatbuffers::Offset<flatbuffers::String> camera_id_offset =
197 fbb.CreateString(camera_id_);
Austin Schuh25837f22021-06-27 15:49:14 -0700198 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
199 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
200 return static_cast<float>(
201 reinterpret_cast<double *>(cameraMatrix.data)[i]);
202 });
203
204 flatbuffers::Offset<flatbuffers::Vector<float>>
205 distortion_coefficients_offset =
206 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
207 return static_cast<float>(
208 reinterpret_cast<double *>(distCoeffs.data)[i]);
209 });
210
211 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
212 std::optional<uint16_t> team_number =
213 aos::network::team_number_internal::ParsePiTeamNumber(pi_);
214 CHECK(team_number) << ": Invalid pi hostname " << pi_
215 << ", failed to parse team number";
216
217 const aos::realtime_clock::time_point realtime_now =
218 aos::realtime_clock::now();
219 camera_calibration_builder.add_node_name(name_offset);
220 camera_calibration_builder.add_team_number(team_number.value());
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800221 camera_calibration_builder.add_camera_id(camera_id_offset);
Austin Schuh25837f22021-06-27 15:49:14 -0700222 camera_calibration_builder.add_calibration_timestamp(
223 realtime_now.time_since_epoch().count());
224 camera_calibration_builder.add_intrinsics(intrinsics_offset);
225 camera_calibration_builder.add_dist_coeffs(
226 distortion_coefficients_offset);
227 fbb.Finish(camera_calibration_builder.Finish());
228
229 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
230 fbb.Release());
231 std::stringstream time_ss;
232 time_ss << realtime_now;
233
234 const std::string calibration_filename =
235 FLAGS_calibration_folder +
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800236 absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json",
237 team_number.value(), pi_number_.value(), camera_id_,
238 time_ss.str());
Austin Schuh25837f22021-06-27 15:49:14 -0700239
240 LOG(INFO) << calibration_filename << " -> "
241 << aos::FlatbufferToJson(camera_calibration,
242 {.multi_line = true});
243
244 aos::util::WriteStringToFileOrDie(
245 calibration_filename,
246 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
247 } else {
248 LOG(INFO) << "Skipping calibration due to not enough images.";
249 }
250 }
251
252 private:
Yash Chainani5c005da2022-01-22 16:51:11 -0800253 static constexpr double kDeltaRThreshold = M_PI / 6.0;
254 static constexpr double kDeltaTThreshold = 0.3;
255
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800256 static constexpr double kFrameDeltaRLimit = M_PI / 60;
257 static constexpr double kFrameDeltaTLimit = 0.01;
258
Austin Schuh25837f22021-06-27 15:49:14 -0700259 aos::ShmEventLoop *event_loop_;
260 std::string pi_;
261 const std::optional<uint16_t> pi_number_;
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800262 const std::string camera_id_;
Austin Schuh25837f22021-06-27 15:49:14 -0700263
264 std::vector<std::vector<int>> all_charuco_ids_;
265 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
266
Yash Chainani460c9fb2022-02-12 18:14:50 -0800267 Eigen::Affine3d H_camera_board_;
268 Eigen::Affine3d prev_H_camera_board_;
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800269 Eigen::Affine3d prev_image_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800270
Austin Schuh25837f22021-06-27 15:49:14 -0700271 CharucoExtractor charuco_extractor_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800272 ImageCallback image_callback_;
Austin Schuh25837f22021-06-27 15:49:14 -0700273};
274
275namespace {
276
277void Main() {
278 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
279 aos::configuration::ReadConfig(FLAGS_config);
280
281 aos::ShmEventLoop event_loop(&config.message());
282
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800283 std::string hostname = FLAGS_pi;
284 if (hostname == "") {
285 hostname = aos::network::GetHostname();
286 LOG(INFO) << "Using pi name from hostname as " << hostname;
287 }
288 Calibration extractor(&event_loop, hostname, FLAGS_camera_id);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700289
290 event_loop.Run();
291
Austin Schuh25837f22021-06-27 15:49:14 -0700292 extractor.MaybeCalibrate();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700293}
294
295} // namespace
296} // namespace vision
297} // namespace frc971
298
Austin Schuhc1f118e2020-04-11 15:50:08 -0700299int main(int argc, char **argv) {
300 aos::InitGoogle(&argc, &argv);
Austin Schuh25837f22021-06-27 15:49:14 -0700301 frc971::vision::Main();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700302}