blob: 6cf9e8e93eee6920b70e82aeb49d97e3df2eb6fa [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
Austin Schuhc1f118e2020-04-11 15:50:08 -070099void ViewerMain() {
100 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
101 aos::configuration::ReadConfig(FLAGS_config);
102
103 aos::ShmEventLoop event_loop(&config.message());
104
105 const CameraCalibration calibration(SiftTrainingData());
106
107 cv::Ptr<cv::aruco::Dictionary> dictionary =
108 cv::aruco::getPredefinedDictionary(FLAGS_large_board
109 ? cv::aruco::DICT_5X5_100
110 : cv::aruco::DICT_6X6_250);
111 cv::Ptr<cv::aruco::CharucoBoard> board =
112 FLAGS_large_board
113 ? cv::aruco::CharucoBoard::create(12, 9, 0.06, 0.045, dictionary)
114 : cv::aruco::CharucoBoard::create(7, 5, 0.04, 0.025, dictionary);
115
116 if (!FLAGS_board_template_path.empty()) {
117 cv::Mat board_image;
118 board->draw(cv::Size(600, 500), board_image, 10, 1);
119 cv::imwrite(FLAGS_board_template_path, board_image);
120 }
121
122 std::vector<std::vector<int>> all_charuco_ids;
123 std::vector<std::vector<cv::Point2f>> all_charuco_corners;
124
125 const cv::Mat camera_matrix = calibration.CameraIntrinsics();
126 Eigen::Matrix3d eigen_camera_matrix;
127 cv::cv2eigen(camera_matrix, eigen_camera_matrix);
128
129 const cv::Mat dist_coeffs = calibration.CameraDistCoeffs();
130 LOG(INFO) << "Camera matrix " << camera_matrix;
131 LOG(INFO) << "Distortion Coefficients " << dist_coeffs;
132
133 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
134 CHECK(pi_number) << ": Invalid pi number " << FLAGS_pi
135 << ", failed to parse pi number";
136
137 const std::string channel =
138 absl::StrCat("/pi", std::to_string(pi_number.value()), "/camera");
139 LOG(INFO) << "Connecting to channel " << channel;
140
Ravago Jonescf453ab2020-05-06 21:14:53 -0700141 event_loop.MakeWatcher(channel, [&event_loop, &board, &all_charuco_ids,
142 &all_charuco_corners, camera_matrix,
143 dist_coeffs, eigen_camera_matrix](
144 const CameraImage &image) {
145 const aos::monotonic_clock::duration age =
146 event_loop.monotonic_now() - event_loop.context().monotonic_event_time;
147 const double age_double =
148 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
149 if (age > std::chrono::milliseconds(100)) {
150 LOG(INFO) << "Age: " << age_double << ", getting behind, skipping";
151 return;
152 }
153 // Create color image:
154 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
155 (void *)image.data()->data());
156 const cv::Size image_size(image.cols(), image.rows());
157 cv::Mat rgb_image(image_size, CV_8UC3);
158 cv::cvtColor(image_color_mat, rgb_image, CV_YUV2BGR_YUYV);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700159
Ravago Jonescf453ab2020-05-06 21:14:53 -0700160 std::vector<int> marker_ids;
161 std::vector<std::vector<cv::Point2f>> marker_corners;
Austin Schuhc1f118e2020-04-11 15:50:08 -0700162
Ravago Jonescf453ab2020-05-06 21:14:53 -0700163 cv::aruco::detectMarkers(rgb_image, board->dictionary, marker_corners,
164 marker_ids);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700165
Ravago Jonescf453ab2020-05-06 21:14:53 -0700166 std::vector<cv::Point2f> charuco_corners;
167 std::vector<int> charuco_ids;
168 // If at least one marker detected
169 if (marker_ids.size() >= FLAGS_min_targets) {
170 // Run everything twice, once with the calibration, and once without.
171 // This lets us both calibrate, and also print out the pose real time
172 // with the previous calibration.
173 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids,
174 rgb_image, board, charuco_corners,
175 charuco_ids);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700176
Ravago Jonescf453ab2020-05-06 21:14:53 -0700177 std::vector<cv::Point2f> charuco_corners_with_calibration;
178 std::vector<int> charuco_ids_with_calibration;
Austin Schuhc1f118e2020-04-11 15:50:08 -0700179
Ravago Jonescf453ab2020-05-06 21:14:53 -0700180 cv::aruco::interpolateCornersCharuco(
181 marker_corners, marker_ids, rgb_image, board,
182 charuco_corners_with_calibration, charuco_ids_with_calibration,
183 camera_matrix, dist_coeffs);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700184
Ravago Jonescf453ab2020-05-06 21:14:53 -0700185 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700186
Ravago Jonescf453ab2020-05-06 21:14:53 -0700187 if (charuco_ids.size() >= FLAGS_min_targets) {
188 cv::aruco::drawDetectedCornersCharuco(
189 rgb_image, charuco_corners, charuco_ids, cv::Scalar(255, 0, 0));
Austin Schuhc1f118e2020-04-11 15:50:08 -0700190
Ravago Jonescf453ab2020-05-06 21:14:53 -0700191 cv::Vec3d rvec, tvec;
192 bool valid = cv::aruco::estimatePoseCharucoBoard(
193 charuco_corners_with_calibration, charuco_ids_with_calibration,
194 board, camera_matrix, dist_coeffs, rvec, tvec);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700195
Ravago Jonescf453ab2020-05-06 21:14:53 -0700196 // if charuco pose is valid
197 if (valid) {
198 LOG(INFO) << std::fixed << std::setprecision(6)
199 << "Age: " << age_double << ", Pose is R:" << rvec
200 << " T:" << tvec;
201 cv::aruco::drawAxis(rgb_image, camera_matrix, dist_coeffs, rvec, tvec,
202 0.1);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700203 } else {
Ravago Jonescf453ab2020-05-06 21:14:53 -0700204 LOG(INFO) << "Age: " << age_double << ", invalid pose";
Austin Schuhc1f118e2020-04-11 15:50:08 -0700205 }
Ravago Jonescf453ab2020-05-06 21:14:53 -0700206 } else {
207 LOG(INFO) << "Age: " << age_double << ", no charuco IDs.";
208 }
209 } else {
210 LOG(INFO) << "Age: " << age_double << ", no marker IDs";
211 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700212
Ravago Jonescf453ab2020-05-06 21:14:53 -0700213 cv::imshow("Display", rgb_image);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700214
Ravago Jonescf453ab2020-05-06 21:14:53 -0700215 if (FLAGS_display_undistorted) {
216 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
217 cv::undistort(rgb_image, undistorted_rgb_image, camera_matrix,
218 dist_coeffs);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700219
Ravago Jonescf453ab2020-05-06 21:14:53 -0700220 cv::imshow("Display undist", undistorted_rgb_image);
221 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700222
Ravago Jonescf453ab2020-05-06 21:14:53 -0700223 int keystroke = cv::waitKey(1);
224 if ((keystroke & 0xFF) == static_cast<int>('c')) {
225 if (charuco_ids.size() >= FLAGS_min_targets) {
226 all_charuco_ids.emplace_back(std::move(charuco_ids));
227 all_charuco_corners.emplace_back(std::move(charuco_corners));
228 LOG(INFO) << "Image " << all_charuco_corners.size();
229 }
Austin Schuhc1f118e2020-04-11 15:50:08 -0700230
Ravago Jonescf453ab2020-05-06 21:14:53 -0700231 if (all_charuco_ids.size() >= 50) {
232 LOG(INFO) << "Got enough images to calibrate";
233 event_loop.Exit();
234 }
235 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
236 event_loop.Exit();
237 }
238 });
Austin Schuhc1f118e2020-04-11 15:50:08 -0700239
240 event_loop.Run();
241
242 if (all_charuco_ids.size() >= 50) {
243 cv::Mat cameraMatrix, distCoeffs;
244 std::vector<cv::Mat> rvecs, tvecs;
245 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
246
247 // Set calibration flags (same than in calibrateCamera() function)
248 int calibration_flags = 0;
249 cv::Size img_size(640, 480);
250 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
251 all_charuco_corners, all_charuco_ids, board, img_size, cameraMatrix,
252 distCoeffs, rvecs, tvecs, stdDeviationsIntrinsics,
253 stdDeviationsExtrinsics, perViewErrors, calibration_flags);
254 CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad.";
255 LOG(INFO) << "Reprojection Error is " << reprojection_error;
256
257 flatbuffers::FlatBufferBuilder fbb;
258 flatbuffers::Offset<flatbuffers::String> name_offset =
259 fbb.CreateString(absl::StrFormat("pi%d", pi_number.value()));
260 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
261 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
262 return static_cast<float>(
263 reinterpret_cast<double *>(cameraMatrix.data)[i]);
264 });
265
266 flatbuffers::Offset<flatbuffers::Vector<float>>
267 distortion_coefficients_offset =
268 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
269 return static_cast<float>(
270 reinterpret_cast<double *>(distCoeffs.data)[i]);
271 });
272
273 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
274 std::optional<uint16_t> team_number =
275 aos::network::team_number_internal::ParsePiTeamNumber(FLAGS_pi);
276 CHECK(team_number) << ": Invalid pi hostname " << FLAGS_pi
277 << ", failed to parse team number";
278
279 const aos::realtime_clock::time_point realtime_now =
280 aos::realtime_clock::now();
281 camera_calibration_builder.add_node_name(name_offset);
282 camera_calibration_builder.add_team_number(team_number.value());
283 camera_calibration_builder.add_calibration_timestamp(
284 realtime_now.time_since_epoch().count());
285 camera_calibration_builder.add_intrinsics(intrinsics_offset);
286 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
287 camera_calibration_builder.add_dist_coeffs(distortion_coefficients_offset);
288 fbb.Finish(camera_calibration_builder.Finish());
289
290 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
291 fbb.Release());
292 std::stringstream time_ss;
293 time_ss << realtime_now;
294
295 const std::string calibration_filename =
296 FLAGS_calibration_folder +
297 absl::StrFormat("/calibration_pi-%d-%d_%s.json", team_number.value(),
298 pi_number.value(), time_ss.str());
299
300 LOG(INFO) << calibration_filename << " -> "
Ravago Jonescf453ab2020-05-06 21:14:53 -0700301 << aos::FlatbufferToJson(camera_calibration,
302 {.multi_line = true});
Austin Schuhc1f118e2020-04-11 15:50:08 -0700303
304 aos::util::WriteStringToFileOrDie(
Ravago Jonescf453ab2020-05-06 21:14:53 -0700305 calibration_filename,
306 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
Austin Schuhc1f118e2020-04-11 15:50:08 -0700307 } else {
308 LOG(INFO) << "Skipping calibration due to not enough images.";
309 }
310}
311
312} // namespace
313} // namespace vision
314} // namespace frc971
315
316// Quick and lightweight grayscale viewer for images
317int main(int argc, char **argv) {
318 aos::InitGoogle(&argc, &argv);
319 frc971::vision::ViewerMain();
320}