blob: 18383af6f7c73b9539434b57c07632cc99cf0ced [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 Ostrowski49be8232023-03-23 01:00:14 -070018#include "frc971/vision/visualize_robot.h"
milind-uc5a494f2023-02-24 15:39:22 -080019#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080020#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080021#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080022
milind-u4a5ef8a2023-03-05 14:10:23 -080023DEFINE_string(config, "",
24 "If set, override the log's config file with this one.");
milind-uc5a494f2023-02-24 15:39:22 -080025DEFINE_string(constants_path, "y2023/constants/constants.json",
26 "Path to the constant file");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070027DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
28 "Write the target constraints to this path");
29DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
30 "Write the mapping stats to this path");
milind-uc5a494f2023-02-24 15:39:22 -080031DEFINE_string(field_name, "charged_up",
32 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070033DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
34 "Specify path for json with initial pose guesses.");
milind-u5ddd5152023-03-04 15:19:17 -080035DEFINE_double(max_pose_error, 1e-6,
36 "Throw out target poses with a higher pose error than this");
milind-ude9045f2023-03-25 18:17:12 -070037DEFINE_double(
38 max_pose_error_ratio, 0.4,
39 "Throw out target poses with a higher pose error ratio than this");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070040DEFINE_string(mcap_output_path, "", "Log to output.");
41DEFINE_string(output_dir, "y2023/vision/maps",
42 "Directory to write solved target map to");
milind-u8cc03da2023-03-25 23:00:39 -070043DEFINE_double(pause_on_distance, 1.0,
44 "Pause if two consecutive implied robot positions differ by more "
45 "than this many meters");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070046DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
milind-ude9045f2023-03-25 18:17:12 -070047DEFINE_uint64(skip_to, 1,
48 "Start at combined image of this number (1 is the first image)");
milind-ua30a4a12023-03-24 20:49:41 -070049DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070050DEFINE_int32(team_number, 0,
51 "Required: Use the calibration for a node with this team number");
52DEFINE_uint64(wait_key, 1,
53 "Time in ms to wait between images, if no click (0 to wait "
54 "indefinitely until click).");
55
milind-u8f4e43e2023-04-09 17:11:19 -070056DECLARE_int32(frozen_target_id);
57DECLARE_int32(min_target_id);
58DECLARE_int32(max_target_id);
59DECLARE_bool(visualize_solver);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080060
milind-u16e3a082023-01-21 13:53:43 -080061namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080062namespace vision {
63using 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
milind-u2ab4db12023-03-25 21:59:23 -0700135const auto TargetMapperReplay::kFixedTargetMapper =
136 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
137
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");
163
164 reader_->Register();
165
166 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
167 FLAGS_constants_path);
168
169 for (size_t i = 1; i < kNumPis; i++) {
170 std::string node_name = "pi" + std::to_string(i);
171 const aos::Node *pi =
172 aos::configuration::GetNode(reader_->configuration(), node_name);
milind-u2ab4db12023-03-25 21:59:23 -0700173 mapping_event_loops_.emplace_back(
174 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
175 pi));
176 HandlePiCaptures(
milind-u2ab4db12023-03-25 21:59:23 -0700177 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
178 }
179
180 if (!FLAGS_mcap_output_path.empty()) {
181 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
182 const aos::Node *node =
183 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
184 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
185 [this, node]() {
186 mcap_event_loop_ =
187 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
188 relogger_ = std::make_unique<aos::McapLogger>(
189 mcap_event_loop_.get(), FLAGS_mcap_output_path,
190 aos::McapLogger::Serialization::kFlatbuffer,
191 aos::McapLogger::CanonicalChannelNames::kShortened,
192 aos::McapLogger::Compression::kLz4);
193 });
194 }
195
milind-u8f4e43e2023-04-09 17:11:19 -0700196 if (FLAGS_visualize_solver) {
milind-u2ab4db12023-03-25 21:59:23 -0700197 vis_robot_.ClearImage();
198 const double kFocalLength = 500.0;
199 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
200 }
201}
202
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800203// Add detected apriltag poses relative to the robot to
204// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700205void TargetMapperReplay::HandleAprilTags(
206 const TargetMap &map,
207 aos::distributed_clock::time_point pi_distributed_time,
208 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700209 bool drew = false;
210 std::stringstream label;
211 label << node_name << " - ";
212
milind-u3f5f83c2023-01-29 15:23:51 -0800213 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700214 // Skip detections with invalid ids
milind-u8f4e43e2023-04-09 17:11:19 -0700215 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
216 FLAGS_min_target_id ||
217 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
218 FLAGS_max_target_id) {
219 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
milind-ufbc5c812023-04-06 21:24:29 -0700220 continue;
221 }
222
milind-u5ddd5152023-03-04 15:19:17 -0800223 // Skip detections with high pose errors
224 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-u8f4e43e2023-04-09 17:11:19 -0700225 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700226 << " due to pose error of " << target_pose_fbs->pose_error();
227 continue;
228 }
229 // Skip detections with high pose error ratios
230 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
milind-u8f4e43e2023-04-09 17:11:19 -0700231 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700232 << " due to pose error ratio of "
233 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800234 continue;
235 }
236
milind-u3f5f83c2023-01-29 15:23:51 -0800237 const TargetMapper::TargetPose target_pose =
238 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800239
milind-uee67abd2023-02-23 18:26:55 -0800240 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800241 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800242 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800243 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800244
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800245 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800246 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800247 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800248 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800249
milind-u09fb1252023-01-28 19:21:41 -0800250 CHECK(map.has_monotonic_timestamp_ns())
251 << "Need detection timestamps for mapping";
252
milind-u2ab4db12023-03-25 21:59:23 -0700253 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800254 DataAdapter::TimestampedDetection{
255 .time = pi_distributed_time,
256 .H_robot_target = H_robot_target,
257 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800258 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800259 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700260
milind-u8f4e43e2023-04-09 17:11:19 -0700261 if (FLAGS_visualize_solver) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700262 // If we've already drawn this node_name in the current image,
263 // display the image before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700264 if (drawn_nodes_.count(node_name) != 0) {
265 display_count_++;
266 cv::putText(vis_robot_.image_,
267 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700268 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
269 cv::Scalar(255, 255, 255));
270
milind-u2ab4db12023-03-25 21:59:23 -0700271 if (display_count_ >= FLAGS_skip_to) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700272 VLOG(1) << "Showing image for node " << node_name
273 << " since we've drawn it already";
milind-u2ab4db12023-03-25 21:59:23 -0700274 cv::imshow("View", vis_robot_.image_);
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700275 // Pause if delta_T is too large, but only after first image (to make
276 // sure the delta's are correct
277 if (max_delta_T_world_robot_ > FLAGS_pause_on_distance &&
278 display_count_ > 1) {
279 LOG(INFO) << "Pausing since the delta between robot estimates is "
280 << max_delta_T_world_robot_ << " which is > threshold of "
281 << FLAGS_pause_on_distance;
282 cv::waitKey(0);
283 } else {
284 cv::waitKey(FLAGS_wait_key);
285 }
milind-u8cc03da2023-03-25 23:00:39 -0700286 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700287 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700288 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700289 }
milind-u2ab4db12023-03-25 21:59:23 -0700290 vis_robot_.ClearImage();
291 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700292 }
293
Jim Ostrowski49be8232023-03-23 01:00:14 -0700294 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700295 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700296 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700297 VLOG(2) << node_name << ", id " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700298 << ", t = " << pi_distributed_time
299 << ", pose_error = " << target_pose_fbs->pose_error()
300 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700301 << ", robot_pos (x,y,z) = "
milind-ude9045f2023-03-25 18:17:12 -0700302 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700303
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700304 label << "id " << target_pose_fbs->id() << ": err (% of max): "
milind-ude9045f2023-03-25 18:17:12 -0700305 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700306 << " err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700307
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700308 vis_robot_.DrawRobotOutline(H_world_robot, node_name,
milind-ua30a4a12023-03-24 20:49:41 -0700309 kPiColors.at(node_name));
milind-u2ab4db12023-03-25 21:59:23 -0700310 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700311 std::to_string(target_pose_fbs->id()),
312 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700313
314 double delta_T_world_robot =
315 (H_world_robot.translation() - last_H_world_robot_.translation())
316 .norm();
317 max_delta_T_world_robot_ =
318 std::max(delta_T_world_robot, max_delta_T_world_robot_);
319
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700320 VLOG(1) << "Drew in info for robot " << node_name << " and target #"
321 << target_pose_fbs->id();
milind-ua30a4a12023-03-24 20:49:41 -0700322 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700323 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700324 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700325 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800326 }
milind-ua30a4a12023-03-24 20:49:41 -0700327
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700328 if (FLAGS_visualize_solver) {
329 if (drew) {
330 // Collect all the labels from a given node, and add the text
331 size_t pi_number =
332 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
333 cv::putText(vis_robot_.image_, label.str(),
334 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN,
335 1.0, kPiColors.at(node_name));
336
337 drawn_nodes_.emplace(node_name);
338 } else if (pi_distributed_time - last_draw_time_ >
339 std::chrono::milliseconds(30) &&
340 display_count_ >= FLAGS_skip_to) {
341 cv::putText(vis_robot_.image_, "No detections", cv::Point(10, 0),
342 cv::FONT_HERSHEY_PLAIN, 1.0, kPiColors.at(node_name));
343 // Display and clear the image if we haven't draw in a while
344 VLOG(1) << "Displaying image due to time lapse";
345 cv::imshow("View", vis_robot_.image_);
346 cv::waitKey(FLAGS_wait_key);
347 vis_robot_.ClearImage();
348 max_delta_T_world_robot_ = 0.0;
349 drawn_nodes_.clear();
350 }
milind-ua30a4a12023-03-24 20:49:41 -0700351 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800352}
353
milind-u8b0f4782023-04-15 13:59:29 -0700354void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) {
milind-uf2a4e322023-02-01 19:33:10 -0800355 // Get the camera extrinsics
milind-u8b0f4782023-04-15 13:59:29 -0700356 const frc971::constants::ConstantsFetcher<Constants> constants(
357 mapping_event_loop);
358 const auto *calibration = FindCameraCalibration(
359 constants.constants(), mapping_event_loop->node()->name()->string_view());
360 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
milind-uf2a4e322023-02-01 19:33:10 -0800361 Eigen::Matrix4d extrinsics_matrix;
362 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
363 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
364
Austin Schuh612d95d2023-10-21 00:01:40 -0700365 mapping_event_loop->MakeWatcher(
366 "/camera", [this, mapping_event_loop, extrinsics](const TargetMap &map) {
367 aos::distributed_clock::time_point pi_distributed_time =
368 reader_->event_loop_factory()
369 ->GetNodeEventLoopFactory(mapping_event_loop->node())
370 ->ToDistributedClock(aos::monotonic_clock::time_point(
371 aos::monotonic_clock::duration(
372 map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800373
Austin Schuh612d95d2023-10-21 00:01:40 -0700374 std::string node_name = mapping_event_loop->node()->name()->str();
375 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
376 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800377}
378
milind-u2ab4db12023-03-25 21:59:23 -0700379void TargetMapperReplay::MaybeSolve() {
380 if (FLAGS_solve) {
381 auto target_constraints =
382 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
383
milind-ufbc5c812023-04-06 21:24:29 -0700384 // Remove constraints between the two sides of the field - these are
385 // basically garbage because of how far the camera is. We will use seeding
386 // below to connect the two sides
387 target_constraints.erase(
388 std::remove_if(target_constraints.begin(), target_constraints.end(),
389 [](const auto &constraint) {
390 constexpr TargetMapper::TargetId kMaxRedId = 4;
391 TargetMapper::TargetId min_id =
392 std::min(constraint.id_begin, constraint.id_end);
393 TargetMapper::TargetId max_id =
394 std::max(constraint.id_begin, constraint.id_end);
395 return (min_id <= kMaxRedId && max_id > kMaxRedId);
396 }),
397 target_constraints.end());
398
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700399 LOG(INFO) << "Solving for locations of tags with "
400 << target_constraints.size() << " constraints";
milind-u2ab4db12023-03-25 21:59:23 -0700401 TargetMapper mapper(FLAGS_json_path, target_constraints);
402 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
milind-u401de982023-04-14 17:32:03 -0700403
404 if (!FLAGS_dump_constraints_to.empty()) {
405 mapper.DumpConstraints(FLAGS_dump_constraints_to);
406 }
407 if (!FLAGS_dump_stats_to.empty()) {
408 mapper.DumpStats(FLAGS_dump_stats_to);
409 }
milind-u2ab4db12023-03-25 21:59:23 -0700410 }
411}
412
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800413void MappingMain(int argc, char *argv[]) {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800414 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
415
milind-u4a5ef8a2023-03-05 14:10:23 -0800416 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
417 (FLAGS_config.empty()
418 ? std::nullopt
419 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800420
milind-u2ab4db12023-03-25 21:59:23 -0700421 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800422 aos::logger::LogReader reader(
Austin Schuhc1609732023-06-26 11:51:28 -0700423 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
milind-u4a5ef8a2023-03-05 14:10:23 -0800424 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800425
milind-u2ab4db12023-03-25 21:59:23 -0700426 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800427 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700428 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800429}
430
431} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800432} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800433
434int main(int argc, char **argv) {
435 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800436 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800437}