blob: 6cf53e875a037b5319ae228d4939ba2f28ed115b [file] [log] [blame]
James Kuszmaul7e958812023-02-11 15:34:31 -08001#include "frc971/vision/intrinsics_calibration_lib.h"
2
3namespace frc971 {
4namespace vision {
5
6IntrinsicsCalibration::IntrinsicsCalibration(
7 aos::EventLoop *event_loop, std::string_view pi, std::string_view camera_id,
8 std::string_view base_intrinsics_file, bool display_undistorted,
9 std::string_view calibration_folder, aos::ExitHandle *exit_handle)
10 : pi_(pi),
11 pi_number_(aos::network::ParsePiNumber(pi)),
12 camera_id_(camera_id),
13 prev_H_camera_board_(Eigen::Affine3d()),
14 prev_image_H_camera_board_(Eigen::Affine3d()),
15 base_intrinsics_(
16 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
17 base_intrinsics_file)),
18 charuco_extractor_(
19 event_loop, &base_intrinsics_.message(), TargetType::kCharuco,
20 "/camera",
21 [this](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof,
22 std::vector<cv::Vec4i> charuco_ids,
23 std::vector<std::vector<cv::Point2f>> charuco_corners,
24 bool valid, std::vector<Eigen::Vector3d> rvecs_eigen,
25 std::vector<Eigen::Vector3d> tvecs_eigen) {
26 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners, valid,
27 rvecs_eigen, tvecs_eigen);
28 }),
29 image_callback_(
30 event_loop,
31 absl::StrCat("/pi",
32 std::to_string(aos::network::ParsePiNumber(pi).value()),
33 "/camera"),
34 [this](cv::Mat rgb_image,
35 const aos::monotonic_clock::time_point eof) {
36 charuco_extractor_.HandleImage(rgb_image, eof);
37 },
38 std::chrono::milliseconds(5)),
39 display_undistorted_(display_undistorted),
40 calibration_folder_(calibration_folder),
41 exit_handle_(exit_handle) {
42 CHECK(pi_number_) << ": Invalid pi number " << pi
43 << ", failed to parse pi number";
44 std::regex re{"^[0-9][0-9]-[0-9][0-9]"};
45 CHECK(std::regex_match(camera_id_, re))
46 << ": Invalid camera_id '" << camera_id_ << "', should be of form YY-NN";
47}
48
49void IntrinsicsCalibration::HandleCharuco(
50 cv::Mat rgb_image, const aos::monotonic_clock::time_point /*eof*/,
51 std::vector<cv::Vec4i> charuco_ids,
52 std::vector<std::vector<cv::Point2f>> charuco_corners, bool valid,
53 std::vector<Eigen::Vector3d> rvecs_eigen,
54 std::vector<Eigen::Vector3d> tvecs_eigen) {
55 // Reduce resolution displayed on remote viewer to prevent lag
56 cv::resize(rgb_image, rgb_image,
57 cv::Size(rgb_image.cols / 2, rgb_image.rows / 2));
58 cv::imshow("Display", rgb_image);
59
60 if (display_undistorted_) {
61 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
62 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
63 cv::undistort(rgb_image, undistorted_rgb_image,
64 charuco_extractor_.camera_matrix(),
65 charuco_extractor_.dist_coeffs());
66
67 cv::imshow("Display undist", undistorted_rgb_image);
68 }
69
70 int keystroke = cv::waitKey(1);
71
72 // If we haven't got a valid pose estimate, don't use these points
73 if (!valid) {
74 return;
75 }
76 CHECK(tvecs_eigen.size() == 1)
77 << "Charuco board should only return one translational pose";
78 CHECK(rvecs_eigen.size() == 1)
79 << "Charuco board should only return one rotational pose";
80 // Calibration calculates rotation and translation delta from last image
81 // stored to automatically capture next image
82
83 Eigen::Affine3d H_board_camera =
84 Eigen::Translation3d(tvecs_eigen[0]) *
85 Eigen::AngleAxisd(rvecs_eigen[0].norm(),
86 rvecs_eigen[0] / rvecs_eigen[0].norm());
87 Eigen::Affine3d H_camera_board_ = H_board_camera.inverse();
88 Eigen::Affine3d H_delta = H_board_camera * prev_H_camera_board_;
89
90 Eigen::AngleAxisd delta_r = Eigen::AngleAxisd(H_delta.rotation());
91
92 Eigen::Vector3d delta_t = H_delta.translation();
93
94 double r_norm = std::abs(delta_r.angle());
95 double t_norm = delta_t.norm();
96
97 bool store_image = false;
98 double percent_motion =
99 std::max<double>(r_norm / kDeltaRThreshold, t_norm / kDeltaTThreshold);
100 LOG(INFO) << "Captured: " << all_charuco_ids_.size() << " points; Moved "
101 << percent_motion << "% of what's needed";
102 // Verify that camera has moved enough from last stored image
103 if (r_norm > kDeltaRThreshold || t_norm > kDeltaTThreshold) {
104 // frame_ refers to deltas between current and last captured image
105 Eigen::Affine3d frame_H_delta = H_board_camera * prev_image_H_camera_board_;
106
107 Eigen::AngleAxisd frame_delta_r =
108 Eigen::AngleAxisd(frame_H_delta.rotation());
109
110 Eigen::Vector3d frame_delta_t = frame_H_delta.translation();
111
112 double frame_r_norm = std::abs(frame_delta_r.angle());
113 double frame_t_norm = frame_delta_t.norm();
114
115 // Make sure camera has stopped moving before storing image
116 store_image =
117 frame_r_norm < kFrameDeltaRLimit && frame_t_norm < kFrameDeltaTLimit;
118 double percent_stop = std::max<double>(frame_r_norm / kFrameDeltaRLimit,
119 frame_t_norm / kFrameDeltaTLimit);
120 LOG(INFO) << "Captured: " << all_charuco_ids_.size()
121 << "points; Moved enough (" << percent_motion
122 << "%); Need to stop (last motion was " << percent_stop
123 << "% of limit; needs to be < 1 to capture)";
124 }
125 prev_image_H_camera_board_ = H_camera_board_;
126
127 if (store_image) {
128 if (valid) {
129 prev_H_camera_board_ = H_camera_board_;
130
131 // Unpack the Charuco ids from Vec4i
132 std::vector<int> charuco_ids_int;
133 for (cv::Vec4i charuco_id : charuco_ids) {
134 charuco_ids_int.emplace_back(charuco_id[0]);
135 }
136 all_charuco_ids_.emplace_back(std::move(charuco_ids_int));
137 all_charuco_corners_.emplace_back(std::move(charuco_corners[0]));
138
139 if (r_norm > kDeltaRThreshold) {
140 LOG(INFO) << "Triggered by rotation delta = " << r_norm << " > "
141 << kDeltaRThreshold;
142 }
143 if (t_norm > kDeltaTThreshold) {
144 LOG(INFO) << "Triggered by translation delta = " << t_norm << " > "
145 << kDeltaTThreshold;
146 }
147 }
148
149 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
150 exit_handle_->Exit();
151 }
152}
153
154aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
155IntrinsicsCalibration::BuildCalibration(
156 cv::Mat camera_matrix, cv::Mat dist_coeffs,
157 aos::realtime_clock::time_point realtime_now, int pi_number,
158 std::string_view camera_id, uint16_t team_number) {
159 flatbuffers::FlatBufferBuilder fbb;
160 flatbuffers::Offset<flatbuffers::String> name_offset =
161 fbb.CreateString(absl::StrFormat("pi%d", pi_number));
162 flatbuffers::Offset<flatbuffers::String> camera_id_offset =
163 fbb.CreateString(camera_id);
164 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
165 fbb.CreateVector<float>(9u, [&camera_matrix](size_t i) {
166 return static_cast<float>(
167 reinterpret_cast<double *>(camera_matrix.data)[i]);
168 });
169
170 flatbuffers::Offset<flatbuffers::Vector<float>>
171 distortion_coefficients_offset =
172 fbb.CreateVector<float>(5u, [&dist_coeffs](size_t i) {
173 return static_cast<float>(
174 reinterpret_cast<double *>(dist_coeffs.data)[i]);
175 });
176
177 calibration::CameraCalibration::Builder camera_calibration_builder(fbb);
178
179 camera_calibration_builder.add_node_name(name_offset);
180 camera_calibration_builder.add_team_number(team_number);
181 camera_calibration_builder.add_camera_id(camera_id_offset);
182 camera_calibration_builder.add_calibration_timestamp(
183 realtime_now.time_since_epoch().count());
184 camera_calibration_builder.add_intrinsics(intrinsics_offset);
185 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
186 fbb.Finish(camera_calibration_builder.Finish());
187
188 return fbb.Release();
189}
190
191void IntrinsicsCalibration::MaybeCalibrate() {
192 // TODO: This number should depend on coarse vs. fine pattern
193 // Maybe just on total # of ids found, not just images
194 if (all_charuco_ids_.size() >= 50) {
195 LOG(INFO) << "Beginning calibration on " << all_charuco_ids_.size()
196 << " images";
197 cv::Mat camera_matrix, dist_coeffs;
198 std::vector<cv::Mat> rvecs, tvecs;
199 cv::Mat std_deviations_intrinsics, std_deviations_extrinsics,
200 per_view_errors;
201
202 // Set calibration flags (same as in calibrateCamera() function)
203 int calibration_flags = 0;
204 cv::Size img_size(640, 480);
205 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
206 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
207 img_size, camera_matrix, dist_coeffs, rvecs, tvecs,
208 std_deviations_intrinsics, std_deviations_extrinsics, per_view_errors,
209 calibration_flags);
210 CHECK_LE(reprojection_error, 1.0)
211 << ": Reproduction error is bad-- greater than 1 pixel.";
212 LOG(INFO) << "Reprojection Error is " << reprojection_error;
213
214 const aos::realtime_clock::time_point realtime_now =
215 aos::realtime_clock::now();
216 std::optional<uint16_t> team_number =
217 aos::network::team_number_internal::ParsePiTeamNumber(pi_);
218 CHECK(team_number) << ": Invalid pi hostname " << pi_
219 << ", failed to parse team number";
220 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
221 camera_calibration = BuildCalibration(camera_matrix, dist_coeffs,
222 realtime_now, pi_number_.value(),
223 camera_id_, team_number.value());
224 std::stringstream time_ss;
225 time_ss << realtime_now;
226
227 const std::string calibration_filename =
228 calibration_folder_ +
229 absl::StrFormat("/calibration_pi-%d-%d_cam-%s_%s.json",
230 team_number.value(), pi_number_.value(), camera_id_,
231 time_ss.str());
232
233 LOG(INFO) << calibration_filename << " -> "
234 << aos::FlatbufferToJson(camera_calibration,
235 {.multi_line = true});
236
237 aos::util::WriteStringToFileOrDie(
238 calibration_filename,
239 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
240 } else {
241 LOG(INFO) << "Skipping calibration due to not enough images.";
242 }
243}
244} // namespace vision
245} // namespace frc971