blob: f743e00f9e205e1af0e0f9984f8ef2db84495713 [file] [log] [blame]
Jim Ostrowski9bf206a2024-01-26 23:31:58 -08001#include <numeric>
2
3#include "aos/configuration.h"
4#include "aos/events/logging/log_reader.h"
5#include "aos/events/simulated_event_loop.h"
6#include "aos/init.h"
7#include "aos/util/mcap_logger.h"
8#include "frc971/control_loops/pose.h"
9#include "frc971/control_loops/quaternion_utils.h"
10#include "frc971/vision/calibration_generated.h"
11#include "frc971/vision/charuco_lib.h"
12#include "frc971/vision/extrinsics_calibration.h"
13#include "frc971/vision/target_mapper.h"
14#include "frc971/vision/visualize_robot.h"
15// clang-format off
16// OpenCV eigen files must be included after Eigen includes
17#include "opencv2/aruco.hpp"
18#include "opencv2/calib3d.hpp"
19#include "opencv2/core/eigen.hpp"
20#include "opencv2/features2d.hpp"
21#include "opencv2/highgui.hpp"
22#include "opencv2/highgui/highgui.hpp"
23#include "opencv2/imgproc.hpp"
24// clang-format on
25#include "frc971/constants/constants_sender_lib.h"
26#include "frc971/vision/vision_util_lib.h"
27#include "y2024/constants/simulated_constants_sender.h"
28#include "y2024/vision/vision_util.h"
29
30DEFINE_bool(alt_view, false,
31 "If true, show visualization from field level, rather than above");
32DEFINE_string(config, "",
33 "If set, override the log's config file with this one.");
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080034DEFINE_string(constants_path, "y2024/constants/constants.json",
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080035 "Path to the constant file");
36DEFINE_double(max_pose_error, 5e-5,
37 "Throw out target poses with a higher pose error than this");
38DEFINE_double(
39 max_pose_error_ratio, 0.4,
40 "Throw out target poses with a higher pose error ratio than this");
41DEFINE_string(output_folder, "/tmp",
42 "Directory in which to store the updated calibration files");
43DEFINE_string(target_type, "charuco_diamond",
44 "Type of target being used [aruco, charuco, charuco_diamond]");
45DEFINE_int32(team_number, 0,
46 "Required: Use the calibration for a node with this team number");
47DEFINE_bool(use_full_logs, false,
48 "If true, extract data from logs with images");
49DEFINE_uint64(
50 wait_key, 1,
51 "Time in ms to wait between images (0 to wait indefinitely until click)");
52
53DECLARE_int32(min_target_id);
54DECLARE_int32(max_target_id);
55
56// Calibrate extrinsic relationship between cameras using two targets
57// seen jointly between cameras. Uses two types of information: 1)
58// when a single camera sees two targets, we estimate the pose between
59// targets, and 2) when two separate cameras each see a target, we can
60// use the pose between targets to estimate the pose between cameras.
61
62// We then create the extrinsics for the robot by starting with the
63// given extrinsic for camera 1 (between imu/robot and camera frames)
64// and then map each subsequent camera based on the data collected and
65// the extrinsic poses computed here.
66
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080067// TODO<Jim>: Not currently using estimate from first camera to last camera--
68// should do full estimation, and probably also include camera->imu extrinsics
69// from all cameras, not just first camera
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080070
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080071namespace y2024::vision {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080072using frc971::vision::DataAdapter;
73using frc971::vision::ImageCallback;
74using frc971::vision::PoseUtils;
75using frc971::vision::TargetMap;
76using frc971::vision::TargetMapper;
77using frc971::vision::VisualizeRobot;
78namespace calibration = frc971::vision::calibration;
79
80static constexpr double kImagePeriodMs =
81 1.0 / 30.0 * 1000.0; // Image capture period in ms
82
83// Change reference frame from camera to robot
84Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
85 Eigen::Affine3d extrinsics) {
86 const Eigen::Affine3d H_robot_camera = extrinsics;
87 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
88 return H_robot_target;
89}
90
91struct TimestampedPiDetection {
92 aos::distributed_clock::time_point time;
93 // Pose of target relative to robot
94 Eigen::Affine3d H_camera_target;
95 // name of pi
96 std::string pi_name;
97 int board_id;
98};
99
100TimestampedPiDetection last_observation;
101std::vector<std::pair<TimestampedPiDetection, TimestampedPiDetection>>
102 detection_list;
103std::vector<TimestampedPiDetection> two_board_extrinsics_list;
104VisualizeRobot vis_robot_;
105
106// TODO<jim>: Implement variance calcs
107Eigen::Affine3d ComputeAveragePose(
108 std::vector<Eigen::Vector3d> &translation_list,
109 std::vector<Eigen::Vector4d> &rotation_list,
110 Eigen::Vector3d *translation_variance = nullptr,
111 Eigen::Vector3d *rotation_variance = nullptr) {
112 Eigen::Vector3d avg_translation =
113 std::accumulate(translation_list.begin(), translation_list.end(),
114 Eigen::Vector3d{0, 0, 0}) /
115 translation_list.size();
116
117 // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this
118 // requires a fixed number of quaternions to be averaged
119 Eigen::Vector4d avg_rotation =
120 std::accumulate(rotation_list.begin(), rotation_list.end(),
121 Eigen::Vector4d{0, 0, 0, 0}) /
122 rotation_list.size();
123 // Normalize, so it's a valid quaternion
124 avg_rotation = avg_rotation / avg_rotation.norm();
125 Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1],
126 avg_rotation[2], avg_rotation[3]};
127 Eigen::Translation3d translation(avg_translation);
128 Eigen::Affine3d return_pose = translation * avg_rotation_q;
129 if (translation_variance != nullptr) {
130 *translation_variance = Eigen::Vector3d();
131 }
132 if (rotation_variance != nullptr) {
133 LOG(INFO) << *rotation_variance;
134 }
135
136 return return_pose;
137}
138
139Eigen::Affine3d ComputeAveragePose(
140 std::vector<Eigen::Affine3d> &pose_list,
141 Eigen::Vector3d *translation_variance = nullptr,
142 Eigen::Vector3d *rotation_variance = nullptr) {
143 std::vector<Eigen::Vector3d> translation_list;
144 std::vector<Eigen::Vector4d> rotation_list;
145
146 for (Eigen::Affine3d pose : pose_list) {
147 translation_list.push_back(pose.translation());
148 Eigen::Quaterniond quat(pose.rotation().matrix());
149 rotation_list.push_back(
150 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
151 }
152
153 return ComputeAveragePose(translation_list, rotation_list,
154 translation_variance, rotation_variance);
155}
156
157Eigen::Affine3d ComputeAveragePose(
158 std::vector<TimestampedPiDetection> &pose_list,
159 Eigen::Vector3d *translation_variance = nullptr,
160 Eigen::Vector3d *rotation_variance = nullptr) {
161 std::vector<Eigen::Vector3d> translation_list;
162 std::vector<Eigen::Vector4d> rotation_list;
163
164 for (TimestampedPiDetection pose : pose_list) {
165 translation_list.push_back(pose.H_camera_target.translation());
166 Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix());
167 rotation_list.push_back(
168 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
169 }
170 return ComputeAveragePose(translation_list, rotation_list,
171 translation_variance, rotation_variance);
172}
173
174void HandlePoses(cv::Mat rgb_image,
175 std::vector<TargetMapper::TargetPose> target_poses,
176 aos::distributed_clock::time_point distributed_eof,
177 std::string node_name) {
178 // This is used to transform points for visualization
179 // Assumes targets are aligned with x->right, y->up, z->out of board
180 Eigen::Affine3d H_world_board;
181 H_world_board = Eigen::Translation3d::Identity() *
182 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
183 if (FLAGS_alt_view) {
184 // Don't rotate -- this is like viewing from the side
185 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
186 }
187
188 bool draw_vis = false;
189 CHECK_LE(target_poses.size(), 2u)
190 << "Can't handle more than two tags in field of view";
191 if (target_poses.size() == 2) {
192 draw_vis = true;
193 VLOG(1) << "Saw two boards in same view from " << node_name;
194 int from_index = 0;
195 int to_index = 1;
196 // Handle when we see two boards at once
197 // We'll store them referenced to the lower id board
198 if (target_poses[from_index].id > target_poses[to_index].id) {
199 std::swap<int>(from_index, to_index);
200 }
201
202 // Create "from" (A) and "to" (B) transforms
203 Eigen::Affine3d H_camera_boardA =
204 PoseUtils::Pose3dToAffine3d(target_poses[from_index].pose);
205 Eigen::Affine3d H_camera_boardB =
206 PoseUtils::Pose3dToAffine3d(target_poses[to_index].pose);
207
208 Eigen::Affine3d H_boardA_boardB =
209 H_camera_boardA.inverse() * H_camera_boardB;
210
211 TimestampedPiDetection boardA_boardB{
212 .time = distributed_eof,
213 .H_camera_target = H_boardA_boardB,
214 .pi_name = node_name,
215 .board_id = target_poses[from_index].id};
216
217 VLOG(1) << "Map from board " << from_index << " to " << to_index << " is\n"
218 << H_boardA_boardB.matrix();
219 // Store this observation of the transform between two boards
220 two_board_extrinsics_list.push_back(boardA_boardB);
221
222 if (FLAGS_visualize) {
223 vis_robot_.DrawFrameAxes(
224 H_world_board,
225 std::string("board ") + std::to_string(target_poses[from_index].id),
226 cv::Scalar(0, 255, 0));
227 vis_robot_.DrawFrameAxes(
228 H_world_board * boardA_boardB.H_camera_target,
229 std::string("board ") + std::to_string(target_poses[to_index].id),
230 cv::Scalar(255, 0, 0));
231 VLOG(2) << "Detection map from camera " << node_name << " to board "
232 << target_poses[from_index].id << " is\n"
233 << H_camera_boardA.matrix() << "\n and inverse is\n"
234 << H_camera_boardA.inverse().matrix()
235 << "\n and with world to board rotation is\n"
236 << H_world_board * H_camera_boardA.inverse().matrix();
237 vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(),
238 node_name, cv::Scalar(0, 0, 255));
239 }
240 } else if (target_poses.size() == 1) {
241 VLOG(1) << "Saw single board in camera " << node_name;
242 Eigen::Affine3d H_camera2_board2 =
243 PoseUtils::Pose3dToAffine3d(target_poses[0].pose);
244 TimestampedPiDetection new_observation{.time = distributed_eof,
245 .H_camera_target = H_camera2_board2,
246 .pi_name = node_name,
247 .board_id = target_poses[0].id};
248
249 // Only take two observations if they're within half an image cycle of each
250 // other (i.e., as close in time as possible)
251 if (std::abs((distributed_eof - last_observation.time).count()) <
252 kImagePeriodMs / 2.0 * 1000000.0) {
253 // Sort by pi numbering, since this is how we will handle them
254 std::pair<TimestampedPiDetection, TimestampedPiDetection> new_pair;
255 if (last_observation.pi_name < new_observation.pi_name) {
256 new_pair = std::pair(last_observation, new_observation);
257 } else if (last_observation.pi_name > new_observation.pi_name) {
258 new_pair = std::pair(new_observation, last_observation);
259 } else {
260 LOG(WARNING) << "Got 2 observations in a row from same pi. Probably "
261 "not too much of an issue???";
262 }
263 detection_list.push_back(new_pair);
264
265 // This bit is just for visualization and checking purposes-- use the
266 // last two-board observation to figure out the current estimate
267 // between the two cameras
268 if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) {
269 draw_vis = true;
270 TimestampedPiDetection &last_two_board_ext =
271 two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
272 Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
273 int boardA_boardB_id = last_two_board_ext.board_id;
274
275 TimestampedPiDetection camera1_boardA = new_pair.first;
276 TimestampedPiDetection camera2_boardB = new_pair.second;
277 // If camera1_boardA doesn't point to the first target, then swap
278 // these two
279 if (camera1_boardA.board_id != boardA_boardB_id) {
280 camera1_boardA = new_pair.second;
281 camera2_boardB = new_pair.first;
282 }
283 VLOG(1) << "Camera " << camera1_boardA.pi_name << " seeing board "
284 << camera1_boardA.board_id << " and camera "
285 << camera2_boardB.pi_name << " seeing board "
286 << camera2_boardB.board_id;
287
288 vis_robot_.DrawRobotOutline(
289 H_world_board * camera1_boardA.H_camera_target.inverse(),
290 camera1_boardA.pi_name, cv::Scalar(0, 0, 255));
291 vis_robot_.DrawRobotOutline(
292 H_world_board * H_boardA_boardB *
293 camera2_boardB.H_camera_target.inverse(),
294 camera2_boardB.pi_name, cv::Scalar(128, 128, 0));
295 vis_robot_.DrawFrameAxes(
296 H_world_board,
297 std::string("Board ") + std::to_string(last_two_board_ext.board_id),
298 cv::Scalar(0, 255, 0));
299 vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
300 cv::Scalar(255, 0, 0));
301 }
302 VLOG(1) << "Storing observation between " << new_pair.first.pi_name
303 << ", target " << new_pair.first.board_id << " and "
304 << new_pair.second.pi_name << ", target "
305 << new_pair.second.board_id;
306 } else {
307 VLOG(2) << "Storing observation for " << node_name << " at time "
308 << distributed_eof;
309 last_observation = new_observation;
310 }
311 }
312
313 if (FLAGS_visualize) {
314 if (!rgb_image.empty()) {
315 std::string image_name = node_name + " Image";
316 cv::Mat rgb_small;
317 cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
318 cv::imshow(image_name, rgb_small);
319 cv::waitKey(FLAGS_wait_key);
320 }
321
322 if (draw_vis) {
323 cv::imshow("View", vis_robot_.image_);
324 cv::waitKey(FLAGS_wait_key);
325 vis_robot_.ClearImage();
326 }
327 }
328}
329
330void HandleTargetMap(const TargetMap &map,
331 aos::distributed_clock::time_point distributed_eof,
332 std::string node_name) {
333 VLOG(1) << "Got april tag map call from node " << node_name;
334 // Create empty RGB image in this case
335 cv::Mat rgb_image;
336 std::vector<TargetMapper::TargetPose> target_poses;
337
338 for (const auto *target_pose_fbs : *map.target_poses()) {
339 // Skip detections with invalid ids
340 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
341 FLAGS_min_target_id ||
342 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
343 FLAGS_max_target_id) {
344 LOG(INFO) << "Skipping tag with invalid id of " << target_pose_fbs->id();
345 continue;
346 }
347
348 // Skip detections with high pose errors
349 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
350 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
351 << " due to pose error of " << target_pose_fbs->pose_error();
352 continue;
353 }
354 // Skip detections with high pose error ratios
355 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
356 LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
357 << " due to pose error ratio of "
358 << target_pose_fbs->pose_error_ratio();
359 continue;
360 }
361
362 const TargetMapper::TargetPose target_pose =
363 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
364
365 target_poses.emplace_back(target_pose);
366
367 Eigen::Affine3d H_camera_target =
368 PoseUtils::Pose3dToAffine3d(target_pose.pose);
369 VLOG(2) << node_name << " saw target " << target_pose.id
370 << " from TargetMap at timestamp " << distributed_eof
371 << " with pose = " << H_camera_target.matrix();
372 }
373 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
374}
375
376void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
377 const aos::monotonic_clock::time_point eof,
378 aos::distributed_clock::time_point distributed_eof,
379 frc971::vision::CharucoExtractor &charuco_extractor,
380 std::string node_name) {
381 std::vector<cv::Vec4i> charuco_ids;
382 std::vector<std::vector<cv::Point2f>> charuco_corners;
383 bool valid = false;
384 std::vector<Eigen::Vector3d> rvecs_eigen;
385 std::vector<Eigen::Vector3d> tvecs_eigen;
386 // Why eof vs. distributed_eof?
387 charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
388 charuco_ids, charuco_corners, valid,
389 rvecs_eigen, tvecs_eigen);
390 if (rvecs_eigen.size() > 0 && !valid) {
391 LOG(WARNING) << "Charuco extractor returned not valid";
392 return;
393 }
394
395 std::vector<TargetMapper::TargetPose> target_poses;
396 for (size_t i = 0; i < tvecs_eigen.size(); i++) {
397 Eigen::Quaterniond rotation(
398 frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i]));
399 ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation);
400 TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose};
401 target_poses.emplace_back(target_pose);
402
403 Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose);
404 VLOG(2) << node_name << " saw target " << target_pose.id
405 << " from image at timestamp " << distributed_eof
406 << " with pose = " << H_camera_target.matrix();
407 }
408 HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
409}
410
411void ExtrinsicsMain(int argc, char *argv[]) {
412 vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
413 vis_robot_.ClearImage();
414 const double kFocalLength = 1000.0;
415 const int kImageWidth = 1000;
416 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
417
418 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
419 (FLAGS_config.empty()
420 ? std::nullopt
421 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
422
423 // open logfiles
424 aos::logger::LogReader reader(
425 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
426 config.has_value() ? &config->message() : nullptr);
427
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800428 reader.RemapLoggedChannel("/imu/constants", "y2024.Constants");
429 reader.RemapLoggedChannel("/orin1/constants", "y2024.Constants");
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800430 reader.Register();
431
432 y2024::SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
433 FLAGS_constants_path);
434
435 VLOG(1) << "Using target type " << FLAGS_target_type;
436 std::vector<std::string> node_list;
Maxwell Henderson3279bc52024-03-01 09:50:53 -0800437 node_list.push_back("orin1");
438 node_list.push_back("imu");
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800439 std::vector<std::string> camera_list;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800440 std::vector<const calibration::CameraCalibration *> calibration_list;
441
442 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
443 std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
444 std::vector<frc971::vision::ImageCallback *> image_callbacks;
445 std::vector<Eigen::Affine3d> default_extrinsics;
446
447 for (uint i = 0; i < node_list.size(); i++) {
448 std::string node = node_list[i];
449 const aos::Node *pi =
450 aos::configuration::GetNode(reader.configuration(), node.c_str());
451
452 detection_event_loops.emplace_back(
453 reader.event_loop_factory()->MakeEventLoop(
454 (node + "_detection").c_str(), pi));
455
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800456 for (const std::string camera : {"/camera0", "/camera1"}) {
457 std::string camera_name = "/" + node + camera;
458 camera_list.push_back(camera_name);
459 frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
460 detection_event_loops.back().get());
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800461
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800462 // Get the calibration for this orin/camera pair
463 int camera_id = std::stoi(camera.substr(7, 1));
464 const calibration::CameraCalibration *calibration =
465 y2024::vision::FindCameraCalibration(constants_fetcher.constants(),
466 node, camera_id);
467 calibration_list.push_back(calibration);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800468
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800469 // Extract the extrinsics from the calibration, and save as "defaults"
470 cv::Mat extrinsics_cv =
471 frc971::vision::CameraExtrinsics(calibration).value();
472 Eigen::Matrix4d extrinsics_matrix;
473 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
474 const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
475 default_extrinsics.emplace_back(ext_H_robot_pi);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800476
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800477 VLOG(1) << "Got extrinsics for " << node << ", " << camera << " as\n"
478 << default_extrinsics.back().matrix();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800479
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800480 // If we've got full logs, we need to set up a charuco/april tag extractor
481 // nd a call back to handle the data
482 if (FLAGS_use_full_logs) {
483 frc971::vision::TargetType target_type =
484 frc971::vision::TargetTypeFromString(FLAGS_target_type);
485 frc971::vision::CharucoExtractor *charuco_ext =
486 new frc971::vision::CharucoExtractor(calibration, target_type);
487 charuco_extractors.emplace_back(charuco_ext);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800488
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800489 LOG(INFO) << "Set up image callback for node " << node << ", camera "
490 << camera;
491 frc971::vision::ImageCallback *image_callback =
492 new frc971::vision::ImageCallback(
493 detection_event_loops[i].get(), camera_name,
494 [&reader, &charuco_extractors, &detection_event_loops,
495 &node_list, i](cv::Mat rgb_image,
496 const aos::monotonic_clock::time_point eof) {
497 aos::distributed_clock::time_point pi_distributed_time =
498 reader.event_loop_factory()
499 ->GetNodeEventLoopFactory(
500 detection_event_loops[i].get()->node())
501 ->ToDistributedClock(eof);
502 HandleImage(detection_event_loops[i].get(), rgb_image, eof,
503 pi_distributed_time, *charuco_extractors[i],
504 node_list[i]);
505 });
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800506
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800507 image_callbacks.emplace_back(image_callback);
508 } else {
509 detection_event_loops[i]->MakeWatcher(
510 camera, [&reader, &detection_event_loops, camera_name,
511 i](const TargetMap &map) {
512 aos::distributed_clock::time_point pi_distributed_time =
513 reader.event_loop_factory()
514 ->GetNodeEventLoopFactory(
515 detection_event_loops[i]->node())
516 ->ToDistributedClock(aos::monotonic_clock::time_point(
517 aos::monotonic_clock::duration(
518 map.monotonic_timestamp_ns())));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800519
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800520 HandleTargetMap(map, pi_distributed_time, camera_name);
521 });
522 LOG(INFO) << "Created watcher for using the detection event loop for "
523 << node << " with i = " << i << " and size "
524 << detection_event_loops.size() << " and camera " << camera;
525 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800526 }
527 }
528
529 reader.event_loop_factory()->Run();
530
531 // 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 Ostrowskiddebdcb2024-02-29 22:25:36 -0800537 for (auto camera : camera_list) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800538 std::vector<TimestampedPiDetection> pose_list;
539 for (auto ext : two_board_extrinsics_list) {
540 CHECK_EQ(base_target_id, ext.board_id)
541 << " All boards should have same reference id";
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800542 if (ext.pi_name == camera) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800543 pose_list.push_back(ext);
544 }
545 }
546 Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800547 VLOG(1) << "Estimate from " << camera << " with " << pose_list.size()
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800548 << " observations is:\n"
549 << avg_pose_from_pi.matrix();
550 }
551 Eigen::Affine3d H_boardA_boardB_avg =
552 ComputeAveragePose(two_board_extrinsics_list);
553 // TODO: Should probably do some outlier rejection
554 LOG(INFO) << "Estimate of two board pose using all nodes with "
555 << two_board_extrinsics_list.size() << " observations is:\n"
556 << H_boardA_boardB_avg.matrix() << "\n";
557
558 // Next, compute the relative camera poses
559 LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
560 std::vector<Eigen::Affine3d> H_camera1_camera2_list;
561 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]);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800564 LOG(INFO) << "Default extrinsic for camera " << camera_list[0] << " is "
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800565 << default_extrinsics[0].matrix();
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800566 for (uint i = 0; i < camera_list.size() - 1; i++) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800567 H_camera1_camera2_list.clear();
568 // Go through the list, and find successive pairs of cameras
569 for (auto [pose1, pose2] : detection_list) {
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800570 if ((pose1.pi_name == camera_list[i]) &&
571 (pose2.pi_name == camera_list[i + 1])) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800572 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();
578 }
579
580 // 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;
583 // If pose2 isn't referenced to boardA (base_target_id), correct
584 // that
585 if (pose2.board_id != base_target_id) {
586 // pose2.H_camera_target references boardB, so map back to boardA
587 H_camera2_boardA =
588 pose2.H_camera_target * H_boardA_boardB_avg.inverse();
589 }
590
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());
606 if (FLAGS_alt_view) {
607 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();
614 }
615 }
616 // 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 Ostrowskiddebdcb2024-02-29 22:25:36 -0800619 << "Failed with zero poses for node " << camera_list[i];
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800620 if (H_camera1_camera2_list.size() > 0) {
621 Eigen::Affine3d H_camera1_camera2_avg =
622 ComputeAveragePose(H_camera1_camera2_list);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800623 LOG(INFO) << "From " << camera_list[i] << " to " << camera_list[i + 1]
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800624 << " found " << H_camera1_camera2_list.size()
625 << " observations, and the average pose is:\n"
626 << H_camera1_camera2_avg.matrix();
627 Eigen::Affine3d H_camera1_camera2_default =
628 default_extrinsics[i].inverse() * default_extrinsics[i + 1];
629 LOG(INFO) << "Compare this to that from default values:\n"
630 << 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)";
642 // Next extrinsic is just previous one * avg_delta_pose
643 Eigen::Affine3d next_extrinsic =
644 updated_extrinsics.back() * H_camera1_camera2_avg;
645 updated_extrinsics.push_back(next_extrinsic);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800646 LOG(INFO) << "Default Extrinsic for " << camera_list[i + 1] << " is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800647 << default_extrinsics[i + 1].matrix();
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800648 LOG(INFO) << "--> Updated Extrinsic for " << camera_list[i + 1]
649 << " is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800650 << next_extrinsic.matrix();
651
652 // Wirte out this extrinsic to a file
653 flatbuffers::FlatBufferBuilder fbb;
654 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
655 fbb.CreateVector(
656 frc971::vision::MatrixToVector(next_extrinsic.matrix()));
657 calibration::TransformationMatrix::Builder matrix_builder(fbb);
658 matrix_builder.add_data(data_offset);
659 flatbuffers::Offset<calibration::TransformationMatrix>
660 extrinsic_calibration_offset = matrix_builder.Finish();
661
662 calibration::CameraCalibration::Builder calibration_builder(fbb);
663 calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset);
664 const aos::realtime_clock::time_point realtime_now =
665 aos::realtime_clock::now();
666 calibration_builder.add_calibration_timestamp(
667 realtime_now.time_since_epoch().count());
668 fbb.Finish(calibration_builder.Finish());
669 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
670 solved_extrinsics = fbb.Release();
671
672 aos::FlatbufferDetachedBuffer<
673 frc971::vision::calibration::CameraCalibration>
674 cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]);
675 cal_copy.mutable_message()->clear_fixed_extrinsics();
676 cal_copy.mutable_message()->clear_calibration_timestamp();
677 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
678 merged_calibration = aos::MergeFlatBuffers(
679 &cal_copy.message(), &solved_extrinsics.message());
680
681 std::stringstream time_ss;
682 time_ss << realtime_now;
683
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800684 // TODO: This breaks because we're naming orin1 and imu as nodes
685 // Assumes camera_list name is of form "/orin#/cameraX" to create
686 // calibration filename
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800687 const std::string calibration_filename =
688 FLAGS_output_folder +
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800689 absl::StrFormat("/calibration_orin-%d-%s-%d_cam-%s_%s.json",
690 FLAGS_team_number, camera_list[i + 1].substr(5, 1),
691 calibration_list[i + 1]->camera_number(),
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800692 calibration_list[i + 1]->camera_id()->data(),
693 time_ss.str());
694
695 LOG(INFO) << calibration_filename << " -> "
696 << aos::FlatbufferToJson(merged_calibration,
697 {.multi_line = true});
698
699 aos::util::WriteStringToFileOrDie(
700 calibration_filename,
701 aos::FlatbufferToJson(merged_calibration, {.multi_line = true}));
702 }
703 }
704
705 // Cleanup
706 for (uint i = 0; i < image_callbacks.size(); i++) {
707 delete charuco_extractors[i];
708 delete image_callbacks[i];
709 }
710}
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800711} // namespace y2024::vision
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800712
713int main(int argc, char **argv) {
714 aos::InitGoogle(&argc, &argv);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800715 y2024::vision::ExtrinsicsMain(argc, argv);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800716}