blob: ec5bf40bbc5d34cd7bfcf098cfe639a77f0d2cdc [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>
5
Yash Chainani5c005da2022-01-22 16:51:11 -08006#include "Eigen/Dense"
7#include "Eigen/Geometry"
Austin Schuhc1f118e2020-04-11 15:50:08 -07008#include "absl/strings/str_format.h"
9#include "aos/events/shm_event_loop.h"
10#include "aos/init.h"
11#include "aos/network/team_number.h"
12#include "aos/time/time.h"
13#include "aos/util/file.h"
Yash Chainani5c005da2022-01-22 16:51:11 -080014#include "y2020/vision/charuco_lib.h"
Austin Schuhc1f118e2020-04-11 15:50:08 -070015
16DEFINE_string(config, "config.json", "Path to the config file to use.");
17DEFINE_string(pi, "pi-7971-1", "Pi name to calibrate.");
Yash Chainani5c005da2022-01-22 16:51:11 -080018DEFINE_string(calibration_folder, ".", "Folder to place calibration files.");
Austin Schuhc1f118e2020-04-11 15:50:08 -070019DEFINE_bool(display_undistorted, false,
20 "If true, display the undistorted image.");
Austin Schuhc1f118e2020-04-11 15:50:08 -070021
22namespace frc971 {
23namespace vision {
24
Austin Schuh25837f22021-06-27 15:49:14 -070025class Calibration {
Austin Schuhc1f118e2020-04-11 15:50:08 -070026 public:
Austin Schuh25837f22021-06-27 15:49:14 -070027 Calibration(aos::ShmEventLoop *event_loop, std::string_view pi)
28 : event_loop_(event_loop),
29 pi_(pi),
30 pi_number_(aos::network::ParsePiNumber(pi)),
Yash Chainani460c9fb2022-02-12 18:14:50 -080031 H_camera_board_(Eigen::Affine3d()),
32 prev_H_camera_board_(Eigen::Affine3d()),
Austin Schuh25837f22021-06-27 15:49:14 -070033 charuco_extractor_(
34 event_loop, pi,
Yash Chainani5c005da2022-01-22 16:51:11 -080035 [this](cv::Mat rgb_image,
36 const aos::monotonic_clock::time_point eof,
Austin Schuh25837f22021-06-27 15:49:14 -070037 std::vector<int> charuco_ids,
38 std::vector<cv::Point2f> charuco_corners, bool valid,
39 Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
Austin Schuhea7b0142021-10-08 22:04:53 -070040 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners,
Austin Schuh25837f22021-06-27 15:49:14 -070041 valid, rvec_eigen, tvec_eigen);
42 }) {
43 CHECK(pi_number_) << ": Invalid pi number " << pi
44 << ", failed to parse pi number";
Austin Schuhc1f118e2020-04-11 15:50:08 -070045 }
46
Austin Schuhea7b0142021-10-08 22:04:53 -070047 void HandleCharuco(cv::Mat rgb_image,
48 const aos::monotonic_clock::time_point /*eof*/,
Austin Schuh25837f22021-06-27 15:49:14 -070049 std::vector<int> charuco_ids,
50 std::vector<cv::Point2f> charuco_corners, bool valid,
Yash Chainani5c005da2022-01-22 16:51:11 -080051 Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
52 // Reduce resolution displayed on remote viewer to prevent lag
53 cv::resize(rgb_image, rgb_image,
54 cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
Ravago Jonescf453ab2020-05-06 21:14:53 -070055 cv::imshow("Display", rgb_image);
Austin Schuhc1f118e2020-04-11 15:50:08 -070056
Ravago Jonescf453ab2020-05-06 21:14:53 -070057 if (FLAGS_display_undistorted) {
Austin Schuh25837f22021-06-27 15:49:14 -070058 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
Ravago Jonescf453ab2020-05-06 21:14:53 -070059 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
Austin Schuh25837f22021-06-27 15:49:14 -070060 cv::undistort(rgb_image, undistorted_rgb_image,
61 charuco_extractor_.camera_matrix(),
62 charuco_extractor_.dist_coeffs());
Austin Schuhc1f118e2020-04-11 15:50:08 -070063
Ravago Jonescf453ab2020-05-06 21:14:53 -070064 cv::imshow("Display undist", undistorted_rgb_image);
65 }
Austin Schuhc1f118e2020-04-11 15:50:08 -070066
Yash Chainani5c005da2022-01-22 16:51:11 -080067 // Calibration calculates rotation and translation delta from last image
68 // captured to automatically capture next image
69
Yash Chainani460c9fb2022-02-12 18:14:50 -080070 Eigen::Affine3d H_board_camera =
71 Eigen::Translation3d(tvec_eigen) *
72 Eigen::AngleAxisd(rvec_eigen.norm(), rvec_eigen / rvec_eigen.norm());
73 H_camera_board_ = H_board_camera.inverse();
74 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -080075
Yash Chainani460c9fb2022-02-12 18:14:50 -080076 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
Yash Chainani5c005da2022-01-22 16:51:11 -080077
Yash Chainani460c9fb2022-02-12 18:14:50 -080078 Eigen::Vector3d delta_t = H_delta.translation();
Yash Chainani5c005da2022-01-22 16:51:11 -080079
80 double r_norm = std::abs(delta_r.angle());
81 double t_norm = delta_t.norm();
82
Ravago Jonescf453ab2020-05-06 21:14:53 -070083 int keystroke = cv::waitKey(1);
Yash Chainani5c005da2022-01-22 16:51:11 -080084 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
Austin Schuh25837f22021-06-27 15:49:14 -070085 if (valid) {
Yash Chainani460c9fb2022-02-12 18:14:50 -080086 prev_H_camera_board_ = H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -080087
Austin Schuh25837f22021-06-27 15:49:14 -070088 all_charuco_ids_.emplace_back(std::move(charuco_ids));
89 all_charuco_corners_.emplace_back(std::move(charuco_corners));
Yash Chainani5c005da2022-01-22 16:51:11 -080090
91 if (r_norm > kDeltaRThreshold) {
92 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
93 << kDeltaRThreshold;
94 }
95 if (t_norm > kDeltaTThreshold) {
96 LOG(INFO) << "Trigerred by translation delta = " << t_norm << " > "
97 << kDeltaTThreshold;
98 }
99
100 LOG(INFO) << "Image count " << all_charuco_corners_.size();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700101 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700102
Austin Schuh25837f22021-06-27 15:49:14 -0700103 if (all_charuco_ids_.size() >= 50) {
Ravago Jonescf453ab2020-05-06 21:14:53 -0700104 LOG(INFO) << "Got enough images to calibrate";
Austin Schuh25837f22021-06-27 15:49:14 -0700105 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700106 }
107 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
Austin Schuh25837f22021-06-27 15:49:14 -0700108 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -0700109 }
Austin Schuh25837f22021-06-27 15:49:14 -0700110 }
111
112 void MaybeCalibrate() {
113 if (all_charuco_ids_.size() >= 50) {
114 cv::Mat cameraMatrix, distCoeffs;
115 std::vector<cv::Mat> rvecs, tvecs;
116 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
117
118 // Set calibration flags (same as in calibrateCamera() function)
119 int calibration_flags = 0;
120 cv::Size img_size(640, 480);
121 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
122 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
123 img_size, cameraMatrix, distCoeffs, rvecs, tvecs,
124 stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors,
125 calibration_flags);
126 CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad.";
127 LOG(INFO) << "Reprojection Error is " << reprojection_error;
128
129 flatbuffers::FlatBufferBuilder fbb;
130 flatbuffers::Offset<flatbuffers::String> name_offset =
131 fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value()));
132 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
133 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
134 return static_cast<float>(
135 reinterpret_cast<double *>(cameraMatrix.data)[i]);
136 });
137
138 flatbuffers::Offset<flatbuffers::Vector<float>>
139 distortion_coefficients_offset =
140 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
141 return static_cast<float>(
142 reinterpret_cast<double *>(distCoeffs.data)[i]);
143 });
144
145 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
146 std::optional<uint16_t> team_number =
147 aos::network::team_number_internal::ParsePiTeamNumber(pi_);
148 CHECK(team_number) << ": Invalid pi hostname " << pi_
149 << ", failed to parse team number";
150
151 const aos::realtime_clock::time_point realtime_now =
152 aos::realtime_clock::now();
153 camera_calibration_builder.add_node_name(name_offset);
154 camera_calibration_builder.add_team_number(team_number.value());
155 camera_calibration_builder.add_calibration_timestamp(
156 realtime_now.time_since_epoch().count());
157 camera_calibration_builder.add_intrinsics(intrinsics_offset);
158 camera_calibration_builder.add_dist_coeffs(
159 distortion_coefficients_offset);
160 fbb.Finish(camera_calibration_builder.Finish());
161
162 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
163 fbb.Release());
164 std::stringstream time_ss;
165 time_ss << realtime_now;
166
167 const std::string calibration_filename =
168 FLAGS_calibration_folder +
169 absl::StrFormat("/calibration_pi-%d-%d_%s.json", team_number.value(),
170 pi_number_.value(), time_ss.str());
171
172 LOG(INFO) << calibration_filename << " -> "
173 << aos::FlatbufferToJson(camera_calibration,
174 {.multi_line = true});
175
176 aos::util::WriteStringToFileOrDie(
177 calibration_filename,
178 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
179 } else {
180 LOG(INFO) << "Skipping calibration due to not enough images.";
181 }
182 }
183
184 private:
Yash Chainani5c005da2022-01-22 16:51:11 -0800185 static constexpr double kDeltaRThreshold = M_PI / 6.0;
186 static constexpr double kDeltaTThreshold = 0.3;
187
Austin Schuh25837f22021-06-27 15:49:14 -0700188 aos::ShmEventLoop *event_loop_;
189 std::string pi_;
190 const std::optional<uint16_t> pi_number_;
191
192 std::vector<std::vector<int>> all_charuco_ids_;
193 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
194
Yash Chainani460c9fb2022-02-12 18:14:50 -0800195 Eigen::Affine3d H_camera_board_;
196 Eigen::Affine3d prev_H_camera_board_;
Yash Chainani5c005da2022-01-22 16:51:11 -0800197
Austin Schuh25837f22021-06-27 15:49:14 -0700198 CharucoExtractor charuco_extractor_;
199};
200
201namespace {
202
203void Main() {
204 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
205 aos::configuration::ReadConfig(FLAGS_config);
206
207 aos::ShmEventLoop event_loop(&config.message());
208
209 Calibration extractor(&event_loop, FLAGS_pi);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700210
211 event_loop.Run();
212
Austin Schuh25837f22021-06-27 15:49:14 -0700213 extractor.MaybeCalibrate();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700214}
215
216} // namespace
217} // namespace vision
218} // namespace frc971
219
Austin Schuhc1f118e2020-04-11 15:50:08 -0700220int main(int argc, char **argv) {
221 aos::InitGoogle(&argc, &argv);
Austin Schuh25837f22021-06-27 15:49:14 -0700222 frc971::vision::Main();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700223}