blob: 7a9f41275d6363c0bc2420e442afbf0116fd8b57 [file] [log] [blame]
Jim Ostrowski9bf206a2024-01-26 23:31:58 -08001#include <numeric>
2
Austin Schuh99f7c6a2024-06-25 22:07:44 -07003#include "absl/flags/flag.h"
4
Jim Ostrowski9bf206a2024-01-26 23:31:58 -08005#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"
14#include "frc971/vision/extrinsics_calibration.h"
15#include "frc971/vision/target_mapper.h"
Jim Ostrowski33208982024-03-02 15:01:45 -080016#include "frc971/vision/vision_util_lib.h"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080017#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 "frc971/constants/constants_sender_lib.h"
29#include "frc971/vision/vision_util_lib.h"
30#include "y2024/constants/simulated_constants_sender.h"
31#include "y2024/vision/vision_util.h"
32
Austin Schuh99f7c6a2024-06-25 22:07:44 -070033ABSL_FLAG(bool, alt_view, false,
34 "If true, show visualization from field level, rather than above");
35ABSL_FLAG(std::string, config, "",
36 "If set, override the log's config file with this one.");
37ABSL_FLAG(std::string, constants_path, "y2024/constants/constants.json",
38 "Path to the constant file");
39ABSL_FLAG(double, max_pose_error, 5e-5,
40 "Throw out target poses with a higher pose error than this");
41ABSL_FLAG(double, max_pose_error_ratio, 0.4,
42 "Throw out target poses with a higher pose error ratio than this");
43ABSL_FLAG(std::string, output_folder, "/tmp",
44 "Directory in which to store the updated calibration files");
45ABSL_FLAG(std::string, target_type, "charuco_diamond",
46 "Type of target being used [aruco, charuco, charuco_diamond]");
47ABSL_FLAG(int32_t, team_number, 0,
48 "Required: Use the calibration for a node with this team number");
49ABSL_FLAG(
50 uint64_t, wait_key, 1,
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080051 "Time in ms to wait between images (0 to wait indefinitely until click)");
Austin Schuh99f7c6a2024-06-25 22:07:44 -070052ABSL_FLAG(bool, robot, false,
53 "If true we're calibrating extrinsics for the robot, use the "
54 "correct node path for the robot.");
Maxwell Henderson9d7b1862024-03-02 11:00:29 -080055
Austin Schuh99f7c6a2024-06-25 22:07:44 -070056ABSL_DECLARE_FLAG(int32_t, min_target_id);
57ABSL_DECLARE_FLAG(int32_t, max_target_id);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080058
59// Calibrate extrinsic relationship between cameras using two targets
60// seen jointly between cameras. Uses two types of information: 1)
61// when a single camera sees two targets, we estimate the pose between
62// targets, and 2) when two separate cameras each see a target, we can
63// use the pose between targets to estimate the pose between cameras.
64
65// We then create the extrinsics for the robot by starting with the
66// given extrinsic for camera 1 (between imu/robot and camera frames)
67// and then map each subsequent camera based on the data collected and
68// the extrinsic poses computed here.
69
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080070// TODO<Jim>: Not currently using estimate from first camera to last camera--
71// should do full estimation, and probably also include camera->imu extrinsics
72// from all cameras, not just first camera
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080073
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -080074namespace y2024::vision {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080075using frc971::vision::DataAdapter;
76using frc971::vision::ImageCallback;
77using frc971::vision::PoseUtils;
78using frc971::vision::TargetMap;
79using frc971::vision::TargetMapper;
80using frc971::vision::VisualizeRobot;
81namespace calibration = frc971::vision::calibration;
82
83static constexpr double kImagePeriodMs =
Maxwell Henderson9d7b1862024-03-02 11:00:29 -080084 1.0 / 60.0 * 1000.0; // Image capture period in ms
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080085
Jim Ostrowski67726282024-03-24 14:39:33 -070086std::vector<CameraNode> node_list(y2024::vision::CreateNodeList());
87
88std::map<std::string, int> ordering_map(
89 y2024::vision::CreateOrderingMap(node_list));
90
Jim Ostrowski9bf206a2024-01-26 23:31:58 -080091// Change reference frame from camera to robot
92Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
93 Eigen::Affine3d extrinsics) {
94 const Eigen::Affine3d H_robot_camera = extrinsics;
95 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
96 return H_robot_target;
97}
98
Jim Ostrowski67726282024-03-24 14:39:33 -070099struct TimestampedCameraDetection {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800100 aos::distributed_clock::time_point time;
101 // Pose of target relative to robot
102 Eigen::Affine3d H_camera_target;
103 // name of pi
Jim Ostrowski67726282024-03-24 14:39:33 -0700104 std::string camera_name;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800105 int board_id;
106};
107
Jim Ostrowski67726282024-03-24 14:39:33 -0700108TimestampedCameraDetection last_observation;
109std::vector<std::pair<TimestampedCameraDetection, TimestampedCameraDetection>>
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800110 detection_list;
Jim Ostrowski67726282024-03-24 14:39:33 -0700111std::vector<TimestampedCameraDetection> two_board_extrinsics_list;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800112VisualizeRobot vis_robot_;
113
114// TODO<jim>: Implement variance calcs
115Eigen::Affine3d ComputeAveragePose(
116 std::vector<Eigen::Vector3d> &translation_list,
117 std::vector<Eigen::Vector4d> &rotation_list,
118 Eigen::Vector3d *translation_variance = nullptr,
119 Eigen::Vector3d *rotation_variance = nullptr) {
120 Eigen::Vector3d avg_translation =
121 std::accumulate(translation_list.begin(), translation_list.end(),
122 Eigen::Vector3d{0, 0, 0}) /
123 translation_list.size();
124
125 // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this
126 // requires a fixed number of quaternions to be averaged
127 Eigen::Vector4d avg_rotation =
128 std::accumulate(rotation_list.begin(), rotation_list.end(),
129 Eigen::Vector4d{0, 0, 0, 0}) /
130 rotation_list.size();
131 // Normalize, so it's a valid quaternion
132 avg_rotation = avg_rotation / avg_rotation.norm();
133 Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1],
134 avg_rotation[2], avg_rotation[3]};
135 Eigen::Translation3d translation(avg_translation);
136 Eigen::Affine3d return_pose = translation * avg_rotation_q;
137 if (translation_variance != nullptr) {
138 *translation_variance = Eigen::Vector3d();
139 }
140 if (rotation_variance != nullptr) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700141 *rotation_variance = Eigen::Vector3d();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800142 }
143
144 return return_pose;
145}
146
147Eigen::Affine3d ComputeAveragePose(
148 std::vector<Eigen::Affine3d> &pose_list,
149 Eigen::Vector3d *translation_variance = nullptr,
150 Eigen::Vector3d *rotation_variance = nullptr) {
151 std::vector<Eigen::Vector3d> translation_list;
152 std::vector<Eigen::Vector4d> rotation_list;
153
154 for (Eigen::Affine3d pose : pose_list) {
155 translation_list.push_back(pose.translation());
156 Eigen::Quaterniond quat(pose.rotation().matrix());
157 rotation_list.push_back(
158 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
159 }
160
161 return ComputeAveragePose(translation_list, rotation_list,
162 translation_variance, rotation_variance);
163}
164
165Eigen::Affine3d ComputeAveragePose(
Jim Ostrowski67726282024-03-24 14:39:33 -0700166 std::vector<TimestampedCameraDetection> &pose_list,
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800167 Eigen::Vector3d *translation_variance = nullptr,
168 Eigen::Vector3d *rotation_variance = nullptr) {
169 std::vector<Eigen::Vector3d> translation_list;
170 std::vector<Eigen::Vector4d> rotation_list;
171
Jim Ostrowski67726282024-03-24 14:39:33 -0700172 for (TimestampedCameraDetection pose : pose_list) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800173 translation_list.push_back(pose.H_camera_target.translation());
174 Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix());
175 rotation_list.push_back(
176 Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
177 }
178 return ComputeAveragePose(translation_list, rotation_list,
179 translation_variance, rotation_variance);
180}
181
182void HandlePoses(cv::Mat rgb_image,
183 std::vector<TargetMapper::TargetPose> target_poses,
184 aos::distributed_clock::time_point distributed_eof,
Jim Ostrowski67726282024-03-24 14:39:33 -0700185 std::string camera_name) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800186 // This is used to transform points for visualization
187 // Assumes targets are aligned with x->right, y->up, z->out of board
188 Eigen::Affine3d H_world_board;
189 H_world_board = Eigen::Translation3d::Identity() *
190 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700191 if (absl::GetFlag(FLAGS_alt_view)) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800192 // Don't rotate -- this is like viewing from the side
193 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
194 }
195
196 bool draw_vis = false;
197 CHECK_LE(target_poses.size(), 2u)
198 << "Can't handle more than two tags in field of view";
199 if (target_poses.size() == 2) {
200 draw_vis = true;
Jim Ostrowski67726282024-03-24 14:39:33 -0700201 VLOG(1) << "Saw two boards in same view from " << camera_name;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800202 int from_index = 0;
203 int to_index = 1;
204 // Handle when we see two boards at once
205 // We'll store them referenced to the lower id board
206 if (target_poses[from_index].id > target_poses[to_index].id) {
207 std::swap<int>(from_index, to_index);
208 }
209
210 // Create "from" (A) and "to" (B) transforms
211 Eigen::Affine3d H_camera_boardA =
212 PoseUtils::Pose3dToAffine3d(target_poses[from_index].pose);
213 Eigen::Affine3d H_camera_boardB =
214 PoseUtils::Pose3dToAffine3d(target_poses[to_index].pose);
215
216 Eigen::Affine3d H_boardA_boardB =
217 H_camera_boardA.inverse() * H_camera_boardB;
218
Jim Ostrowski67726282024-03-24 14:39:33 -0700219 TimestampedCameraDetection boardA_boardB{
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800220 .time = distributed_eof,
221 .H_camera_target = H_boardA_boardB,
Jim Ostrowski67726282024-03-24 14:39:33 -0700222 .camera_name = camera_name,
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800223 .board_id = target_poses[from_index].id};
224
Jim Ostrowski67726282024-03-24 14:39:33 -0700225 VLOG(1) << "Two boards seen by " << camera_name << ". Map from board "
226 << target_poses[from_index].id << " to "
227 << target_poses[to_index].id << " is\n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800228 << H_boardA_boardB.matrix();
229 // Store this observation of the transform between two boards
230 two_board_extrinsics_list.push_back(boardA_boardB);
231
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700232 if (absl::GetFlag(FLAGS_visualize)) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800233 vis_robot_.DrawFrameAxes(
234 H_world_board,
Jim Ostrowski67726282024-03-24 14:39:33 -0700235 std::string("Board ") + std::to_string(target_poses[from_index].id),
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800236 cv::Scalar(0, 255, 0));
237 vis_robot_.DrawFrameAxes(
238 H_world_board * boardA_boardB.H_camera_target,
Jim Ostrowski67726282024-03-24 14:39:33 -0700239 std::string("Board ") + std::to_string(target_poses[to_index].id),
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800240 cv::Scalar(255, 0, 0));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800241 vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(),
Jim Ostrowski67726282024-03-24 14:39:33 -0700242 camera_name, kOrinColors.at(camera_name));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800243 }
244 } else if (target_poses.size() == 1) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700245 VLOG(1) << camera_name << " saw single board " << target_poses[0].id;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800246 Eigen::Affine3d H_camera2_board2 =
247 PoseUtils::Pose3dToAffine3d(target_poses[0].pose);
Jim Ostrowski67726282024-03-24 14:39:33 -0700248 TimestampedCameraDetection new_observation{
249 .time = distributed_eof,
250 .H_camera_target = H_camera2_board2,
251 .camera_name = camera_name,
252 .board_id = target_poses[0].id};
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800253
Jim Ostrowski67726282024-03-24 14:39:33 -0700254 // Only take two observations if they're within half an image cycle of
255 // each other (i.e., as close in time as possible) And, if two consecutive
256 // observations are from the same camera, just replace with the newest one
257 if ((new_observation.camera_name != last_observation.camera_name) &&
258 (std::abs((distributed_eof - last_observation.time).count()) <
259 kImagePeriodMs / 2.0 * 1000000.0)) {
260 // Sort by camera numbering, since this is how we will handle them
261 std::pair<TimestampedCameraDetection, TimestampedCameraDetection>
262 new_pair;
263 if (ordering_map.at(last_observation.camera_name) <
264 ordering_map.at(new_observation.camera_name)) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800265 new_pair = std::pair(last_observation, new_observation);
Jim Ostrowski67726282024-03-24 14:39:33 -0700266 } else if (ordering_map.at(last_observation.camera_name) >
267 ordering_map.at(new_observation.camera_name)) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800268 new_pair = std::pair(new_observation, last_observation);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800269 }
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800270
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800271 detection_list.push_back(new_pair);
272
273 // This bit is just for visualization and checking purposes-- use the
274 // last two-board observation to figure out the current estimate
275 // between the two cameras
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700276 if (absl::GetFlag(FLAGS_visualize) &&
277 two_board_extrinsics_list.size() > 0) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800278 draw_vis = true;
Jim Ostrowski67726282024-03-24 14:39:33 -0700279 TimestampedCameraDetection &last_two_board_ext =
280 two_board_extrinsics_list.back();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800281 Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
282 int boardA_boardB_id = last_two_board_ext.board_id;
283
Jim Ostrowski67726282024-03-24 14:39:33 -0700284 TimestampedCameraDetection camera1_boardA = new_pair.first;
285 TimestampedCameraDetection camera2_boardB = new_pair.second;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800286 // If camera1_boardA doesn't point to the first target, then swap
287 // these two
288 if (camera1_boardA.board_id != boardA_boardB_id) {
289 camera1_boardA = new_pair.second;
290 camera2_boardB = new_pair.first;
291 }
Jim Ostrowski67726282024-03-24 14:39:33 -0700292 VLOG(1) << "Camera " << camera1_boardA.camera_name << " seeing board "
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800293 << camera1_boardA.board_id << " and camera "
Jim Ostrowski67726282024-03-24 14:39:33 -0700294 << camera2_boardB.camera_name << " seeing board "
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800295 << camera2_boardB.board_id;
296
297 vis_robot_.DrawRobotOutline(
298 H_world_board * camera1_boardA.H_camera_target.inverse(),
Jim Ostrowski67726282024-03-24 14:39:33 -0700299 camera1_boardA.camera_name,
300 kOrinColors.at(camera1_boardA.camera_name));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800301 vis_robot_.DrawRobotOutline(
302 H_world_board * H_boardA_boardB *
303 camera2_boardB.H_camera_target.inverse(),
Jim Ostrowski67726282024-03-24 14:39:33 -0700304 camera2_boardB.camera_name,
305 kOrinColors.at(camera2_boardB.camera_name));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800306 vis_robot_.DrawFrameAxes(
307 H_world_board,
308 std::string("Board ") + std::to_string(last_two_board_ext.board_id),
309 cv::Scalar(0, 255, 0));
310 vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
311 cv::Scalar(255, 0, 0));
Jim Ostrowski67726282024-03-24 14:39:33 -0700312 VLOG(1) << "Storing observation between " << new_pair.first.camera_name
313 << ", target " << new_pair.first.board_id << " and "
314 << new_pair.second.camera_name << ", target "
315 << new_pair.second.board_id;
316 } else if (two_board_extrinsics_list.size() == 0) {
317 VLOG(1) << "Not drawing observation yet, since we don't have a two "
318 "board estimate";
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800319 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800320 } else {
Jim Ostrowski67726282024-03-24 14:39:33 -0700321 if (new_observation.camera_name == last_observation.camera_name) {
322 VLOG(2) << "Updating repeated observation for " << camera_name;
323 } else {
324 VLOG(1) << "Storing observation for " << camera_name << " at time "
325 << distributed_eof << " since last observation was "
326 << std::abs((distributed_eof - last_observation.time).count()) /
327 1000000.0
328 << "ms ago";
329 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800330 last_observation = new_observation;
331 }
332 }
333
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700334 if (absl::GetFlag(FLAGS_visualize)) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800335 if (!rgb_image.empty()) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700336 std::string image_name = camera_name + " Image";
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800337 cv::Mat rgb_small;
338 cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
339 cv::imshow(image_name, rgb_small);
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700340 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800341 }
342
343 if (draw_vis) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700344 cv::imshow("Overhead View", vis_robot_.image_);
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700345 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800346 vis_robot_.ClearImage();
347 }
348 }
349}
350
351void HandleTargetMap(const TargetMap &map,
352 aos::distributed_clock::time_point distributed_eof,
Jim Ostrowski67726282024-03-24 14:39:33 -0700353 std::string camera_name) {
354 VLOG(1) << "Got april tag map call from camera " << camera_name;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800355 // Create empty RGB image in this case
356 cv::Mat rgb_image;
357 std::vector<TargetMapper::TargetPose> target_poses;
358
359 for (const auto *target_pose_fbs : *map.target_poses()) {
360 // Skip detections with invalid ids
361 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700362 absl::GetFlag(FLAGS_min_target_id) ||
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800363 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700364 absl::GetFlag(FLAGS_max_target_id)) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700365 VLOG(1) << "Skipping tag from " << camera_name << " with invalid id of "
366 << target_pose_fbs->id();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800367 continue;
368 }
369
370 // Skip detections with high pose errors
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700371 if (target_pose_fbs->pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700372 LOG(INFO) << "Skipping tag from " << camera_name << " with id "
373 << target_pose_fbs->id() << " due to pose error of "
374 << target_pose_fbs->pose_error();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800375 continue;
376 }
377 // Skip detections with high pose error ratios
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700378 if (target_pose_fbs->pose_error_ratio() >
379 absl::GetFlag(FLAGS_max_pose_error_ratio)) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700380 LOG(INFO) << "Skipping tag from " << camera_name << " with id "
381 << target_pose_fbs->id() << " due to pose error ratio of "
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800382 << target_pose_fbs->pose_error_ratio();
383 continue;
384 }
385
386 const TargetMapper::TargetPose target_pose =
387 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
388
389 target_poses.emplace_back(target_pose);
390
391 Eigen::Affine3d H_camera_target =
392 PoseUtils::Pose3dToAffine3d(target_pose.pose);
Jim Ostrowski67726282024-03-24 14:39:33 -0700393 VLOG(1) << camera_name << " saw target " << target_pose.id
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800394 << " from TargetMap at timestamp " << distributed_eof
395 << " with pose = " << H_camera_target.matrix();
396 }
Jim Ostrowski67726282024-03-24 14:39:33 -0700397 HandlePoses(rgb_image, target_poses, distributed_eof, camera_name);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800398}
399
400void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
401 const aos::monotonic_clock::time_point eof,
402 aos::distributed_clock::time_point distributed_eof,
403 frc971::vision::CharucoExtractor &charuco_extractor,
Jim Ostrowski67726282024-03-24 14:39:33 -0700404 std::string camera_name) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800405 std::vector<cv::Vec4i> charuco_ids;
406 std::vector<std::vector<cv::Point2f>> charuco_corners;
407 bool valid = false;
408 std::vector<Eigen::Vector3d> rvecs_eigen;
409 std::vector<Eigen::Vector3d> tvecs_eigen;
410 // Why eof vs. distributed_eof?
411 charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
412 charuco_ids, charuco_corners, valid,
413 rvecs_eigen, tvecs_eigen);
414 if (rvecs_eigen.size() > 0 && !valid) {
415 LOG(WARNING) << "Charuco extractor returned not valid";
416 return;
417 }
418
419 std::vector<TargetMapper::TargetPose> target_poses;
420 for (size_t i = 0; i < tvecs_eigen.size(); i++) {
421 Eigen::Quaterniond rotation(
422 frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i]));
423 ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation);
424 TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose};
425 target_poses.emplace_back(target_pose);
426
427 Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose);
Jim Ostrowski67726282024-03-24 14:39:33 -0700428 VLOG(2) << camera_name << " saw target " << target_pose.id
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800429 << " from image at timestamp " << distributed_eof
430 << " with pose = " << H_camera_target.matrix();
431 }
Jim Ostrowski67726282024-03-24 14:39:33 -0700432 HandlePoses(rgb_image, target_poses, distributed_eof, camera_name);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800433}
434
435void ExtrinsicsMain(int argc, char *argv[]) {
436 vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
437 vis_robot_.ClearImage();
438 const double kFocalLength = 1000.0;
439 const int kImageWidth = 1000;
440 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
441
442 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700443 (absl::GetFlag(FLAGS_config).empty()
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800444 ? std::nullopt
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700445 : std::make_optional(
446 aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config))));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800447
448 // open logfiles
449 aos::logger::LogReader reader(
450 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
451 config.has_value() ? &config->message() : nullptr);
452
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800453 reader.RemapLoggedChannel("/imu/constants", "y2024.Constants");
454 reader.RemapLoggedChannel("/orin1/constants", "y2024.Constants");
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700455 if (absl::GetFlag(FLAGS_robot)) {
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800456 reader.RemapLoggedChannel("/roborio/constants", "y2024.Constants");
457 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800458 reader.Register();
459
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700460 y2024::SendSimulationConstants(reader.event_loop_factory(),
461 absl::GetFlag(FLAGS_team_number),
462 absl::GetFlag(FLAGS_constants_path));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800463
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700464 VLOG(1) << "Using target type " << absl::GetFlag(FLAGS_target_type);
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800465
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800466 std::vector<const calibration::CameraCalibration *> calibration_list;
467
468 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
469 std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
470 std::vector<frc971::vision::ImageCallback *> image_callbacks;
471 std::vector<Eigen::Affine3d> default_extrinsics;
472
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800473 for (const CameraNode &camera_node : node_list) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700474 const aos::Node *node = aos::configuration::GetNode(
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800475 reader.configuration(), camera_node.node_name.c_str());
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800476
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800477 detection_event_loops.emplace_back(
478 reader.event_loop_factory()->MakeEventLoop(
Jim Ostrowski67726282024-03-24 14:39:33 -0700479 (camera_node.camera_name() + "_detection").c_str(), node));
480
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700481 aos::EventLoop *const event_loop = detection_event_loops.back().get();
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800482 frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700483 event_loop);
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800484 // Get the calibration for this orin/camera pair
485 const calibration::CameraCalibration *calibration =
486 y2024::vision::FindCameraCalibration(constants_fetcher.constants(),
487 camera_node.node_name,
488 camera_node.camera_number);
489 calibration_list.push_back(calibration);
Maxwell Henderson69ec45e2024-03-01 22:52:21 -0800490
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800491 // Extract the extrinsics from the calibration, and save as "defaults"
492 cv::Mat extrinsics_cv =
493 frc971::vision::CameraExtrinsics(calibration).value();
494 Eigen::Matrix4d extrinsics_matrix;
495 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
Jim Ostrowski67726282024-03-24 14:39:33 -0700496 const auto ext_H_robot_camera = Eigen::Affine3d(extrinsics_matrix);
497 default_extrinsics.emplace_back(ext_H_robot_camera);
Maxwell Henderson69ec45e2024-03-01 22:52:21 -0800498
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800499 VLOG(1) << "Got extrinsics for " << camera_node.camera_name() << " as\n"
500 << default_extrinsics.back().matrix();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800501
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700502 event_loop->MakeWatcher(
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800503 camera_node.camera_name(),
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700504 [&reader, event_loop, camera_node](const TargetMap &map) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700505 aos::distributed_clock::time_point camera_distributed_time =
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800506 reader.event_loop_factory()
Maxwell Henderson9beb5692024-03-17 18:36:11 -0700507 ->GetNodeEventLoopFactory(event_loop->node())
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800508 ->ToDistributedClock(aos::monotonic_clock::time_point(
509 aos::monotonic_clock::duration(
510 map.monotonic_timestamp_ns())));
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800511
Jim Ostrowski67726282024-03-24 14:39:33 -0700512 HandleTargetMap(map, camera_distributed_time,
513 camera_node.camera_name());
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800514 });
Jim Ostrowski33208982024-03-02 15:01:45 -0800515 VLOG(1) << "Created watcher for using the detection event loop for "
Jim Ostrowski67726282024-03-24 14:39:33 -0700516 << camera_node.camera_name();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800517 }
518
519 reader.event_loop_factory()->Run();
520
Jim Ostrowski67726282024-03-24 14:39:33 -0700521 // Do quick check to see what averaged two-board pose for
522 // each camera is individually
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800523 CHECK_GT(two_board_extrinsics_list.size(), 0u)
524 << "Must have at least one view of both boards";
525 int base_target_id = two_board_extrinsics_list[0].board_id;
526 VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800527
528 for (auto camera_node : node_list) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700529 std::vector<TimestampedCameraDetection> pose_list;
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800530 for (auto ext : two_board_extrinsics_list) {
531 CHECK_EQ(base_target_id, ext.board_id)
532 << " All boards should have same reference id";
Jim Ostrowski67726282024-03-24 14:39:33 -0700533 if (ext.camera_name == camera_node.camera_name()) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800534 pose_list.push_back(ext);
535 }
536 }
Jim Ostrowski67726282024-03-24 14:39:33 -0700537 Eigen::Affine3d avg_pose_from_camera = ComputeAveragePose(pose_list);
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800538 VLOG(1) << "Estimate from " << camera_node.camera_name() << " with "
539 << pose_list.size() << " observations is:\n"
Jim Ostrowski67726282024-03-24 14:39:33 -0700540 << avg_pose_from_camera.matrix();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800541 }
542 Eigen::Affine3d H_boardA_boardB_avg =
543 ComputeAveragePose(two_board_extrinsics_list);
544 // TODO: Should probably do some outlier rejection
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800545 VLOG(1) << "Estimate of two board pose using all nodes with "
546 << two_board_extrinsics_list.size() << " observations is:\n"
547 << H_boardA_boardB_avg.matrix() << "\n";
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800548
549 // Next, compute the relative camera poses
550 LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
551 std::vector<Eigen::Affine3d> H_camera1_camera2_list;
552 std::vector<Eigen::Affine3d> updated_extrinsics;
553 // Use the first node's extrinsics as our base, and fix from there
554 updated_extrinsics.push_back(default_extrinsics[0]);
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800555 LOG(INFO) << "Default extrinsic for camera " << node_list.at(0).camera_name()
556 << " is " << default_extrinsics[0].matrix();
557 for (uint i = 0; i < node_list.size() - 1; i++) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800558 H_camera1_camera2_list.clear();
Jim Ostrowski67726282024-03-24 14:39:33 -0700559 // Go through the list, and find successive pairs of
560 // cameras We'll be calculating and writing the second
561 // of the pair (the i+1'th camera)
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800562 for (auto [pose1, pose2] : detection_list) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700563 if ((pose1.camera_name == node_list.at(i).camera_name()) &&
564 (pose2.camera_name == node_list.at(i + 1).camera_name())) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800565 Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
566 // If pose1 isn't referenced to base_target_id, correct that
567 if (pose1.board_id != base_target_id) {
568 // pose1.H_camera_target references boardB, so map back to boardA
569 H_camera1_boardA =
570 pose1.H_camera_target * H_boardA_boardB_avg.inverse();
571 }
572
573 // Now, get the camera2->boardA map (notice it's boardA, same as
Jim Ostrowski33208982024-03-02 15:01:45 -0800574 // camera1, so we can compute the difference between the cameras with
575 // both referenced to boardA)
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800576 Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target;
Jim Ostrowski67726282024-03-24 14:39:33 -0700577 // If pose2 isn't referenced to boardA (base_target_id), correct that
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800578 if (pose2.board_id != base_target_id) {
579 // pose2.H_camera_target references boardB, so map back to boardA
580 H_camera2_boardA =
581 pose2.H_camera_target * H_boardA_boardB_avg.inverse();
582 }
583
584 // Compute camera1->camera2 map
585 Eigen::Affine3d H_camera1_camera2 =
586 H_camera1_boardA * H_camera2_boardA.inverse();
587 H_camera1_camera2_list.push_back(H_camera1_camera2);
Jim Ostrowski67726282024-03-24 14:39:33 -0700588 VLOG(1) << "Map from camera " << pose1.camera_name << " and tag "
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800589 << pose1.board_id << " with observation: \n"
590 << pose1.H_camera_target.matrix() << "\n to camera "
Jim Ostrowski67726282024-03-24 14:39:33 -0700591 << pose2.camera_name << " and tag " << pose2.board_id
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800592 << " with observation: \n"
593 << pose2.H_camera_target.matrix() << "\ngot map as\n"
594 << H_camera1_camera2.matrix();
595
596 Eigen::Affine3d H_world_board;
597 H_world_board = Eigen::Translation3d::Identity() *
598 Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700599 if (absl::GetFlag(FLAGS_alt_view)) {
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800600 H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
601 }
602
Jim Ostrowski67726282024-03-24 14:39:33 -0700603 VLOG(2) << "Camera1 " << pose1.camera_name << " in world frame is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800604 << (H_world_board * H_camera1_boardA.inverse()).matrix();
Jim Ostrowski67726282024-03-24 14:39:33 -0700605 VLOG(2) << "Camera2 " << pose2.camera_name << " in world frame is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800606 << (H_world_board * H_camera2_boardA.inverse()).matrix();
607 }
608 }
609 // TODO<Jim>: If we don't get any matches, we could just use default
610 // extrinsics
611 CHECK(H_camera1_camera2_list.size() > 0)
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800612 << "Failed with zero poses for node " << node_list.at(i).camera_name()
613 << " and " << node_list.at(i + 1).camera_name();
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800614 if (H_camera1_camera2_list.size() > 0) {
615 Eigen::Affine3d H_camera1_camera2_avg =
616 ComputeAveragePose(H_camera1_camera2_list);
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800617 LOG(INFO) << "From " << node_list.at(i).camera_name() << " to "
618 << node_list.at(i + 1).camera_name() << " found "
619 << H_camera1_camera2_list.size()
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800620 << " observations, and the average pose is:\n"
621 << H_camera1_camera2_avg.matrix();
622 Eigen::Affine3d H_camera1_camera2_default =
623 default_extrinsics[i].inverse() * default_extrinsics[i + 1];
624 LOG(INFO) << "Compare this to that from default values:\n"
625 << H_camera1_camera2_default.matrix();
626 Eigen::Affine3d H_camera1_camera2_diff =
627 H_camera1_camera2_avg * H_camera1_camera2_default.inverse();
628 LOG(INFO)
629 << "Difference between averaged and default delta poses "
630 "has |T| = "
631 << H_camera1_camera2_diff.translation().norm() << "m and |R| = "
632 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle()
633 << " radians ("
634 << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() *
635 180.0 / M_PI
636 << " degrees)";
637 // Next extrinsic is just previous one * avg_delta_pose
638 Eigen::Affine3d next_extrinsic =
639 updated_extrinsics.back() * H_camera1_camera2_avg;
640 updated_extrinsics.push_back(next_extrinsic);
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800641 LOG(INFO) << "Default Extrinsic for " << node_list.at(i + 1).camera_name()
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800642 << " is \n"
Maxwell Henderson9d7b1862024-03-02 11:00:29 -0800643 << default_extrinsics[i + 1].matrix();
644 LOG(INFO) << "--> Updated Extrinsic for "
645 << node_list.at(i + 1).camera_name() << " is \n"
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800646 << next_extrinsic.matrix();
647
Jim Ostrowski67726282024-03-24 14:39:33 -0700648 // Write out this extrinsic to a file
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800649 flatbuffers::FlatBufferBuilder fbb;
650 flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
651 fbb.CreateVector(
652 frc971::vision::MatrixToVector(next_extrinsic.matrix()));
653 calibration::TransformationMatrix::Builder matrix_builder(fbb);
654 matrix_builder.add_data(data_offset);
655 flatbuffers::Offset<calibration::TransformationMatrix>
656 extrinsic_calibration_offset = matrix_builder.Finish();
657
658 calibration::CameraCalibration::Builder calibration_builder(fbb);
659 calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset);
660 const aos::realtime_clock::time_point realtime_now =
661 aos::realtime_clock::now();
662 calibration_builder.add_calibration_timestamp(
663 realtime_now.time_since_epoch().count());
664 fbb.Finish(calibration_builder.Finish());
665 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
666 solved_extrinsics = fbb.Release();
667
668 aos::FlatbufferDetachedBuffer<
669 frc971::vision::calibration::CameraCalibration>
670 cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]);
671 cal_copy.mutable_message()->clear_fixed_extrinsics();
672 cal_copy.mutable_message()->clear_calibration_timestamp();
673 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
674 merged_calibration = aos::MergeFlatBuffers(
675 &cal_copy.message(), &solved_extrinsics.message());
676
677 std::stringstream time_ss;
678 time_ss << realtime_now;
679
Jim Ostrowski33208982024-03-02 15:01:45 -0800680 CameraNode &camera_node = node_list[i + 1];
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800681 const std::string calibration_filename =
Jim Ostrowski33208982024-03-02 15:01:45 -0800682 frc971::vision::CalibrationFilename(
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700683 absl::GetFlag(FLAGS_output_folder), camera_node.node_name,
684 absl::GetFlag(FLAGS_team_number), camera_node.camera_number,
685 cal_copy.message().camera_id()->data(), time_ss.str());
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800686 LOG(INFO) << calibration_filename << " -> "
687 << aos::FlatbufferToJson(merged_calibration,
688 {.multi_line = true});
689
690 aos::util::WriteStringToFileOrDie(
691 calibration_filename,
692 aos::FlatbufferToJson(merged_calibration, {.multi_line = true}));
Jim Ostrowski67726282024-03-24 14:39:33 -0700693
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700694 if (absl::GetFlag(FLAGS_visualize)) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700695 // Draw each of the updated extrinsic camera locations
696 vis_robot_.SetDefaultViewpoint(1000.0, 1500.0);
697 vis_robot_.DrawFrameAxes(
698 updated_extrinsics.back(), node_list.at(i + 1).camera_name(),
699 kOrinColors.at(node_list.at(i + 1).camera_name()));
700 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800701 }
702 }
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700703 if (absl::GetFlag(FLAGS_visualize)) {
Jim Ostrowski67726282024-03-24 14:39:33 -0700704 // And don't forget to draw the base camera location
705 vis_robot_.DrawFrameAxes(updated_extrinsics[0],
706 node_list.at(0).camera_name(),
707 kOrinColors.at(node_list.at(0).camera_name()));
708 cv::imshow("Extrinsic visualization", vis_robot_.image_);
709 // Add a bit extra time, so that we don't go right through the extrinsics
710 cv::waitKey(3000);
711 cv::waitKey(0);
712 }
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800713
714 // Cleanup
715 for (uint i = 0; i < image_callbacks.size(); i++) {
716 delete charuco_extractors[i];
717 delete image_callbacks[i];
718 }
719}
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800720} // namespace y2024::vision
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800721
722int main(int argc, char **argv) {
723 aos::InitGoogle(&argc, &argv);
Jim Ostrowskiddebdcb2024-02-29 22:25:36 -0800724 y2024::vision::ExtrinsicsMain(argc, argv);
Jim Ostrowski9bf206a2024-01-26 23:31:58 -0800725}