blob: 15f1f4c7986782e69be7e585b809d96d44e570e5 [file] [log] [blame]
Austin Schuhc1f118e2020-04-11 15:50:08 -07001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3#include <opencv2/aruco/charuco.hpp>
4#include <opencv2/calib3d.hpp>
5#include <opencv2/core/eigen.hpp>
6#include <opencv2/features2d.hpp>
7#include <opencv2/highgui/highgui.hpp>
8#include <opencv2/imgproc.hpp>
9
10#include "absl/strings/str_format.h"
11#include "aos/events/shm_event_loop.h"
12#include "aos/init.h"
13#include "aos/network/team_number.h"
14#include "aos/time/time.h"
15#include "aos/util/file.h"
16#include "frc971/control_loops/drivetrain/improved_down_estimator.h"
17#include "y2020/vision/sift/sift_generated.h"
18#include "y2020/vision/sift/sift_training_generated.h"
19#include "y2020/vision/tools/python_code/sift_training_data.h"
20#include "y2020/vision/vision_generated.h"
21
22DEFINE_string(config, "config.json", "Path to the config file to use.");
23DEFINE_string(pi, "pi-7971-1", "Pi name to calibrate.");
24DEFINE_string(calibration_folder, "y2020/vision/tools/python_code/calib_files",
25 "Folder to place calibration files.");
26DEFINE_bool(large_board, true, "If true, use the large calibration board.");
27DEFINE_bool(display_undistorted, false,
28 "If true, display the undistorted image.");
29DEFINE_string(board_template_path, "",
30 "If specified, write an image to the specified path for the "
31 "charuco board pattern.");
32DEFINE_uint32(min_targets, 10,
33 "The mininum number of targets required to match.");
34
35namespace frc971 {
36namespace vision {
37
38class CameraCalibration {
39 public:
40 CameraCalibration(const std::string_view training_data_bfbs) {
41 const sift::TrainingData *const training_data =
42 flatbuffers::GetRoot<sift::TrainingData>(training_data_bfbs.data());
43 {
44 flatbuffers::Verifier verifier(
45 reinterpret_cast<const uint8_t *>(training_data_bfbs.data()),
46 training_data_bfbs.size());
47 CHECK(training_data->Verify(verifier));
48 }
49
50 camera_calibration_ = FindCameraCalibration(training_data);
51 }
52
53 cv::Mat CameraIntrinsics() const {
54 const cv::Mat result(3, 3, CV_32F,
55 const_cast<void *>(static_cast<const void *>(
56 camera_calibration_->intrinsics()->data())));
57 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
58 return result;
59 }
60
61 cv::Mat CameraDistCoeffs() const {
62 const cv::Mat result(5, 1, CV_32F,
63 const_cast<void *>(static_cast<const void *>(
64 camera_calibration_->dist_coeffs()->data())));
65 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
66 return result;
67 }
68
69 private:
70 const sift::CameraCalibration *FindCameraCalibration(
71 const sift::TrainingData *const training_data) const {
72 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
73 std::optional<uint16_t> team_number =
74 aos::network::team_number_internal::ParsePiTeamNumber(FLAGS_pi);
75 CHECK(pi_number);
76 CHECK(team_number);
77 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
78 LOG(INFO) << "Looking for node name " << node_name << " team number "
79 << team_number.value();
80 for (const sift::CameraCalibration *candidate :
81 *training_data->camera_calibrations()) {
82 if (candidate->node_name()->string_view() != node_name) {
83 continue;
84 }
85 if (candidate->team_number() != team_number.value()) {
86 continue;
87 }
88 return candidate;
89 }
90 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
91 << " on " << team_number.value();
92 }
93
94 const sift::CameraCalibration *camera_calibration_;
95};
96
97namespace {
98
99
100void ViewerMain() {
101 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
102 aos::configuration::ReadConfig(FLAGS_config);
103
104 aos::ShmEventLoop event_loop(&config.message());
105
106 const CameraCalibration calibration(SiftTrainingData());
107
108 cv::Ptr<cv::aruco::Dictionary> dictionary =
109 cv::aruco::getPredefinedDictionary(FLAGS_large_board
110 ? cv::aruco::DICT_5X5_100
111 : cv::aruco::DICT_6X6_250);
112 cv::Ptr<cv::aruco::CharucoBoard> board =
113 FLAGS_large_board
114 ? cv::aruco::CharucoBoard::create(12, 9, 0.06, 0.045, dictionary)
115 : cv::aruco::CharucoBoard::create(7, 5, 0.04, 0.025, dictionary);
116
117 if (!FLAGS_board_template_path.empty()) {
118 cv::Mat board_image;
119 board->draw(cv::Size(600, 500), board_image, 10, 1);
120 cv::imwrite(FLAGS_board_template_path, board_image);
121 }
122
123 std::vector<std::vector<int>> all_charuco_ids;
124 std::vector<std::vector<cv::Point2f>> all_charuco_corners;
125
126 const cv::Mat camera_matrix = calibration.CameraIntrinsics();
127 Eigen::Matrix3d eigen_camera_matrix;
128 cv::cv2eigen(camera_matrix, eigen_camera_matrix);
129
130 const cv::Mat dist_coeffs = calibration.CameraDistCoeffs();
131 LOG(INFO) << "Camera matrix " << camera_matrix;
132 LOG(INFO) << "Distortion Coefficients " << dist_coeffs;
133
134 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
135 CHECK(pi_number) << ": Invalid pi number " << FLAGS_pi
136 << ", failed to parse pi number";
137
138 const std::string channel =
139 absl::StrCat("/pi", std::to_string(pi_number.value()), "/camera");
140 LOG(INFO) << "Connecting to channel " << channel;
141
142 event_loop.MakeWatcher(
143 channel, [&event_loop, &board, &all_charuco_ids, &all_charuco_corners,
144 camera_matrix, dist_coeffs,
145 eigen_camera_matrix](const CameraImage &image) {
146 const aos::monotonic_clock::duration age =
147 event_loop.monotonic_now() -
148 event_loop.context().monotonic_event_time;
149 const double age_double =
150 std::chrono::duration_cast<std::chrono::duration<double>>(age)
151 .count();
152 if (age > std::chrono::milliseconds(100)) {
153 LOG(INFO) << "Age: " << age_double << ", getting behind, skipping";
154 return;
155 }
156 // Create color image:
157 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
158 (void *)image.data()->data());
159 const cv::Size image_size(image.cols(), image.rows());
160 cv::Mat rgb_image(image_size, CV_8UC3);
161 cv::cvtColor(image_color_mat, rgb_image, CV_YUV2BGR_YUYV);
162
163 std::vector<int> marker_ids;
164 std::vector<std::vector<cv::Point2f>> marker_corners;
165
166 cv::aruco::detectMarkers(rgb_image, board->dictionary, marker_corners,
167 marker_ids);
168
169 std::vector<cv::Point2f> charuco_corners;
170 std::vector<int> charuco_ids;
171 // If at least one marker detected
172 if (marker_ids.size() >= FLAGS_min_targets) {
173 // Run everything twice, once with the calibration, and once without.
174 // This lets us both calibrate, and also print out the pose real time
175 // with the previous calibration.
176 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
177 rgb_image, board,
178 charuco_corners, charuco_ids);
179
180 std::vector<cv::Point2f> charuco_corners_with_calibration;
181 std::vector<int> charuco_ids_with_calibration;
182
183 cv::aruco::interpolateCornersCharuco(
184 marker_corners, marker_ids, rgb_image, board,
185 charuco_corners_with_calibration, charuco_ids_with_calibration,
186 camera_matrix, dist_coeffs);
187
188 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
189
190 if (charuco_ids.size() >= FLAGS_min_targets) {
191 cv::aruco::drawDetectedCornersCharuco(
192 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
193
194 cv::Vec3d rvec, tvec;
195 bool valid = cv::aruco::estimatePoseCharucoBoard(
196 charuco_corners_with_calibration, charuco_ids_with_calibration,
197 board, camera_matrix, dist_coeffs, rvec, tvec);
198
199
200 // if charuco pose is valid
201 if (valid) {
202 LOG(INFO) << std::fixed << std::setprecision(6)
203 << "Age: " << age_double << ", Pose is R:" << rvec
204 << " T:" << tvec;
205 cv::aruco::drawAxis(rgb_image, camera_matrix,
206 dist_coeffs, rvec, tvec, 0.1);
207 } else {
208 LOG(INFO) << "Age: " << age_double << ", invalid pose";
209 }
210 } else {
211 LOG(INFO) << "Age: " << age_double << ", no charuco IDs.";
212 }
213 } else {
214 LOG(INFO) << "Age: " << age_double << ", no marker IDs";
215 }
216
217 cv::imshow("Display", rgb_image);
218
219 if (FLAGS_display_undistorted) {
220 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
221 cv::undistort(rgb_image, undistorted_rgb_image, camera_matrix,
222 dist_coeffs);
223
224 cv::imshow("Display undist", undistorted_rgb_image);
225 }
226
227 int keystroke = cv::waitKey(1);
228 if ((keystroke & 0xFF) == static_cast<int>('c')) {
229 if (charuco_ids.size() >= FLAGS_min_targets) {
230 all_charuco_ids.emplace_back(std::move(charuco_ids));
231 all_charuco_corners.emplace_back(std::move(charuco_corners));
232 LOG(INFO) << "Image " << all_charuco_corners.size();
233 }
234
235 if (all_charuco_ids.size() >= 50) {
236 LOG(INFO) << "Got enough images to calibrate";
237 event_loop.Exit();
238 }
239 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
240 event_loop.Exit();
241 }
242 });
243
244 event_loop.Run();
245
246 if (all_charuco_ids.size() >= 50) {
247 cv::Mat cameraMatrix, distCoeffs;
248 std::vector<cv::Mat> rvecs, tvecs;
249 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
250
251 // Set calibration flags (same than in calibrateCamera() function)
252 int calibration_flags = 0;
253 cv::Size img_size(640, 480);
254 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
255 all_charuco_corners, all_charuco_ids, board, img_size, cameraMatrix,
256 distCoeffs, rvecs, tvecs, stdDeviationsIntrinsics,
257 stdDeviationsExtrinsics, perViewErrors, calibration_flags);
258 CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad.";
259 LOG(INFO) << "Reprojection Error is " << reprojection_error;
260
261 flatbuffers::FlatBufferBuilder fbb;
262 flatbuffers::Offset<flatbuffers::String> name_offset =
263 fbb.CreateString(absl::StrFormat("pi%d", pi_number.value()));
264 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
265 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
266 return static_cast<float>(
267 reinterpret_cast<double *>(cameraMatrix.data)[i]);
268 });
269
270 flatbuffers::Offset<flatbuffers::Vector<float>>
271 distortion_coefficients_offset =
272 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
273 return static_cast<float>(
274 reinterpret_cast<double *>(distCoeffs.data)[i]);
275 });
276
277 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
278 std::optional<uint16_t> team_number =
279 aos::network::team_number_internal::ParsePiTeamNumber(FLAGS_pi);
280 CHECK(team_number) << ": Invalid pi hostname " << FLAGS_pi
281 << ", failed to parse team number";
282
283 const aos::realtime_clock::time_point realtime_now =
284 aos::realtime_clock::now();
285 camera_calibration_builder.add_node_name(name_offset);
286 camera_calibration_builder.add_team_number(team_number.value());
287 camera_calibration_builder.add_calibration_timestamp(
288 realtime_now.time_since_epoch().count());
289 camera_calibration_builder.add_intrinsics(intrinsics_offset);
290 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
291 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
292 fbb.Finish(camera_calibration_builder.Finish());
293
294 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
295 fbb.Release());
296 std::stringstream time_ss;
297 time_ss << realtime_now;
298
299 const std::string calibration_filename =
300 FLAGS_calibration_folder +
301 absl::StrFormat("/calibration_pi-%d-%d_%s.json", team_number.value(),
302 pi_number.value(), time_ss.str());
303
304 LOG(INFO) << calibration_filename << " -> "
305 << aos::FlatbufferToJson(camera_calibration, true);
306
307 aos::util::WriteStringToFileOrDie(
308 calibration_filename, aos::FlatbufferToJson(camera_calibration, true));
309 } else {
310 LOG(INFO) << "Skipping calibration due to not enough images.";
311 }
312}
313
314} // namespace
315} // namespace vision
316} // namespace frc971
317
318// Quick and lightweight grayscale viewer for images
319int main(int argc, char **argv) {
320 aos::InitGoogle(&argc, &argv);
321 frc971::vision::ViewerMain();
322}