blob: 1398af511c21b027cfe289ed4ca7834a6404bd10 [file] [log] [blame]
Austin Schuhdcb6b362022-02-25 18:06:21 -08001#include "frc971/vision/charuco_lib.h"
Austin Schuh25837f22021-06-27 15:49:14 -07002
3#include <chrono>
4#include <functional>
Austin Schuh25837f22021-06-27 15:49:14 -07005#include <opencv2/core/eigen.hpp>
6#include <opencv2/highgui/highgui.hpp>
7#include <opencv2/imgproc.hpp>
Austin Schuhdcb6b362022-02-25 18:06:21 -08008#include <string_view>
9
Austin Schuh25837f22021-06-27 15:49:14 -070010#include "aos/events/event_loop.h"
11#include "aos/flatbuffers.h"
12#include "aos/network/team_number.h"
13#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080014#include "frc971/vision/vision_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070015#include "glog/logging.h"
16#include "y2020/vision/sift/sift_generated.h"
17#include "y2020/vision/sift/sift_training_generated.h"
18#include "y2020/vision/tools/python_code/sift_training_data.h"
Austin Schuh25837f22021-06-27 15:49:14 -070019
20DEFINE_uint32(min_targets, 10,
21 "The mininum number of targets required to match.");
22DEFINE_bool(large_board, true, "If true, use the large calibration board.");
23DEFINE_bool(coarse_pattern, true, "If true, use coarse arucos; else, use fine");
24DEFINE_string(board_template_path, "",
25 "If specified, write an image to the specified path for the "
26 "charuco board pattern.");
27
28namespace frc971 {
29namespace vision {
30namespace chrono = std::chrono;
Austin Schuhea7b0142021-10-08 22:04:53 -070031using aos::monotonic_clock;
Austin Schuh25837f22021-06-27 15:49:14 -070032
33CameraCalibration::CameraCalibration(
34 const absl::Span<const uint8_t> training_data_bfbs, std::string_view pi) {
35 const aos::FlatbufferSpan<sift::TrainingData> training_data(
36 training_data_bfbs);
37 CHECK(training_data.Verify());
38 camera_calibration_ = FindCameraCalibration(&training_data.message(), pi);
39}
40
41cv::Mat CameraCalibration::CameraIntrinsics() const {
42 const cv::Mat result(3, 3, CV_32F,
43 const_cast<void *>(static_cast<const void *>(
44 camera_calibration_->intrinsics()->data())));
45 CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
46 return result;
47}
48
49Eigen::Matrix3d CameraCalibration::CameraIntrinsicsEigen() const {
50 cv::Mat camera_intrinsics = CameraIntrinsics();
51 Eigen::Matrix3d result;
52 cv::cv2eigen(camera_intrinsics, result);
53 return result;
54}
55
56cv::Mat CameraCalibration::CameraDistCoeffs() const {
57 const cv::Mat result(5, 1, CV_32F,
58 const_cast<void *>(static_cast<const void *>(
59 camera_calibration_->dist_coeffs()->data())));
60 CHECK_EQ(result.total(), camera_calibration_->dist_coeffs()->size());
61 return result;
62}
63
64const sift::CameraCalibration *CameraCalibration::FindCameraCalibration(
65 const sift::TrainingData *const training_data, std::string_view pi) const {
66 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(pi);
67 std::optional<uint16_t> team_number =
68 aos::network::team_number_internal::ParsePiTeamNumber(pi);
69 CHECK(pi_number);
70 CHECK(team_number);
71 const std::string node_name = absl::StrFormat("pi%d", pi_number.value());
72 LOG(INFO) << "Looking for node name " << node_name << " team number "
73 << team_number.value();
74 for (const sift::CameraCalibration *candidate :
75 *training_data->camera_calibrations()) {
76 if (candidate->node_name()->string_view() != node_name) {
77 continue;
78 }
79 if (candidate->team_number() != team_number.value()) {
80 continue;
81 }
82 return candidate;
83 }
84 LOG(FATAL) << ": Failed to find camera calibration for " << node_name
85 << " on " << team_number.value();
86}
87
Austin Schuhea7b0142021-10-08 22:04:53 -070088ImageCallback::ImageCallback(
89 aos::EventLoop *event_loop, std::string_view channel,
90 std::function<void(cv::Mat, monotonic_clock::time_point)> &&fn)
91 : event_loop_(event_loop),
92 server_fetcher_(
93 event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
94 "/aos")),
95 source_node_(aos::configuration::GetNode(
96 event_loop_->configuration(),
97 event_loop_->GetChannel<CameraImage>(channel)
98 ->source_node()
99 ->string_view())),
100 handle_image_(std::move(fn)) {
Austin Schuh25837f22021-06-27 15:49:14 -0700101 event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
Austin Schuhea7b0142021-10-08 22:04:53 -0700102 const monotonic_clock::time_point eof_source_node =
103 monotonic_clock::time_point(
104 chrono::nanoseconds(image.monotonic_timestamp_ns()));
Austin Schuhea7b0142021-10-08 22:04:53 -0700105 chrono::nanoseconds offset{0};
106 if (source_node_ != event_loop_->node()) {
Austin Schuhee8bc1e2021-11-20 16:23:41 -0800107 server_fetcher_.Fetch();
108 if (!server_fetcher_.get()) {
109 return;
110 }
111
Austin Schuhea7b0142021-10-08 22:04:53 -0700112 // If we are viewing this image from another node, convert to our
113 // monotonic clock.
114 const aos::message_bridge::ServerConnection *server_connection = nullptr;
115
116 for (const aos::message_bridge::ServerConnection *connection :
117 *server_fetcher_->connections()) {
118 CHECK(connection->has_node());
119 if (connection->node()->name()->string_view() ==
120 source_node_->name()->string_view()) {
121 server_connection = connection;
122 break;
123 }
124 }
125
126 CHECK(server_connection != nullptr) << ": Failed to find client";
127 if (!server_connection->has_monotonic_offset()) {
128 VLOG(1) << "No offset yet.";
129 return;
130 }
131 offset = chrono::nanoseconds(server_connection->monotonic_offset());
132 }
133
134 const monotonic_clock::time_point eof = eof_source_node - offset;
135
Jim Ostrowski977850f2022-01-22 21:04:22 -0800136 const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
Austin Schuh25837f22021-06-27 15:49:14 -0700137 const double age_double =
138 std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
139 if (age > std::chrono::milliseconds(100)) {
Jim Ostrowskifec0c332022-02-06 23:28:26 -0800140 VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
Austin Schuh25837f22021-06-27 15:49:14 -0700141 return;
142 }
143 // Create color image:
144 cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
145 (void *)image.data()->data());
146 const cv::Size image_size(image.cols(), image.rows());
147 cv::Mat rgb_image(image_size, CV_8UC3);
Brian Silverman4c7235a2021-11-17 19:04:37 -0800148 cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
Austin Schuhea7b0142021-10-08 22:04:53 -0700149 handle_image_(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700150 });
151}
152
153CharucoExtractor::CharucoExtractor(
154 aos::EventLoop *event_loop, std::string_view pi,
Austin Schuhea7b0142021-10-08 22:04:53 -0700155 std::function<void(cv::Mat, monotonic_clock::time_point, std::vector<int>,
Austin Schuh25837f22021-06-27 15:49:14 -0700156 std::vector<cv::Point2f>, bool, Eigen::Vector3d,
157 Eigen::Vector3d)> &&fn)
Austin Schuhea7b0142021-10-08 22:04:53 -0700158 : event_loop_(event_loop),
159 calibration_(SiftTrainingData(), pi),
Austin Schuh25837f22021-06-27 15:49:14 -0700160 dictionary_(cv::aruco::getPredefinedDictionary(
161 FLAGS_large_board ? cv::aruco::DICT_5X5_250
162 : cv::aruco::DICT_6X6_250)),
163 board_(
164 FLAGS_large_board
165 ? (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
166 12, 9, 0.06, 0.04666, dictionary_)
167 : cv::aruco::CharucoBoard::create(
168 25, 18, 0.03, 0.0233, dictionary_))
169 : (FLAGS_coarse_pattern ? cv::aruco::CharucoBoard::create(
170 7, 5, 0.04, 0.025, dictionary_)
171 // TODO(jim): Need to figure out what size
172 // is for small board, fine pattern
173 : cv::aruco::CharucoBoard::create(
174 7, 5, 0.03, 0.0233, dictionary_))),
175 camera_matrix_(calibration_.CameraIntrinsics()),
176 eigen_camera_matrix_(calibration_.CameraIntrinsicsEigen()),
177 dist_coeffs_(calibration_.CameraDistCoeffs()),
178 pi_number_(aos::network::ParsePiNumber(pi)),
179 image_callback_(
180 event_loop,
181 absl::StrCat("/pi", std::to_string(pi_number_.value()), "/camera"),
Austin Schuhea7b0142021-10-08 22:04:53 -0700182 [this](cv::Mat rgb_image, const monotonic_clock::time_point eof) {
183 HandleImage(rgb_image, eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700184 }),
185 handle_charuco_(std::move(fn)) {
186 LOG(INFO) << "Using " << (FLAGS_large_board ? "large" : "small")
187 << " board with " << (FLAGS_coarse_pattern ? "coarse" : "fine")
188 << " pattern";
189 if (!FLAGS_board_template_path.empty()) {
190 cv::Mat board_image;
191 board_->draw(cv::Size(600, 500), board_image, 10, 1);
192 cv::imwrite(FLAGS_board_template_path, board_image);
193 }
194
195 LOG(INFO) << "Camera matrix " << camera_matrix_;
196 LOG(INFO) << "Distortion Coefficients " << dist_coeffs_;
197
198 CHECK(pi_number_) << ": Invalid pi number " << pi
199 << ", failed to parse pi number";
200
201 LOG(INFO) << "Connecting to channel /pi" << pi_number_.value() << "/camera";
202}
203
Austin Schuhea7b0142021-10-08 22:04:53 -0700204void CharucoExtractor::HandleImage(cv::Mat rgb_image,
205 const monotonic_clock::time_point eof) {
206 const double age_double =
207 std::chrono::duration_cast<std::chrono::duration<double>>(
208 event_loop_->monotonic_now() - eof)
209 .count();
Austin Schuh25837f22021-06-27 15:49:14 -0700210 std::vector<int> marker_ids;
211 std::vector<std::vector<cv::Point2f>> marker_corners;
212
213 cv::aruco::detectMarkers(rgb_image, board_->dictionary, marker_corners,
214 marker_ids);
215
216 std::vector<cv::Point2f> charuco_corners;
217 std::vector<int> charuco_ids;
Austin Schuhea7b0142021-10-08 22:04:53 -0700218 bool valid = false;
219 Eigen::Vector3d rvec_eigen = Eigen::Vector3d::Zero();
220 Eigen::Vector3d tvec_eigen = Eigen::Vector3d::Zero();
221
Austin Schuh25837f22021-06-27 15:49:14 -0700222 // If at least one marker detected
223 if (marker_ids.size() >= FLAGS_min_targets) {
224 // Run everything twice, once with the calibration, and once
225 // without. This lets us both calibrate, and also print out the pose
226 // real time with the previous calibration.
227 cv::aruco::interpolateCornersCharuco(marker_corners, marker_ids, rgb_image,
228 board_, charuco_corners, charuco_ids);
229
230 std::vector<cv::Point2f> charuco_corners_with_calibration;
231 std::vector<int> charuco_ids_with_calibration;
232
233 cv::aruco::interpolateCornersCharuco(
234 marker_corners, marker_ids, rgb_image, board_,
235 charuco_corners_with_calibration, charuco_ids_with_calibration,
236 camera_matrix_, dist_coeffs_);
237
238 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
239
240 if (charuco_ids.size() >= FLAGS_min_targets) {
241 cv::aruco::drawDetectedCornersCharuco(rgb_image, charuco_corners,
242 charuco_ids, cv::Scalar(255, 0, 0));
243
244 cv::Vec3d rvec, tvec;
Austin Schuhea7b0142021-10-08 22:04:53 -0700245 valid = cv::aruco::estimatePoseCharucoBoard(
Austin Schuh25837f22021-06-27 15:49:14 -0700246 charuco_corners_with_calibration, charuco_ids_with_calibration,
247 board_, camera_matrix_, dist_coeffs_, rvec, tvec);
248
249 // if charuco pose is valid
250 if (valid) {
Austin Schuh25837f22021-06-27 15:49:14 -0700251 cv::cv2eigen(rvec, rvec_eigen);
252 cv::cv2eigen(tvec, tvec_eigen);
253
254 Eigen::Quaternion<double> rotation(
255 frc971::controls::ToQuaternionFromRotationVector(rvec_eigen));
256 Eigen::Translation3d translation(tvec_eigen);
257
258 const Eigen::Affine3d board_to_camera = translation * rotation;
259
260 Eigen::Matrix<double, 3, 4> camera_projection =
261 Eigen::Matrix<double, 3, 4>::Identity();
262 Eigen::Vector3d result = eigen_camera_matrix_ * camera_projection *
263 board_to_camera * Eigen::Vector3d::Zero();
264
Jim Ostrowski634b2652022-03-04 02:10:53 -0800265 // Found that drawAxis hangs if you try to draw with z values too small
266 // (trying to draw axes at inifinity)
267 // TODO<Jim>: Explore what real thresholds for this should be; likely
268 // Don't need to get rid of negative values
269 if (result.z() < 0.01) {
270 LOG(INFO) << "Skipping, due to z value too small: " << result.z();
271 valid = false;
272 } else {
273 result /= result.z();
274 cv::circle(rgb_image, cv::Point(result.x(), result.y()), 4,
275 cv::Scalar(255, 255, 255), 0, cv::LINE_8);
Austin Schuh25837f22021-06-27 15:49:14 -0700276
Jim Ostrowski634b2652022-03-04 02:10:53 -0800277 cv::aruco::drawAxis(rgb_image, camera_matrix_, dist_coeffs_, rvec,
278 tvec, 0.1);
279 }
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800280 std::stringstream ss;
281 ss << "tvec = " << tvec << "; |t| = " << tvec_eigen.norm();
282 cv::putText(rgb_image, ss.str(), cv::Point(10, 25),
283 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
284 ss.str("");
285 ss << "rvec = " << rvec;
286 cv::putText(rgb_image, ss.str(), cv::Point(10, 50),
287 cv::FONT_HERSHEY_PLAIN, 1.0, cv::Scalar(255, 255, 255));
Austin Schuh25837f22021-06-27 15:49:14 -0700288 } else {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800289 VLOG(2) << "Age: " << age_double << ", invalid pose";
Austin Schuh25837f22021-06-27 15:49:14 -0700290 }
291 } else {
Jim Ostrowski634b2652022-03-04 02:10:53 -0800292 VLOG(2) << "Age: " << age_double << ", not enough charuco IDs, got "
293 << charuco_ids.size() << ", needed " << FLAGS_min_targets;
Austin Schuh25837f22021-06-27 15:49:14 -0700294 }
295 } else {
Jim Ostrowski634b2652022-03-04 02:10:53 -0800296 VLOG(2) << "Age: " << age_double << ", not enough marker IDs, got "
297 << marker_ids.size() << ", needed " << FLAGS_min_targets;
Austin Schuh25837f22021-06-27 15:49:14 -0700298 cv::aruco::drawDetectedMarkers(rgb_image, marker_corners, marker_ids);
Austin Schuh25837f22021-06-27 15:49:14 -0700299 }
Austin Schuhea7b0142021-10-08 22:04:53 -0700300
301 handle_charuco_(rgb_image, eof, charuco_ids, charuco_corners, valid,
302 rvec_eigen, tvec_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700303}
304
305} // namespace vision
306} // namespace frc971