blob: 80f14911bf9a04eab3bc22faa7316e4533baeb9f [file] [log] [blame]
Austin Schuhc1f118e2020-04-11 15:50:08 -07001#include "Eigen/Dense"
2#include "Eigen/Geometry"
Brian Silverman36c7f342021-06-11 15:21:41 -07003
Austin Schuhc1f118e2020-04-11 15:50:08 -07004#include <opencv2/calib3d.hpp>
Austin Schuhc1f118e2020-04-11 15:50:08 -07005#include <opencv2/highgui/highgui.hpp>
6#include <opencv2/imgproc.hpp>
7
8#include "absl/strings/str_format.h"
Austin Schuh25837f22021-06-27 15:49:14 -07009#include "y2020/vision/charuco_lib.h"
Austin Schuhc1f118e2020-04-11 15:50:08 -070010#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"
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.");
18DEFINE_string(calibration_folder, "y2020/vision/tools/python_code/calib_files",
19 "Folder to place calibration files.");
Austin Schuhc1f118e2020-04-11 15:50:08 -070020DEFINE_bool(display_undistorted, false,
21 "If true, display the undistorted image.");
Austin Schuhc1f118e2020-04-11 15:50:08 -070022
23namespace frc971 {
24namespace vision {
25
Austin Schuh25837f22021-06-27 15:49:14 -070026class Calibration {
Austin Schuhc1f118e2020-04-11 15:50:08 -070027 public:
Austin Schuh25837f22021-06-27 15:49:14 -070028 Calibration(aos::ShmEventLoop *event_loop, std::string_view pi)
29 : event_loop_(event_loop),
30 pi_(pi),
31 pi_number_(aos::network::ParsePiNumber(pi)),
32 charuco_extractor_(
33 event_loop, pi,
Austin Schuhea7b0142021-10-08 22:04:53 -070034 [this](cv::Mat rgb_image, const aos::monotonic_clock::time_point eof,
Austin Schuh25837f22021-06-27 15:49:14 -070035 std::vector<int> charuco_ids,
36 std::vector<cv::Point2f> charuco_corners, bool valid,
37 Eigen::Vector3d rvec_eigen, Eigen::Vector3d tvec_eigen) {
Austin Schuhea7b0142021-10-08 22:04:53 -070038 HandleCharuco(rgb_image, eof, charuco_ids, charuco_corners,
Austin Schuh25837f22021-06-27 15:49:14 -070039 valid, rvec_eigen, tvec_eigen);
40 }) {
41 CHECK(pi_number_) << ": Invalid pi number " << pi
42 << ", failed to parse pi number";
Austin Schuhc1f118e2020-04-11 15:50:08 -070043 }
44
Austin Schuhea7b0142021-10-08 22:04:53 -070045 void HandleCharuco(cv::Mat rgb_image,
46 const aos::monotonic_clock::time_point /*eof*/,
Austin Schuh25837f22021-06-27 15:49:14 -070047 std::vector<int> charuco_ids,
48 std::vector<cv::Point2f> charuco_corners, bool valid,
49 Eigen::Vector3d /*rvec_eigen*/,
50 Eigen::Vector3d /*tvec_eigen*/) {
Ravago Jonescf453ab2020-05-06 21:14:53 -070051 cv::imshow("Display", rgb_image);
Austin Schuhc1f118e2020-04-11 15:50:08 -070052
Ravago Jonescf453ab2020-05-06 21:14:53 -070053 if (FLAGS_display_undistorted) {
Austin Schuh25837f22021-06-27 15:49:14 -070054 const cv::Size image_size(rgb_image.cols, rgb_image.rows);
Ravago Jonescf453ab2020-05-06 21:14:53 -070055 cv::Mat undistorted_rgb_image(image_size, CV_8UC3);
Austin Schuh25837f22021-06-27 15:49:14 -070056 cv::undistort(rgb_image, undistorted_rgb_image,
57 charuco_extractor_.camera_matrix(),
58 charuco_extractor_.dist_coeffs());
Austin Schuhc1f118e2020-04-11 15:50:08 -070059
Ravago Jonescf453ab2020-05-06 21:14:53 -070060 cv::imshow("Display undist", undistorted_rgb_image);
61 }
Austin Schuhc1f118e2020-04-11 15:50:08 -070062
Ravago Jonescf453ab2020-05-06 21:14:53 -070063 int keystroke = cv::waitKey(1);
64 if ((keystroke & 0xFF) == static_cast<int>('c')) {
Austin Schuh25837f22021-06-27 15:49:14 -070065 if (valid) {
66 all_charuco_ids_.emplace_back(std::move(charuco_ids));
67 all_charuco_corners_.emplace_back(std::move(charuco_corners));
68 LOG(INFO) << "Image " << all_charuco_corners_.size();
Ravago Jonescf453ab2020-05-06 21:14:53 -070069 }
Austin Schuhc1f118e2020-04-11 15:50:08 -070070
Austin Schuh25837f22021-06-27 15:49:14 -070071 if (all_charuco_ids_.size() >= 50) {
Ravago Jonescf453ab2020-05-06 21:14:53 -070072 LOG(INFO) << "Got enough images to calibrate";
Austin Schuh25837f22021-06-27 15:49:14 -070073 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -070074 }
75 } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
Austin Schuh25837f22021-06-27 15:49:14 -070076 event_loop_->Exit();
Ravago Jonescf453ab2020-05-06 21:14:53 -070077 }
Austin Schuh25837f22021-06-27 15:49:14 -070078 }
79
80 void MaybeCalibrate() {
81 if (all_charuco_ids_.size() >= 50) {
82 cv::Mat cameraMatrix, distCoeffs;
83 std::vector<cv::Mat> rvecs, tvecs;
84 cv::Mat stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors;
85
86 // Set calibration flags (same as in calibrateCamera() function)
87 int calibration_flags = 0;
88 cv::Size img_size(640, 480);
89 const double reprojection_error = cv::aruco::calibrateCameraCharuco(
90 all_charuco_corners_, all_charuco_ids_, charuco_extractor_.board(),
91 img_size, cameraMatrix, distCoeffs, rvecs, tvecs,
92 stdDeviationsIntrinsics, stdDeviationsExtrinsics, perViewErrors,
93 calibration_flags);
94 CHECK_LE(reprojection_error, 1.0) << ": Reproduction error is bad.";
95 LOG(INFO) << "Reprojection Error is " << reprojection_error;
96
97 flatbuffers::FlatBufferBuilder fbb;
98 flatbuffers::Offset<flatbuffers::String> name_offset =
99 fbb.CreateString(absl::StrFormat("pi%d", pi_number_.value()));
100 flatbuffers::Offset<flatbuffers::Vector<float>> intrinsics_offset =
101 fbb.CreateVector<float>(9u, [&cameraMatrix](size_t i) {
102 return static_cast<float>(
103 reinterpret_cast<double *>(cameraMatrix.data)[i]);
104 });
105
106 flatbuffers::Offset<flatbuffers::Vector<float>>
107 distortion_coefficients_offset =
108 fbb.CreateVector<float>(5u, [&distCoeffs](size_t i) {
109 return static_cast<float>(
110 reinterpret_cast<double *>(distCoeffs.data)[i]);
111 });
112
113 sift::CameraCalibration::Builder camera_calibration_builder(fbb);
114 std::optional<uint16_t> team_number =
115 aos::network::team_number_internal::ParsePiTeamNumber(pi_);
116 CHECK(team_number) << ": Invalid pi hostname " << pi_
117 << ", failed to parse team number";
118
119 const aos::realtime_clock::time_point realtime_now =
120 aos::realtime_clock::now();
121 camera_calibration_builder.add_node_name(name_offset);
122 camera_calibration_builder.add_team_number(team_number.value());
123 camera_calibration_builder.add_calibration_timestamp(
124 realtime_now.time_since_epoch().count());
125 camera_calibration_builder.add_intrinsics(intrinsics_offset);
126 camera_calibration_builder.add_dist_coeffs(
127 distortion_coefficients_offset);
128 fbb.Finish(camera_calibration_builder.Finish());
129
130 aos::FlatbufferDetachedBuffer<sift::CameraCalibration> camera_calibration(
131 fbb.Release());
132 std::stringstream time_ss;
133 time_ss << realtime_now;
134
135 const std::string calibration_filename =
136 FLAGS_calibration_folder +
137 absl::StrFormat("/calibration_pi-%d-%d_%s.json", team_number.value(),
138 pi_number_.value(), time_ss.str());
139
140 LOG(INFO) << calibration_filename << " -> "
141 << aos::FlatbufferToJson(camera_calibration,
142 {.multi_line = true});
143
144 aos::util::WriteStringToFileOrDie(
145 calibration_filename,
146 aos::FlatbufferToJson(camera_calibration, {.multi_line = true}));
147 } else {
148 LOG(INFO) << "Skipping calibration due to not enough images.";
149 }
150 }
151
152 private:
153 aos::ShmEventLoop *event_loop_;
154 std::string pi_;
155 const std::optional<uint16_t> pi_number_;
156
157 std::vector<std::vector<int>> all_charuco_ids_;
158 std::vector<std::vector<cv::Point2f>> all_charuco_corners_;
159
160 CharucoExtractor charuco_extractor_;
161};
162
163namespace {
164
165void Main() {
166 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
167 aos::configuration::ReadConfig(FLAGS_config);
168
169 aos::ShmEventLoop event_loop(&config.message());
170
171 Calibration extractor(&event_loop, FLAGS_pi);
Austin Schuhc1f118e2020-04-11 15:50:08 -0700172
173 event_loop.Run();
174
Austin Schuh25837f22021-06-27 15:49:14 -0700175 extractor.MaybeCalibrate();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700176}
177
178} // namespace
179} // namespace vision
180} // namespace frc971
181
Austin Schuhc1f118e2020-04-11 15:50:08 -0700182int main(int argc, char **argv) {
183 aos::InitGoogle(&argc, &argv);
Austin Schuh25837f22021-06-27 15:49:14 -0700184 frc971::vision::Main();
Austin Schuhc1f118e2020-04-11 15:50:08 -0700185}