blob: 0a541dee19810105cbe6ceec72c882990ec8d5e4 [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"
Yash Chainani5c005da2022-01-22 16:51:11 -080015#include "y2020/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.");
19DEFINE_string(config, "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
Yash Chainani5c005da2022-01-22 16:51:11 -080075 // Calibration calculates rotation and translation delta from last image
Yash Chainani24fc2bd2022-02-14 12:43:29 -080076 // stored to automatically capture next image
Yash Chainani5c005da2022-01-22 16:51:11 -080077
Yash Chainani460c9fb2022-02-12 18:14:50 -080078 Eigen::Affine3d H_board_camera =
79 Eigen::Translation3d(tvec_eigen) *
80 Eigen::AngleAxisd(rvec_eigen.norm(), rvec_eigen / rvec_eigen.norm());
Yash Chainani24fc2bd2022-02-14 12:43:29 -080081 Eigen::Affine3d H_camera_board_ = H_board_camera.inverse();
Yash Chainani460c9fb2022-02-12 18:14:50 -080082 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -080083
Yash Chainani460c9fb2022-02-12 18:14:50 -080084 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
Yash Chainani5c005da2022-01-22 16:51:11 -080085
Yash Chainani460c9fb2022-02-12 18:14:50 -080086 Eigen::Vector3d delta_t = H_delta.translation();
Yash Chainani5c005da2022-01-22 16:51:11 -080087
88 double r_norm = std::abs(delta_r.angle());
89 double t_norm = delta_t.norm();
90
Yash Chainani24fc2bd2022-02-14 12:43:29 -080091 bool store_image = false;
92 // Verify that camera has moved enough from last stored image
Yash Chainani5c005da2022-01-22 16:51:11 -080093 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
Yash Chainani24fc2bd2022-02-14 12:43:29 -080094 // frame_ refers to deltas between current and last captured image
95 Eigen::Affine3d frame_H_delta =
96 H_board_camera * prev_image_H_camera_board_;
97
98 Eigen::AngleAxisd frame_delta_r =
99 Eigen::AngleAxisd(frame_H_delta.rotation());
100
101 Eigen::Vector3d frame_delta_t = frame_H_delta.translation();
102
103 double frame_r_norm = std::abs(frame_delta_r.angle());
104 double frame_t_norm = frame_delta_t.norm();
105
106 // Make sure camera has stopped moving before storing image
107 store_image =
108 frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit;
109 }
110
111 prev_image_H_camera_board_ = H_camera_board_;
112
113 int keystroke = cv::waitKey(1);
114 if (store_image) {
Austin Schuh25837f22021-06-27 15:49:14 -0700115 if (valid) {
Yash Chainani460c9fb2022-02-12 18:14:50 -0800116 prev_H_camera_board_ = H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800117
Austin Schuh25837f22021-06-27 15:49:14 -0700118 all_charuco_ids_.emplace_back(std::move(charuco_ids));
119 all_charuco_corners_.emplace_back(std::move(charuco_corners));
Yash Chainani5c005da2022-01-22 16:51:11 -0800120
121 if (r_norm > kDeltaRThreshold) {
122 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
123 << kDeltaRThreshold;
124 }
125 if (t_norm > kDeltaTThreshold) {
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800126 LOG(INFO) << "Triggered by translation delta = " << t_norm << " > "
Yash Chainani5c005da2022-01-22 16:51:11 -0800127 << kDeltaTThreshold;
128 }
129
130 LOG(INFO) << "Image count " << all_charuco_corners_.size();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700131 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700132
Austin Schuh25837f22021-06-27 15:49:14 -0700133 if (all_charuco_ids_.size() >= 50) {
Ravago Jonescf453ab2020-05-06 21:14:53 -0700134 LOG(INFO) << "Got enough images to calibrate";
Austin Schuh25837f22021-06-27 15:49:14 -0700135 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700136 }
137 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
Austin Schuh25837f22021-06-27 15:49:14 -0700138 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700139 }
Austin Schuh25837f22021-06-27 15:49:14 -0700140 }
141
142 void MaybeCalibrate() {
143 if (all_charuco_ids_.size() >= 50) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800144 LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
145 << " images";
Austin Schuh25837f22021-06-27 15:49:14 -0700146 cv::Mat cameraMatrix, distCoeffs;
147 std::vector<cv::Mat> rvecs, tvecs;
148 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
149
150 // Set calibration flags (same as in calibrateCamera() function)
151 int calibration_flags = 0;
152 cv::Size img_size(640, 480);
153 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
154 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
155 img_size, cameraMatrix, distCoeffs, rvecs, tvecs,
156 stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors,
157 calibration_flags);
158 CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad.";
159 LOG(INFO) << "Reprojection Error is " << reprojection_error;
160
161 flatbuffers::FlatBufferBuilder fbb;
162 flatbuffers::Offset<flatbuffers::String> name_offset =
163 fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value()));
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800164 flatbuffers::Offset<flatbuffers::String> camera_id_offset =
165 fbb.CreateString(camera_id_);
Austin Schuh25837f22021-06-27 15:49:14 -0700166 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
167 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
168 return static_cast<float>(
169 reinterpret_cast<double *>(cameraMatrix.data)[i]);
170 });
171
172 flatbuffers::Offset<flatbuffers::Vector<float>>
173 distortion_coefficients_offset =
174 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
175 return static_cast<float>(
176 reinterpret_cast<double *>(distCoeffs.data)[i]);
177 });
178
179 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
180 std::optional<uint16_t> team_number =
181 aos::network::team_number_internal::ParsePiTeamNumber(pi_);
182 CHECK(team_number) << ": Invalid pi hostname " << pi_
183 << ", failed to parse team number";
184
185 const aos::realtime_clock::time_point realtime_now =
186 aos::realtime_clock::now();
187 camera_calibration_builder.add_node_name(name_offset);
188 camera_calibration_builder.add_team_number(team_number.value());
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800189 camera_calibration_builder.add_camera_id(camera_id_offset);
Austin Schuh25837f22021-06-27 15:49:14 -0700190 camera_calibration_builder.add_calibration_timestamp(
191 realtime_now.time_since_epoch().count());
192 camera_calibration_builder.add_intrinsics(intrinsics_offset);
193 camera_calibration_builder.add_dist_coeffs(
194 distortion_coefficients_offset);
195 fbb.Finish(camera_calibration_builder.Finish());
196
197 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
198 fbb.Release());
199 std::stringstream time_ss;
200 time_ss << realtime_now;
201
202 const std::string calibration_filename =
203 FLAGS_calibration_folder +
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800204 absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json",
205 team_number.value(), pi_number_.value(), camera_id_,
206 time_ss.str());
Austin Schuh25837f22021-06-27 15:49:14 -0700207
208 LOG(INFO) << calibration_filename << " -> "
209 << aos::FlatbufferToJson(camera_calibration,
210 {.multi_line = true});
211
212 aos::util::WriteStringToFileOrDie(
213 calibration_filename,
214 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
215 } else {
216 LOG(INFO) << "Skipping calibration due to not enough images.";
217 }
218 }
219
220 private:
Yash Chainani5c005da2022-01-22 16:51:11 -0800221 static constexpr double kDeltaRThreshold = M_PI / 6.0;
222 static constexpr double kDeltaTThreshold = 0.3;
223
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800224 static constexpr double kFrameDeltaRLimit = M_PI / 60;
225 static constexpr double kFrameDeltaTLimit = 0.01;
226
Austin Schuh25837f22021-06-27 15:49:14 -0700227 aos::ShmEventLoop *event_loop_;
228 std::string pi_;
229 const std::optional<uint16_t> pi_number_;
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800230 const std::string camera_id_;
Austin Schuh25837f22021-06-27 15:49:14 -0700231
232 std::vector<std::vector<int>> all_charuco_ids_;
233 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
234
Yash Chainani460c9fb2022-02-12 18:14:50 -0800235 Eigen::Affine3d H_camera_board_;
236 Eigen::Affine3d prev_H_camera_board_;
Yash Chainani24fc2bd2022-02-14 12:43:29 -0800237 Eigen::Affine3d prev_image_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800238
Austin Schuh25837f22021-06-27 15:49:14 -0700239 CharucoExtractor charuco_extractor_;
240};
241
242namespace {
243
244void Main() {
245 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
246 aos::configuration::ReadConfig(FLAGS_config);
247
248 aos::ShmEventLoop event_loop(&config.message());
249
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800250 std::string hostname = FLAGS_pi;
251 if (hostname == "") {
252 hostname = aos::network::GetHostname();
253 LOG(INFO) << "Using pi name from hostname as " << hostname;
254 }
255 Calibration extractor(&event_loop, hostname, FLAGS_camera_id);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700256
257 event_loop.Run();
258
Austin Schuh25837f22021-06-27 15:49:14 -0700259 extractor.MaybeCalibrate();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700260}
261
262} // namespace
263} // namespace vision
264} // namespace frc971
265
Austin Schuhc1f118e2020-04-11 15:50:08 -0700266int main(int argc, char **argv) {
267 aos::InitGoogle(&argc, &argv);
Austin Schuh25837f22021-06-27 15:49:14 -0700268 frc971::vision::Main();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700269}