blob: 325ad90382928c12757b3829bff474251b63d5fc [file] [log] [blame]
Philipp Schrader790cb542023-07-05 21:06:52 -07001#include "Eigen/Dense"
2#include "opencv2/aruco.hpp"
3#include "opencv2/calib3d.hpp"
4#include "opencv2/core/eigen.hpp"
5#include "opencv2/features2d.hpp"
6#include "opencv2/highgui.hpp"
7#include "opencv2/highgui/highgui.hpp"
8#include "opencv2/imgproc.hpp"
9
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -080010#include "aos/configuration.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080011#include "aos/events/logging/log_reader.h"
12#include "aos/events/simulated_event_loop.h"
13#include "aos/init.h"
Jim Ostrowski68965cd2023-03-01 20:32:51 -080014#include "aos/util/mcap_logger.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080015#include "frc971/control_loops/pose.h"
milind-u16e3a082023-01-21 13:53:43 -080016#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080017#include "frc971/vision/target_mapper.h"
Jim Ostrowski6d242d52024-04-03 20:39:03 -070018#include "frc971/vision/vision_util_lib.h"
Jim Ostrowski49be8232023-03-23 01:00:14 -070019#include "frc971/vision/visualize_robot.h"
milind-uc5a494f2023-02-24 15:39:22 -080020#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080021#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080022#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080023
Austin Schuh99f7c6a2024-06-25 22:07:44 -070024ABSL_FLAG(std::string, config, "",
25 "If set, override the log's config file with this one.");
26ABSL_FLAG(std::string, constants_path, "y2023/constants/constants.json",
27 "Path to the constant file");
28ABSL_FLAG(std::string, dump_constraints_to, "/tmp/mapping_constraints.txt",
29 "Write the target constraints to this path");
30ABSL_FLAG(std::string, dump_stats_to, "/tmp/mapping_stats.txt",
31 "Write the mapping stats to this path");
32ABSL_FLAG(std::string, field_name, "charged_up",
33 "Field name, for the output json filename and flatbuffer field");
34ABSL_FLAG(std::string, json_path, "y2023/vision/maps/target_map.json",
35 "Specify path for json with initial pose guesses.");
36ABSL_FLAG(double, max_pose_error, 1e-6,
37 "Throw out target poses with a higher pose error than this");
38ABSL_FLAG(double, max_pose_error_ratio, 0.4,
39 "Throw out target poses with a higher pose error ratio than this");
40ABSL_FLAG(std::string, mcap_output_path, "", "Log to output.");
41ABSL_FLAG(std::string, output_dir, "y2023/vision/maps",
42 "Directory to write solved target map to");
43ABSL_FLAG(double, pause_on_distance, 1.0,
44 "Pause if two consecutive implied robot positions differ by more "
45 "than this many meters");
46ABSL_FLAG(std::string, pi, "pi1",
47 "Pi name to generate mcap log for; defaults to pi1.");
48ABSL_FLAG(uint64_t, skip_to, 1,
49 "Start at combined image of this number (1 is the first image)");
50ABSL_FLAG(bool, solve, true, "Whether to solve for the field's target map.");
51ABSL_FLAG(int32_t, team_number, 0,
52 "Required: Use the calibration for a node with this team number");
53ABSL_FLAG(uint64_t, wait_key, 1,
54 "Time in ms to wait between images, if no click (0 to wait "
55 "indefinitely until click).");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070056
Austin Schuh99f7c6a2024-06-25 22:07:44 -070057ABSL_DECLARE_FLAG(int32_t, frozen_target_id);
58ABSL_DECLARE_FLAG(int32_t, min_target_id);
59ABSL_DECLARE_FLAG(int32_t, max_target_id);
60ABSL_DECLARE_FLAG(bool, visualize_solver);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080061
Stephan Pleinesf63bde82024-01-13 15:59:33 -080062namespace y2023::vision {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080063using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080064using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080065using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080066using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080067using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070068using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080069namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080070
milind-u2ab4db12023-03-25 21:59:23 -070071// Class to handle reading target poses from a replayed log,
72// displaying various debug info, and passing the poses to
73// frc971::vision::TargetMapper for field mapping.
74class TargetMapperReplay {
75 public:
76 TargetMapperReplay(aos::logger::LogReader *reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080077
milind-u2ab4db12023-03-25 21:59:23 -070078 // Solves for the target poses with the accumulated detections if FLAGS_solve.
79 void MaybeSolve();
80
81 private:
82 static constexpr int kImageWidth = 1280;
83 // Map from pi node name to color for drawing
84 static const std::map<std::string, cv::Scalar> kPiColors;
85 // Contains fixed target poses without solving, for use with visualization
86 static const TargetMapper kFixedTargetMapper;
87
88 // Change reference frame from camera to robot
89 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
90 Eigen::Affine3d extrinsics);
91
92 // Adds april tag detections into the detection list, and handles
93 // visualization
94 void HandleAprilTags(const TargetMap &map,
95 aos::distributed_clock::time_point pi_distributed_time,
96 std::string node_name, Eigen::Affine3d extrinsics);
97
98 // Gets images from the given pi and passes apriltag positions to
99 // HandleAprilTags()
milind-u8b0f4782023-04-15 13:59:29 -0700100 void HandlePiCaptures(aos::EventLoop *mapping_event_loop);
milind-u2ab4db12023-03-25 21:59:23 -0700101
102 aos::logger::LogReader *reader_;
103 // April tag detections from all pis
104 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
milind-u2ab4db12023-03-25 21:59:23 -0700105
106 VisualizeRobot vis_robot_;
107 // Set of node names which are currently drawn on the display
108 std::set<std::string> drawn_nodes_;
109 // Number of frames displayed
110 size_t display_count_;
111 // Last time we drew onto the display image.
112 // This is different from when we actually call imshow() to update
113 // the display window
114 aos::distributed_clock::time_point last_draw_time_;
115
milind-u8cc03da2023-03-25 23:00:39 -0700116 Eigen::Affine3d last_H_world_robot_;
117 // Maximum distance between consecutive T_world_robot's in one display frame,
118 // used to determine if we need to pause for the user to see this frame
119 // clearly
120 double max_delta_T_world_robot_;
121
milind-u2ab4db12023-03-25 21:59:23 -0700122 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
123
124 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
125 std::unique_ptr<aos::McapLogger> relogger_;
126};
127
128const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700129 {"pi1", cv::Scalar(255, 0, 255)},
130 {"pi2", cv::Scalar(255, 255, 0)},
131 {"pi3", cv::Scalar(0, 255, 255)},
132 {"pi4", cv::Scalar(255, 165, 0)},
133};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700134
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700135const auto TargetMapperReplay::kFixedTargetMapper = TargetMapper(
136 absl::GetFlag(FLAGS_json_path), ceres::examples::VectorOfConstraints{});
milind-u2ab4db12023-03-25 21:59:23 -0700137
138Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
139 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
140 const Eigen::Affine3d H_robot_camera = extrinsics;
141 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
142 return H_robot_target;
143}
144
145TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
146 : reader_(reader),
147 timestamped_target_detections_(),
milind-u2ab4db12023-03-25 21:59:23 -0700148 vis_robot_(cv::Size(1280, 1000)),
149 drawn_nodes_(),
150 display_count_(0),
milind-u8cc03da2023-03-25 23:00:39 -0700151 last_draw_time_(aos::distributed_clock::min_time),
152 last_H_world_robot_(Eigen::Matrix4d::Identity()),
153 max_delta_T_world_robot_(0.0) {
milind-u2ab4db12023-03-25 21:59:23 -0700154 constexpr size_t kNumPis = 4;
milind-u8b0f4782023-04-15 13:59:29 -0700155 // TODO(milind): add a flag to support replaying april detection from full
156 // logs as well.
milind-u2ab4db12023-03-25 21:59:23 -0700157 for (size_t i = 1; i <= kNumPis; i++) {
milind-u2ab4db12023-03-25 21:59:23 -0700158 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
159 "y2023.Constants");
160 }
161
162 reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants");
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800163 reader_->RemapLoggedChannel("/logger/constants", "y2023.Constants");
164 reader_->RemapLoggedChannel("/roborio/constants", "y2023.Constants");
milind-u2ab4db12023-03-25 21:59:23 -0700165
166 reader_->Register();
167
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700168 SendSimulationConstants(reader_->event_loop_factory(),
169 absl::GetFlag(FLAGS_team_number),
170 absl::GetFlag(FLAGS_constants_path));
milind-u2ab4db12023-03-25 21:59:23 -0700171
172 for (size_t i = 1; i < kNumPis; i++) {
173 std::string node_name = "pi" + std::to_string(i);
174 const aos::Node *pi =
175 aos::configuration::GetNode(reader_->configuration(), node_name);
milind-u2ab4db12023-03-25 21:59:23 -0700176 mapping_event_loops_.emplace_back(
177 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
178 pi));
179 HandlePiCaptures(
milind-u2ab4db12023-03-25 21:59:23 -0700180 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
181 }
182
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700183 if (!absl::GetFlag(FLAGS_mcap_output_path).empty()) {
184 LOG(INFO) << "Writing out mcap file to "
185 << absl::GetFlag(FLAGS_mcap_output_path);
186 const aos::Node *node = aos::configuration::GetNode(
187 reader_->configuration(), absl::GetFlag(FLAGS_pi));
milind-u2ab4db12023-03-25 21:59:23 -0700188 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
189 [this, node]() {
190 mcap_event_loop_ =
191 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
192 relogger_ = std::make_unique<aos::McapLogger>(
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700193 mcap_event_loop_.get(), absl::GetFlag(FLAGS_mcap_output_path),
milind-u2ab4db12023-03-25 21:59:23 -0700194 aos::McapLogger::Serialization::kFlatbuffer,
195 aos::McapLogger::CanonicalChannelNames::kShortened,
196 aos::McapLogger::Compression::kLz4);
197 });
198 }
199
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700200 if (absl::GetFlag(FLAGS_visualize_solver)) {
milind-u2ab4db12023-03-25 21:59:23 -0700201 vis_robot_.ClearImage();
202 const double kFocalLength = 500.0;
203 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
204 }
205}
206
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800207// Add detected apriltag poses relative to the robot to
208// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700209void TargetMapperReplay::HandleAprilTags(
210 const TargetMap &map,
211 aos::distributed_clock::time_point pi_distributed_time,
212 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700213 bool drew = false;
214 std::stringstream label;
215 label << node_name << " - ";
216
milind-u3f5f83c2023-01-29 15:23:51 -0800217 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700218 // Skip detections with invalid ids
milind-u8f4e43e2023-04-09 17:11:19 -0700219 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700220 absl::GetFlag(FLAGS_min_target_id) ||
milind-u8f4e43e2023-04-09 17:11:19 -0700221 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700222 absl::GetFlag(FLAGS_max_target_id)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700223 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
milind-ufbc5c812023-04-06 21:24:29 -0700224 continue;
225 }
226
milind-u5ddd5152023-03-04 15:19:17 -0800227 // Skip detections with high pose errors
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700228 if (target_pose_fbs->pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700229 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700230 << " due to pose error of " << target_pose_fbs->pose_error();
231 continue;
232 }
233 // Skip detections with high pose error ratios
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700234 if (target_pose_fbs->pose_error_ratio() >
235 absl::GetFlag(FLAGS_max_pose_error_ratio)) {
milind-u8f4e43e2023-04-09 17:11:19 -0700236 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700237 << " due to pose error ratio of "
238 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800239 continue;
240 }
241
milind-u3f5f83c2023-01-29 15:23:51 -0800242 const TargetMapper::TargetPose target_pose =
Jim Ostrowski6d242d52024-04-03 20:39:03 -0700243 TargetMapper::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800244
milind-uee67abd2023-02-23 18:26:55 -0800245 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800246 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800247 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800248 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800249
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800250 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800251 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800252 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800253 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800254
milind-u09fb1252023-01-28 19:21:41 -0800255 CHECK(map.has_monotonic_timestamp_ns())
256 << "Need detection timestamps for mapping";
257
milind-u2ab4db12023-03-25 21:59:23 -0700258 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800259 DataAdapter::TimestampedDetection{
260 .time = pi_distributed_time,
261 .H_robot_target = H_robot_target,
262 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800263 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800264 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700265
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700266 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700267 // If we've already drawn this node_name in the current image,
268 // display the image before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700269 if (drawn_nodes_.count(node_name) != 0) {
270 display_count_++;
271 cv::putText(vis_robot_.image_,
272 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700273 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
274 cv::Scalar(255, 255, 255));
275
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700276 if (display_count_ >= absl::GetFlag(FLAGS_skip_to)) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700277 VLOG(1) << "Showing image for node " << node_name
278 << " since we've drawn it already";
milind-u2ab4db12023-03-25 21:59:23 -0700279 cv::imshow("View", vis_robot_.image_);
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700280 // Pause if delta_T is too large, but only after first image (to make
281 // sure the delta's are correct
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700282 if (max_delta_T_world_robot_ >
283 absl::GetFlag(FLAGS_pause_on_distance) &&
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700284 display_count_ > 1) {
285 LOG(INFO) << "Pausing since the delta between robot estimates is "
286 << max_delta_T_world_robot_ << " which is > threshold of "
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700287 << absl::GetFlag(FLAGS_pause_on_distance);
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700288 cv::waitKey(0);
289 } else {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700290 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700291 }
milind-u8cc03da2023-03-25 23:00:39 -0700292 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700293 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700294 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700295 }
milind-u2ab4db12023-03-25 21:59:23 -0700296 vis_robot_.ClearImage();
297 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700298 }
299
Jim Ostrowski49be8232023-03-23 01:00:14 -0700300 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700301 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700302 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700303 VLOG(2) << node_name << ", id " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700304 << ", t = " << pi_distributed_time
305 << ", pose_error = " << target_pose_fbs->pose_error()
306 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700307 << ", robot_pos (x,y,z) = "
milind-ude9045f2023-03-25 18:17:12 -0700308 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700309
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700310 label << "id " << target_pose_fbs->id() << ": err (% of max): "
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700311 << (target_pose_fbs->pose_error() /
312 absl::GetFlag(FLAGS_max_pose_error))
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700313 << " err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700314
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700315 vis_robot_.DrawRobotOutline(H_world_robot, node_name,
milind-ua30a4a12023-03-24 20:49:41 -0700316 kPiColors.at(node_name));
milind-u2ab4db12023-03-25 21:59:23 -0700317 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700318 std::to_string(target_pose_fbs->id()),
319 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700320
321 double delta_T_world_robot =
322 (H_world_robot.translation() - last_H_world_robot_.translation())
323 .norm();
324 max_delta_T_world_robot_ =
325 std::max(delta_T_world_robot, max_delta_T_world_robot_);
326
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700327 VLOG(1) << "Drew in info for robot " << node_name << " and target #"
328 << target_pose_fbs->id();
milind-ua30a4a12023-03-24 20:49:41 -0700329 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700330 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700331 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700332 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800333 }
milind-ua30a4a12023-03-24 20:49:41 -0700334
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700335 if (absl::GetFlag(FLAGS_visualize_solver)) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700336 if (drew) {
337 // Collect all the labels from a given node, and add the text
338 size_t pi_number =
339 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
340 cv::putText(vis_robot_.image_, label.str(),
341 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN,
342 1.0, kPiColors.at(node_name));
343
344 drawn_nodes_.emplace(node_name);
345 } else if (pi_distributed_time - last_draw_time_ >
346 std::chrono::milliseconds(30) &&
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700347 display_count_ >= absl::GetFlag(FLAGS_skip_to)) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700348 cv::putText(vis_robot_.image_, "No detections", cv::Point(10, 0),
349 cv::FONT_HERSHEY_PLAIN, 1.0, kPiColors.at(node_name));
350 // Display and clear the image if we haven't draw in a while
351 VLOG(1) << "Displaying image due to time lapse";
352 cv::imshow("View", vis_robot_.image_);
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700353 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700354 vis_robot_.ClearImage();
355 max_delta_T_world_robot_ = 0.0;
356 drawn_nodes_.clear();
357 }
milind-ua30a4a12023-03-24 20:49:41 -0700358 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800359}
360
milind-u8b0f4782023-04-15 13:59:29 -0700361void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) {
milind-uf2a4e322023-02-01 19:33:10 -0800362 // Get the camera extrinsics
milind-u8b0f4782023-04-15 13:59:29 -0700363 const frc971::constants::ConstantsFetcher<Constants> constants(
364 mapping_event_loop);
365 const auto *calibration = FindCameraCalibration(
366 constants.constants(), mapping_event_loop->node()->name()->string_view());
367 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
milind-uf2a4e322023-02-01 19:33:10 -0800368 Eigen::Matrix4d extrinsics_matrix;
369 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
370 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
371
Austin Schuh612d95d2023-10-21 00:01:40 -0700372 mapping_event_loop->MakeWatcher(
373 "/camera", [this, mapping_event_loop, extrinsics](const TargetMap &map) {
374 aos::distributed_clock::time_point pi_distributed_time =
375 reader_->event_loop_factory()
376 ->GetNodeEventLoopFactory(mapping_event_loop->node())
377 ->ToDistributedClock(aos::monotonic_clock::time_point(
378 aos::monotonic_clock::duration(
379 map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800380
Austin Schuh612d95d2023-10-21 00:01:40 -0700381 std::string node_name = mapping_event_loop->node()->name()->str();
382 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
383 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800384}
385
milind-u2ab4db12023-03-25 21:59:23 -0700386void TargetMapperReplay::MaybeSolve() {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700387 if (absl::GetFlag(FLAGS_solve)) {
milind-u2ab4db12023-03-25 21:59:23 -0700388 auto target_constraints =
389 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
390
milind-ufbc5c812023-04-06 21:24:29 -0700391 // Remove constraints between the two sides of the field - these are
392 // basically garbage because of how far the camera is. We will use seeding
393 // below to connect the two sides
394 target_constraints.erase(
395 std::remove_if(target_constraints.begin(), target_constraints.end(),
396 [](const auto &constraint) {
397 constexpr TargetMapper::TargetId kMaxRedId = 4;
398 TargetMapper::TargetId min_id =
399 std::min(constraint.id_begin, constraint.id_end);
400 TargetMapper::TargetId max_id =
401 std::max(constraint.id_begin, constraint.id_end);
402 return (min_id <= kMaxRedId && max_id > kMaxRedId);
403 }),
404 target_constraints.end());
405
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700406 LOG(INFO) << "Solving for locations of tags with "
407 << target_constraints.size() << " constraints";
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700408 TargetMapper mapper(absl::GetFlag(FLAGS_json_path), target_constraints);
409 mapper.Solve(absl::GetFlag(FLAGS_field_name),
410 absl::GetFlag(FLAGS_output_dir));
milind-u401de982023-04-14 17:32:03 -0700411
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700412 if (!absl::GetFlag(FLAGS_dump_constraints_to).empty()) {
413 mapper.DumpConstraints(absl::GetFlag(FLAGS_dump_constraints_to));
milind-u401de982023-04-14 17:32:03 -0700414 }
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700415 if (!absl::GetFlag(FLAGS_dump_stats_to).empty()) {
416 mapper.DumpStats(absl::GetFlag(FLAGS_dump_stats_to));
milind-u401de982023-04-14 17:32:03 -0700417 }
milind-u2ab4db12023-03-25 21:59:23 -0700418 }
419}
420
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800421void MappingMain(int argc, char *argv[]) {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800422 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
423
milind-u4a5ef8a2023-03-05 14:10:23 -0800424 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700425 (absl::GetFlag(FLAGS_config).empty()
milind-u4a5ef8a2023-03-05 14:10:23 -0800426 ? std::nullopt
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700427 : std::make_optional(
428 aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config))));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800429
milind-u2ab4db12023-03-25 21:59:23 -0700430 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800431 aos::logger::LogReader reader(
Austin Schuhc1609732023-06-26 11:51:28 -0700432 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
milind-u4a5ef8a2023-03-05 14:10:23 -0800433 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800434
milind-u2ab4db12023-03-25 21:59:23 -0700435 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800436 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700437 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800438}
439
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800440} // namespace y2023::vision
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800441
442int main(int argc, char **argv) {
443 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800444 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800445}