blob: 5c297975790d382f2b5b032cbbbc2b9a69b56b3b [file] [log] [blame]
Jim Ostrowski2f2685f2023-03-25 11:57:54 -07001#include <numeric>
2
Austin Schuh99f7c6a2024-06-25 22:07:44 -07003#include "absl/flags/flag.h"
4
Jim Ostrowski2f2685f2023-03-25 11:57:54 -07005#include "aos/configuration.h"
6#include "aos/events/logging/log_reader.h"
7#include "aos/events/simulated_event_loop.h"
8#include "aos/init.h"
9#include "aos/util/mcap_logger.h"
10#include "frc971/control_loops/pose.h"
11#include "frc971/control_loops/quaternion_utils.h"
12#include "frc971/vision/calibration_generated.h"
13#include "frc971/vision/charuco_lib.h"
Jim Ostrowski68c321d2023-11-14 21:36:28 -080014#include "frc971/vision/extrinsics_calibration.h"
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070015#include "frc971/vision/target_mapper.h"
Jim Ostrowski6d242d52024-04-03 20:39:03 -070016#include "frc971/vision/vision_util_lib.h"
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070017#include "frc971/vision/visualize_robot.h"
18// clang-format off
19// OpenCV eigen files must be included after Eigen includes
20#include "opencv2/aruco.hpp"
21#include "opencv2/calib3d.hpp"
22#include "opencv2/core/eigen.hpp"
23#include "opencv2/features2d.hpp"
24#include "opencv2/highgui.hpp"
25#include "opencv2/highgui/highgui.hpp"
26#include "opencv2/imgproc.hpp"
27// clang-format on
28#include "y2023/constants/simulated_constants_sender.h"
29#include "y2023/vision/aprilrobotics.h"
30#include "y2023/vision/vision_util.h"
31
Austin Schuh99f7c6a2024-06-25 22:07:44 -070032ABSL_FLAG(bool, alt_view, false,
33 "If true, show visualization from field level, rather than above");
34ABSL_FLAG(std::string, config, "",
35 "If set, override the log's config file with this one.");
36ABSL_FLAG(std::string, constants_path, "y2023/constants/constants.json",
37 "Path to the constant file");
38ABSL_FLAG(double, max_pose_error, 5e-5,
39 "Throw out target poses with a higher pose error than this");
40ABSL_FLAG(double, max_pose_error_ratio, 0.4,
41 "Throw out target poses with a higher pose error ratio than this");
42ABSL_FLAG(std::string, output_folder, "/tmp",
43 "Directory in which to store the updated calibration files");
44ABSL_FLAG(std::string, target_type, "charuco_diamond",
45 "Type of target being used [aruco, charuco, charuco_diamond]");
46ABSL_FLAG(int32_t, team_number, 0,
47 "Required: Use the calibration for a node with this team number");
48ABSL_FLAG(bool, use_full_logs, false,
49 "If true, extract data from logs with images");
50ABSL_FLAG(
51 uint64_t, wait_key, 1,
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070052 "Time in ms to wait between images (0 to wait indefinitely until click)");
53
Austin Schuh99f7c6a2024-06-25 22:07:44 -070054ABSL_DECLARE_FLAG(int32_t, min_target_id);
55ABSL_DECLARE_FLAG(int32_t, max_target_id);
Jim Ostrowski68c321d2023-11-14 21:36:28 -080056
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070057// Calibrate extrinsic relationship between cameras using two targets
58// seen jointly between cameras. Uses two types of information: 1)
59// when a single camera sees two targets, we estimate the pose between
60// targets, and 2) when two separate cameras each see a target, we can
61// use the pose between targets to estimate the pose between cameras.
62
63// We then create the extrinsics for the robot by starting with the
64// given extrinsic for camera 1 (between imu/robot and camera frames)
65// and then map each subsequent camera based on the data collected and
66// the extrinsic poses computed here.
67
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070068// TODO<Jim>: Not currently using estimate from pi1->pi4-- should do full
69// estimation, and probably also include camera->imu extrinsics from all
70// cameras, not just pi1
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070071
Stephan Pleinesf63bde82024-01-13 15:59:33 -080072namespace y2023::vision {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070073using frc971::vision::DataAdapter;
74using frc971::vision::ImageCallback;
75using frc971::vision::PoseUtils;
76using frc971::vision::TargetMap;
77using frc971::vision::TargetMapper;
Jim Ostrowski2be78e32023-03-25 11:57:54 -070078using frc971::vision::VisualizeRobot;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070079namespace calibration = frc971::vision::calibration;
80
81static constexpr double kImagePeriodMs =
82 1.0 / 30.0 * 1000.0; // Image capture period in ms
83
84// Change reference frame from camera to robot
85Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
86 Eigen::Affine3d extrinsics) {
87 const Eigen::Affine3d H_robot_camera = extrinsics;
88 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
89 return H_robot_target;
90}
91
92struct TimestampedPiDetection {
93 aos::distributed_clock::time_point time;
94 // Pose of target relative to robot
95 Eigen::Affine3d H_camera_target;
96 // name of pi
97 std::string pi_name;
98 int board_id;
99};
100
101TimestampedPiDetection last_observation;
102std::vector<std::pair<TimestampedPiDetection, TimestampedPiDetection>>
103 detection_list;
104std::vector<TimestampedPiDetection> two_board_extrinsics_list;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700105VisualizeRobot vis_robot_;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700106
107// TODO<jim>: Implement variance calcs
108Eigen::Affine3d ComputeAveragePose(
109 std::vector<Eigen::Vector3d> &translation_list,
110 std::vector<Eigen::Vector4d> &rotation_list,
111 Eigen::Vector3d *translation_variance = nullptr,
112 Eigen::Vector3d *rotation_variance = nullptr) {
113 Eigen::Vector3d avg_translation =
114 std::accumulate(translation_list.begin(), translation_list.end(),
115 Eigen::Vector3d{0, 0, 0}) /
116 translation_list.size();
117
118 // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this
119 // requires a fixed number of quaternions to be averaged
120 Eigen::Vector4d avg_rotation =
121 std::accumulate(rotation_list.begin(), rotation_list.end(),
122 Eigen::Vector4d{0, 0, 0, 0}) /
123 rotation_list.size();
124 // Normalize, so it's a valid quaternion
125 avg_rotation = avg_rotation / avg_rotation.norm();
126 Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1],
127 avg_rotation[2], avg_rotation[3]};
128 Eigen::Translation3d translation(avg_translation);
129 Eigen::Affine3d return_pose = translation * avg_rotation_q;
130 if (translation_variance != nullptr) {
131 *translation_variance = Eigen::Vector3d();
132 }
133 if (rotation_variance != nullptr) {
134 LOG(INFO) << *rotation_variance;
135 }
136
137 return return_pose;
138}
139
140Eigen::Affine3d ComputeAveragePose(
141 std::vector<Eigen::Affine3d> &pose_list,
142 Eigen::Vector3d *translation_variance = nullptr,
143 Eigen::Vector3d *rotation_variance = nullptr) {
144 std::vector<Eigen::Vector3d> translation_list;
145 std::vector<Eigen::Vector4d> rotation_list;
146
147 for (Eigen::Affine3d pose : pose_list) {
148 translation_list.push_back(pose.translation());
149 Eigen::Quaterniond quat(pose.rotation().matrix());
150 rotation_list.push_back(
151 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
152 }
153
154 return ComputeAveragePose(translation_list, rotation_list,
155 translation_variance, rotation_variance);
156}
157
158Eigen::Affine3d ComputeAveragePose(
159 std::vector<TimestampedPiDetection> &pose_list,
160 Eigen::Vector3d *translation_variance = nullptr,
161 Eigen::Vector3d *rotation_variance = nullptr) {
162 std::vector<Eigen::Vector3d> translation_list;
163 std::vector<Eigen::Vector4d> rotation_list;
164
165 for (TimestampedPiDetection pose : pose_list) {
166 translation_list.push_back(pose.H_camera_target.translation());
167 Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix());
168 rotation_list.push_back(
169 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
170 }
171 return ComputeAveragePose(translation_list, rotation_list,
172 translation_variance, rotation_variance);
173}
174
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800175void HandlePoses(cv::Mat rgb_image,
176 std::vector<TargetMapper::TargetPose> target_poses,
177 aos::distributed_clock::time_point distributed_eof,
178 std::string node_name) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700179 // This is used to transform points for visualization
180 // Assumes targets are aligned with x->right, y->up, z->out of board
181 Eigen::Affine3d H_world_board;
182 H_world_board = Eigen::Translation3d::Identity() *
183 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700184 if (absl::GetFlag(FLAGS_alt_view)) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700185 // Don't rotate -- this is like viewing from the side
186 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
187 }
188
189 bool draw_vis = false;
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800190 CHECK_LE(target_poses.size(), 2u)
191 << "Can't handle more than two tags in field of view";
192 if (target_poses.size() == 2) {
193 draw_vis = true;
194 VLOG(1) << "Saw two boards in same view from " << node_name;
195 int from_index = 0;
196 int to_index = 1;
197 // Handle when we see two boards at once
198 // We'll store them referenced to the lower id board
199 if (target_poses[from_index].id > target_poses[to_index].id) {
200 std::swap<int>(from_index, to_index);
201 }
202
203 // Create "from" (A) and "to" (B) transforms
204 Eigen::Affine3d H_camera_boardA =
205 PoseUtils::Pose3dToAffine3d(target_poses[from_index].pose);
206 Eigen::Affine3d H_camera_boardB =
207 PoseUtils::Pose3dToAffine3d(target_poses[to_index].pose);
208
209 Eigen::Affine3d H_boardA_boardB =
210 H_camera_boardA.inverse() * H_camera_boardB;
211
212 TimestampedPiDetection boardA_boardB{
213 .time = distributed_eof,
214 .H_camera_target = H_boardA_boardB,
215 .pi_name = node_name,
216 .board_id = target_poses[from_index].id};
217
218 VLOG(1) << "Map from board " << from_index << " to " << to_index << " is\n"
219 << H_boardA_boardB.matrix();
220 // Store this observation of the transform between two boards
221 two_board_extrinsics_list.push_back(boardA_boardB);
222
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700223 if (absl::GetFlag(FLAGS_visualize)) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800224 vis_robot_.DrawFrameAxes(
225 H_world_board,
226 std::string("board ") + std::to_string(target_poses[from_index].id),
227 cv::Scalar(0, 255, 0));
228 vis_robot_.DrawFrameAxes(
229 H_world_board * boardA_boardB.H_camera_target,
230 std::string("board ") + std::to_string(target_poses[to_index].id),
231 cv::Scalar(255, 0, 0));
232 VLOG(2) << "Detection map from camera " << node_name << " to board "
233 << target_poses[from_index].id << " is\n"
234 << H_camera_boardA.matrix() << "\n and inverse is\n"
235 << H_camera_boardA.inverse().matrix()
236 << "\n and with world to board rotation is\n"
237 << H_world_board * H_camera_boardA.inverse().matrix();
238 vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(),
239 node_name, cv::Scalar(0, 0, 255));
240 }
241 } else if (target_poses.size() == 1) {
242 VLOG(1) << "Saw single board in camera " << node_name;
243 Eigen::Affine3d H_camera2_board2 =
244 PoseUtils::Pose3dToAffine3d(target_poses[0].pose);
245 TimestampedPiDetection new_observation{.time = distributed_eof,
246 .H_camera_target = H_camera2_board2,
247 .pi_name = node_name,
248 .board_id = target_poses[0].id};
249
250 // Only take two observations if they're within half an image cycle of each
251 // other (i.e., as close in time as possible)
252 if (std::abs((distributed_eof - last_observation.time).count()) <
253 kImagePeriodMs / 2.0 * 1000000.0) {
254 // Sort by pi numbering, since this is how we will handle them
255 std::pair<TimestampedPiDetection, TimestampedPiDetection> new_pair;
256 if (last_observation.pi_name < new_observation.pi_name) {
257 new_pair = std::pair(last_observation, new_observation);
258 } else if (last_observation.pi_name > new_observation.pi_name) {
259 new_pair = std::pair(new_observation, last_observation);
260 } else {
261 LOG(WARNING) << "Got 2 observations in a row from same pi. Probably "
262 "not too much of an issue???";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700263 }
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800264 detection_list.push_back(new_pair);
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700265
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800266 // This bit is just for visualization and checking purposes-- use the
267 // last two-board observation to figure out the current estimate
268 // between the two cameras
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700269 if (absl::GetFlag(FLAGS_visualize) &&
270 two_board_extrinsics_list.size() > 0) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800271 draw_vis = true;
272 TimestampedPiDetection &last_two_board_ext =
273 two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
274 Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
275 int boardA_boardB_id = last_two_board_ext.board_id;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700276
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800277 TimestampedPiDetection camera1_boardA = new_pair.first;
278 TimestampedPiDetection camera2_boardB = new_pair.second;
279 // If camera1_boardA doesn't point to the first target, then swap
280 // these two
281 if (camera1_boardA.board_id != boardA_boardB_id) {
282 camera1_boardA = new_pair.second;
283 camera2_boardB = new_pair.first;
284 }
285 VLOG(1) << "Camera " << camera1_boardA.pi_name << " seeing board "
286 << camera1_boardA.board_id << " and camera "
287 << camera2_boardB.pi_name << " seeing board "
288 << camera2_boardB.board_id;
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700289
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800290 vis_robot_.DrawRobotOutline(
291 H_world_board * camera1_boardA.H_camera_target.inverse(),
292 camera1_boardA.pi_name, cv::Scalar(0, 0, 255));
293 vis_robot_.DrawRobotOutline(
294 H_world_board * H_boardA_boardB *
295 camera2_boardB.H_camera_target.inverse(),
296 camera2_boardB.pi_name, cv::Scalar(128, 128, 0));
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700297 vis_robot_.DrawFrameAxes(
298 H_world_board,
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800299 std::string("Board ") + std::to_string(last_two_board_ext.board_id),
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700300 cv::Scalar(0, 255, 0));
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800301 vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
302 cv::Scalar(255, 0, 0));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700303 }
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800304 VLOG(1) << "Storing observation between " << new_pair.first.pi_name
305 << ", target " << new_pair.first.board_id << " and "
306 << new_pair.second.pi_name << ", target "
307 << new_pair.second.board_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700308 } else {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800309 VLOG(2) << "Storing observation for " << node_name << " at time "
310 << distributed_eof;
311 last_observation = new_observation;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700312 }
313 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700314
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700315 if (absl::GetFlag(FLAGS_visualize)) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800316 if (!rgb_image.empty()) {
317 std::string image_name = node_name + " Image";
318 cv::Mat rgb_small;
319 cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
320 cv::imshow(image_name, rgb_small);
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700321 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800322 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700323
324 if (draw_vis) {
325 cv::imshow("View", vis_robot_.image_);
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700326 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700327 vis_robot_.ClearImage();
328 }
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700329 }
330}
331
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800332void HandleTargetMap(const TargetMap &map,
333 aos::distributed_clock::time_point distributed_eof,
334 std::string node_name) {
335 VLOG(1) << "Got april tag map call from node " << node_name;
336 // Create empty RGB image in this case
337 cv::Mat rgb_image;
338 std::vector<TargetMapper::TargetPose> target_poses;
339
340 for (const auto *target_pose_fbs : *map.target_poses()) {
341 // Skip detections with invalid ids
342 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700343 absl::GetFlag(FLAGS_min_target_id) ||
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800344 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700345 absl::GetFlag(FLAGS_max_target_id)) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800346 LOG(INFO) << "Skipping tag with invalid id of " << target_pose_fbs->id();
347 continue;
348 }
349
350 // Skip detections with high pose errors
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700351 if (target_pose_fbs->pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800352 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
353 << " due to pose error of " << target_pose_fbs->pose_error();
354 continue;
355 }
356 // Skip detections with high pose error ratios
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700357 if (target_pose_fbs->pose_error_ratio() >
358 absl::GetFlag(FLAGS_max_pose_error_ratio)) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800359 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
360 << " due to pose error ratio of "
361 << target_pose_fbs->pose_error_ratio();
362 continue;
363 }
364
365 const TargetMapper::TargetPose target_pose =
Jim Ostrowski6d242d52024-04-03 20:39:03 -0700366 TargetMapper::TargetPoseFromFbs(*target_pose_fbs);
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800367
368 target_poses.emplace_back(target_pose);
369
370 Eigen::Affine3d H_camera_target =
371 PoseUtils::Pose3dToAffine3d(target_pose.pose);
372 VLOG(2) << node_name << " saw target " << target_pose.id
373 << " from TargetMap at timestamp " << distributed_eof
374 << " with pose = " << H_camera_target.matrix();
375 }
376 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
377}
378
379void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
380 const aos::monotonic_clock::time_point eof,
381 aos::distributed_clock::time_point distributed_eof,
382 frc971::vision::CharucoExtractor &charuco_extractor,
383 std::string node_name) {
384 std::vector<cv::Vec4i> charuco_ids;
385 std::vector<std::vector<cv::Point2f>> charuco_corners;
386 bool valid = false;
387 std::vector<Eigen::Vector3d> rvecs_eigen;
388 std::vector<Eigen::Vector3d> tvecs_eigen;
389 // Why eof vs. distributed_eof?
390 charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
391 charuco_ids, charuco_corners, valid,
392 rvecs_eigen, tvecs_eigen);
393 if (rvecs_eigen.size() > 0 && !valid) {
394 LOG(WARNING) << "Charuco extractor returned not valid";
395 return;
396 }
397
398 std::vector<TargetMapper::TargetPose> target_poses;
399 for (size_t i = 0; i < tvecs_eigen.size(); i++) {
400 Eigen::Quaterniond rotation(
401 frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i]));
402 ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation);
403 TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose};
404 target_poses.emplace_back(target_pose);
405
406 Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose);
407 VLOG(2) << node_name << " saw target " << target_pose.id
408 << " from image at timestamp " << distributed_eof
409 << " with pose = " << H_camera_target.matrix();
410 }
411 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
412}
413
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700414void ExtrinsicsMain(int argc, char *argv[]) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700415 vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
416 vis_robot_.ClearImage();
417 const double kFocalLength = 1000.0;
418 const int kImageWidth = 1000;
419 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700420
421 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700422 (absl::GetFlag(FLAGS_config).empty()
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700423 ? std::nullopt
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700424 : std::make_optional(
425 aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config))));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700426
427 // open logfiles
428 aos::logger::LogReader reader(
429 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
430 config.has_value() ? &config->message() : nullptr);
431
432 constexpr size_t kNumPis = 4;
433 for (size_t i = 1; i <= kNumPis; i++) {
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700434 reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
435 "y2023.Constants");
436 }
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800437
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700438 reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800439 reader.RemapLoggedChannel("/logger/constants", "y2023.Constants");
440 reader.RemapLoggedChannel("/roborio/constants", "y2023.Constants");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700441 reader.Register();
442
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700443 SendSimulationConstants(reader.event_loop_factory(),
444 absl::GetFlag(FLAGS_team_number),
445 absl::GetFlag(FLAGS_constants_path));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700446
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700447 VLOG(1) << "Using target type " << absl::GetFlag(FLAGS_target_type);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700448 std::vector<std::string> node_list;
449 node_list.push_back("pi1");
450 node_list.push_back("pi2");
451 node_list.push_back("pi3");
452 node_list.push_back("pi4");
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800453 std::vector<const calibration::CameraCalibration *> calibration_list;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700454
455 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
456 std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
457 std::vector<frc971::vision::ImageCallback *> image_callbacks;
458 std::vector<Eigen::Affine3d> default_extrinsics;
459
460 for (uint i = 0; i < node_list.size(); i++) {
461 std::string node = node_list[i];
462 const aos::Node *pi =
463 aos::configuration::GetNode(reader.configuration(), node.c_str());
464
465 detection_event_loops.emplace_back(
466 reader.event_loop_factory()->MakeEventLoop(
467 (node + "_detection").c_str(), pi));
468
469 frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher(
470 detection_event_loops.back().get());
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700471
472 const calibration::CameraCalibration *calibration =
473 FindCameraCalibration(constants_fetcher.constants(), node);
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800474 calibration_list.push_back(calibration);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700475
476 frc971::vision::TargetType target_type =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700477 frc971::vision::TargetTypeFromString(absl::GetFlag(FLAGS_target_type));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700478 frc971::vision::CharucoExtractor *charuco_ext =
479 new frc971::vision::CharucoExtractor(calibration, target_type);
480 charuco_extractors.emplace_back(charuco_ext);
481
482 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
483 Eigen::Matrix4d extrinsics_matrix;
484 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
485 const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
486 default_extrinsics.emplace_back(ext_H_robot_pi);
487
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700488 VLOG(1) << "Got extrinsics for " << node << " as\n"
489 << default_extrinsics.back().matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700490
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700491 if (absl::GetFlag(FLAGS_use_full_logs)) {
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800492 LOG(INFO) << "Set up image callback for node " << node_list[i];
493 frc971::vision::ImageCallback *image_callback =
494 new frc971::vision::ImageCallback(
495 detection_event_loops[i].get(), "/" + node_list[i] + "/camera",
496 [&reader, &charuco_extractors, &detection_event_loops, &node_list,
497 i](cv::Mat rgb_image,
498 const aos::monotonic_clock::time_point eof) {
499 aos::distributed_clock::time_point pi_distributed_time =
500 reader.event_loop_factory()
501 ->GetNodeEventLoopFactory(
502 detection_event_loops[i].get()->node())
503 ->ToDistributedClock(eof);
504 HandleImage(detection_event_loops[i].get(), rgb_image, eof,
505 pi_distributed_time, *charuco_extractors[i],
506 node_list[i]);
507 });
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700508
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800509 image_callbacks.emplace_back(image_callback);
510 } else {
511 detection_event_loops[i]->MakeWatcher(
512 "/camera", [&reader, &detection_event_loops, &node_list,
513 i](const TargetMap &map) {
514 aos::distributed_clock::time_point pi_distributed_time =
515 reader.event_loop_factory()
516 ->GetNodeEventLoopFactory(detection_event_loops[i]->node())
517 ->ToDistributedClock(aos::monotonic_clock::time_point(
518 aos::monotonic_clock::duration(
519 map.monotonic_timestamp_ns())));
520
521 HandleTargetMap(map, pi_distributed_time, node_list[i]);
522 });
523 LOG(INFO) << "Created watcher for using the detection event loop for "
524 << node_list[i] << " with i = " << i << " and size "
525 << detection_event_loops.size();
526 }
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700527 }
528
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700529 reader.event_loop_factory()->Run();
530
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700531 // Do quick check to see what averaged two-board pose for each pi is
532 // individually
533 CHECK_GT(two_board_extrinsics_list.size(), 0u)
534 << "Must have at least one view of both boards";
535 int base_target_id = two_board_extrinsics_list[0].board_id;
536 VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700537 for (auto node : node_list) {
538 std::vector<TimestampedPiDetection> pose_list;
539 for (auto ext : two_board_extrinsics_list) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700540 CHECK_EQ(base_target_id, ext.board_id)
541 << " All boards should have same reference id";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700542 if (ext.pi_name == node) {
543 pose_list.push_back(ext);
544 }
545 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700546 Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700547 VLOG(1) << "Estimate from " << node << " with " << pose_list.size()
548 << " observations is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700549 << avg_pose_from_pi.matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700550 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700551 Eigen::Affine3d H_boardA_boardB_avg =
552 ComputeAveragePose(two_board_extrinsics_list);
553 // TODO: Should probably do some outlier rejection
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700554 LOG(INFO) << "Estimate of two board pose using all nodes with "
555 << two_board_extrinsics_list.size() << " observations is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700556 << H_boardA_boardB_avg.matrix() << "\n";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700557
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700558 // Next, compute the relative camera poses
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700559 LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700560 std::vector<Eigen::Affine3d> H_camera1_camera2_list;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700561 std::vector<Eigen::Affine3d> updated_extrinsics;
562 // Use the first node's extrinsics as our base, and fix from there
563 updated_extrinsics.push_back(default_extrinsics[0]);
564 LOG(INFO) << "Default extrinsic for node " << node_list[0] << " is "
565 << default_extrinsics[0].matrix();
566 for (uint i = 0; i < node_list.size() - 1; i++) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700567 H_camera1_camera2_list.clear();
568 // Go through the list, and find successive pairs of cameras
569 for (auto [pose1, pose2] : detection_list) {
570 if ((pose1.pi_name == node_list[i]) &&
571 (pose2.pi_name == node_list[i + 1])) {
572 Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
573 // If pose1 isn't referenced to base_target_id, correct that
574 if (pose1.board_id != base_target_id) {
575 // pose1.H_camera_target references boardB, so map back to boardA
576 H_camera1_boardA =
577 pose1.H_camera_target * H_boardA_boardB_avg.inverse();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700578 }
579
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700580 // Now, get the camera2->boardA map (notice it's boardA, same as
581 // camera1, so we can compute the difference based both on boardA)
582 Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target;
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800583 // If pose2 isn't referenced to boardA (base_target_id), correct
584 // that
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700585 if (pose2.board_id != base_target_id) {
586 // pose2.H_camera_target references boardB, so map back to boardA
587 H_camera2_boardA =
Jim Ostrowski1f7cdc62023-12-02 14:09:23 -0800588 pose2.H_camera_target * H_boardA_boardB_avg.inverse();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700589 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700590
591 // Compute camera1->camera2 map
592 Eigen::Affine3d H_camera1_camera2 =
593 H_camera1_boardA * H_camera2_boardA.inverse();
594 H_camera1_camera2_list.push_back(H_camera1_camera2);
595 VLOG(1) << "Map from camera " << pose1.pi_name << " and tag "
596 << pose1.board_id << " with observation: \n"
597 << pose1.H_camera_target.matrix() << "\n to camera "
598 << pose2.pi_name << " and tag " << pose2.board_id
599 << " with observation: \n"
600 << pose2.H_camera_target.matrix() << "\ngot map as\n"
601 << H_camera1_camera2.matrix();
602
603 Eigen::Affine3d H_world_board;
604 H_world_board = Eigen::Translation3d::Identity() *
605 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700606 if (absl::GetFlag(FLAGS_alt_view)) {
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700607 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
608 }
609
610 VLOG(2) << "Camera1 " << pose1.pi_name << " in world frame is \n"
611 << (H_world_board * H_camera1_boardA.inverse()).matrix();
612 VLOG(2) << "Camera2 " << pose2.pi_name << " in world frame is \n"
613 << (H_world_board * H_camera2_boardA.inverse()).matrix();
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700614 }
615 }
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700616 // TODO<Jim>: If we don't get any matches, we could just use default
617 // extrinsics
618 CHECK(H_camera1_camera2_list.size() > 0)
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700619 << "Failed with zero poses for node " << node_list[i];
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700620 if (H_camera1_camera2_list.size() > 0) {
621 Eigen::Affine3d H_camera1_camera2_avg =
622 ComputeAveragePose(H_camera1_camera2_list);
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700623 LOG(INFO) << "From " << node_list[i] << " to " << node_list[i + 1]
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700624 << " found " << H_camera1_camera2_list.size()
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700625 << " observations, and the average pose is:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700626 << H_camera1_camera2_avg.matrix();
627 Eigen::Affine3d H_camera1_camera2_default =
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700628 default_extrinsics[i].inverse() * default_extrinsics[i + 1];
629 LOG(INFO) << "Compare this to that from default values:\n"
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700630 << H_camera1_camera2_default.matrix();
631 Eigen::Affine3d H_camera1_camera2_diff =
632 H_camera1_camera2_avg * H_camera1_camera2_default.inverse();
633 LOG(INFO)
634 << "Difference between averaged and default delta poses "
635 "has |T| = "
636 << H_camera1_camera2_diff.translation().norm() << "m and |R| = "
637 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle()
638 << " radians ("
639 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() *
640 180.0 / M_PI
641 << " degrees)";
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700642 // Next extrinsic is just previous one * avg_delta_pose
643 Eigen::Affine3d next_extrinsic =
Jim Ostrowski2be78e32023-03-25 11:57:54 -0700644 updated_extrinsics.back() * H_camera1_camera2_avg;
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700645 updated_extrinsics.push_back(next_extrinsic);
646 LOG(INFO) << "Default Extrinsic for " << node_list[i + 1] << " is \n"
647 << default_extrinsics[i + 1].matrix();
648 LOG(INFO) << "--> Updated Extrinsic for " << node_list[i + 1] << " is \n"
649 << next_extrinsic.matrix();
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800650
651 // Wirte out this extrinsic to a file
652 flatbuffers::FlatBufferBuilder fbb;
653 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
654 fbb.CreateVector(
655 frc971::vision::MatrixToVector(next_extrinsic.matrix()));
656 calibration::TransformationMatrix::Builder matrix_builder(fbb);
657 matrix_builder.add_data(data_offset);
658 flatbuffers::Offset<calibration::TransformationMatrix>
659 extrinsic_calibration_offset = matrix_builder.Finish();
660
661 calibration::CameraCalibration::Builder calibration_builder(fbb);
662 calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset);
663 const aos::realtime_clock::time_point realtime_now =
664 aos::realtime_clock::now();
665 calibration_builder.add_calibration_timestamp(
666 realtime_now.time_since_epoch().count());
667 fbb.Finish(calibration_builder.Finish());
668 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
669 solved_extrinsics = fbb.Release();
670
671 aos::FlatbufferDetachedBuffer<
672 frc971::vision::calibration::CameraCalibration>
673 cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]);
674 cal_copy.mutable_message()->clear_fixed_extrinsics();
675 cal_copy.mutable_message()->clear_calibration_timestamp();
676 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
677 merged_calibration = aos::MergeFlatBuffers(
678 &cal_copy.message(), &solved_extrinsics.message());
679
680 std::stringstream time_ss;
681 time_ss << realtime_now;
682
683 // Assumes node_list name is of form "pi#" to create camera id
684 const std::string calibration_filename =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700685 absl::GetFlag(FLAGS_output_folder) +
686 absl::StrFormat(
687 "/calibration_pi-%d-%s_cam-%s_%s.json",
688 absl::GetFlag(FLAGS_team_number), node_list[i + 1].substr(2, 3),
689 calibration_list[i + 1]->camera_id()->data(), time_ss.str());
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800690
691 LOG(INFO) << calibration_filename << " -> "
692 << aos::FlatbufferToJson(merged_calibration,
693 {.multi_line = true});
694
695 aos::util::WriteStringToFileOrDie(
696 calibration_filename,
697 aos::FlatbufferToJson(merged_calibration, {.multi_line = true}));
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700698 }
699 }
700
701 // Cleanup
702 for (uint i = 0; i < image_callbacks.size(); i++) {
703 delete charuco_extractors[i];
704 delete image_callbacks[i];
705 }
706}
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800707} // namespace y2023::vision
Jim Ostrowski2f2685f2023-03-25 11:57:54 -0700708
709int main(int argc, char **argv) {
710 aos::InitGoogle(&argc, &argv);
711 y2023::vision::ExtrinsicsMain(argc, argv);
712}