blob: 804583c0fdea71e47132fe8607e878867c5845b8 [file] [log] [blame]
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -08001#include "aos/configuration.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08002#include "aos/events/logging/log_reader.h"
3#include "aos/events/simulated_event_loop.h"
4#include "aos/init.h"
Jim Ostrowski68965cd2023-03-01 20:32:51 -08005#include "aos/util/mcap_logger.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08006#include "frc971/control_loops/pose.h"
milind-u16e3a082023-01-21 13:53:43 -08007#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08008#include "frc971/vision/target_mapper.h"
Jim Ostrowski49be8232023-03-23 01:00:14 -07009#include "frc971/vision/visualize_robot.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080010#include "opencv2/aruco.hpp"
11#include "opencv2/calib3d.hpp"
12#include "opencv2/core/eigen.hpp"
13#include "opencv2/features2d.hpp"
14#include "opencv2/highgui.hpp"
15#include "opencv2/highgui/highgui.hpp"
16#include "opencv2/imgproc.hpp"
milind-uc5a494f2023-02-24 15:39:22 -080017#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080018#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080019#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080020
milind-uc5a494f2023-02-24 15:39:22 -080021DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080022 "Specify path for json with initial pose guesses.");
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");
27DEFINE_string(output_dir, "y2023/vision/maps",
28 "Directory to write solved target map to");
29DEFINE_string(field_name, "charged_up",
30 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski49be8232023-03-23 01:00:14 -070031DEFINE_int32(team_number, 0,
32 "Required: Use the calibration for a node with this team number");
Jim Ostrowski68965cd2023-03-01 20:32:51 -080033DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output.");
34DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
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");
milind-ua30a4a12023-03-24 20:49:41 -070040DEFINE_uint64(wait_key, 0,
41 "Time in ms to wait between images, if no click (0 to wait "
42 "indefinitely until click).");
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");
milind-ude9045f2023-03-25 18:17:12 -070046DEFINE_uint64(skip_to, 1,
47 "Start at combined image of this number (1 is the first image)");
milind-ua30a4a12023-03-24 20:49:41 -070048DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
milind-u401de982023-04-14 17:32:03 -070049DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
50 "Write the target constraints to this path");
51DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
milind-ufbc5c812023-04-06 21:24:29 -070052 "Write the target constraints to this path");
milind-u8f4e43e2023-04-09 17:11:19 -070053DECLARE_int32(frozen_target_id);
54DECLARE_int32(min_target_id);
55DECLARE_int32(max_target_id);
56DECLARE_bool(visualize_solver);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080057
milind-u16e3a082023-01-21 13:53:43 -080058namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080059namespace vision {
60using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080061using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080062using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080063using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080064using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070065using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080066namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080067
milind-u2ab4db12023-03-25 21:59:23 -070068// Class to handle reading target poses from a replayed log,
69// displaying various debug info, and passing the poses to
70// frc971::vision::TargetMapper for field mapping.
71class TargetMapperReplay {
72 public:
73 TargetMapperReplay(aos::logger::LogReader *reader);
74 ~TargetMapperReplay();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080075
milind-u2ab4db12023-03-25 21:59:23 -070076 // Solves for the target poses with the accumulated detections if FLAGS_solve.
77 void MaybeSolve();
78
79 private:
80 static constexpr int kImageWidth = 1280;
81 // Map from pi node name to color for drawing
82 static const std::map<std::string, cv::Scalar> kPiColors;
83 // Contains fixed target poses without solving, for use with visualization
84 static const TargetMapper kFixedTargetMapper;
85
86 // Change reference frame from camera to robot
87 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
88 Eigen::Affine3d extrinsics);
89
90 // Adds april tag detections into the detection list, and handles
91 // visualization
92 void HandleAprilTags(const TargetMap &map,
93 aos::distributed_clock::time_point pi_distributed_time,
94 std::string node_name, Eigen::Affine3d extrinsics);
95
96 // Gets images from the given pi and passes apriltag positions to
97 // HandleAprilTags()
milind-u8b0f4782023-04-15 13:59:29 -070098 void HandlePiCaptures(aos::EventLoop *mapping_event_loop);
milind-u2ab4db12023-03-25 21:59:23 -070099
100 aos::logger::LogReader *reader_;
101 // April tag detections from all pis
102 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
103 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_;
104
105 VisualizeRobot vis_robot_;
106 // Set of node names which are currently drawn on the display
107 std::set<std::string> drawn_nodes_;
108 // Number of frames displayed
109 size_t display_count_;
110 // Last time we drew onto the display image.
111 // This is different from when we actually call imshow() to update
112 // the display window
113 aos::distributed_clock::time_point last_draw_time_;
114
milind-u8cc03da2023-03-25 23:00:39 -0700115 Eigen::Affine3d last_H_world_robot_;
116 // Maximum distance between consecutive T_world_robot's in one display frame,
117 // used to determine if we need to pause for the user to see this frame
118 // clearly
119 double max_delta_T_world_robot_;
120
milind-u2ab4db12023-03-25 21:59:23 -0700121 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
122
123 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
124 std::unique_ptr<aos::McapLogger> relogger_;
125};
126
127const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700128 {"pi1", cv::Scalar(255, 0, 255)},
129 {"pi2", cv::Scalar(255, 255, 0)},
130 {"pi3", cv::Scalar(0, 255, 255)},
131 {"pi4", cv::Scalar(255, 165, 0)},
132};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700133
milind-u2ab4db12023-03-25 21:59:23 -0700134const auto TargetMapperReplay::kFixedTargetMapper =
135 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
136
137Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
138 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
139 const Eigen::Affine3d H_robot_camera = extrinsics;
140 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
141 return H_robot_target;
142}
143
144TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
145 : reader_(reader),
146 timestamped_target_detections_(),
147 detectors_(),
148 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
203TargetMapperReplay::~TargetMapperReplay() {
204 // Clean up all the pointers
205 for (auto &detector_ptr : detectors_) {
206 detector_ptr.reset();
207 }
208}
209
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800210// Add detected apriltag poses relative to the robot to
211// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700212void TargetMapperReplay::HandleAprilTags(
213 const TargetMap &map,
214 aos::distributed_clock::time_point pi_distributed_time,
215 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700216 bool drew = false;
217 std::stringstream label;
218 label << node_name << " - ";
219
milind-u3f5f83c2023-01-29 15:23:51 -0800220 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700221 // Skip detections with invalid ids
milind-u8f4e43e2023-04-09 17:11:19 -0700222 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
223 FLAGS_min_target_id ||
224 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
225 FLAGS_max_target_id) {
226 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
milind-ufbc5c812023-04-06 21:24:29 -0700227 continue;
228 }
229
milind-u5ddd5152023-03-04 15:19:17 -0800230 // Skip detections with high pose errors
231 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-u8f4e43e2023-04-09 17:11:19 -0700232 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700233 << " due to pose error of " << target_pose_fbs->pose_error();
234 continue;
235 }
236 // Skip detections with high pose error ratios
237 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
milind-u8f4e43e2023-04-09 17:11:19 -0700238 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700239 << " due to pose error ratio of "
240 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800241 continue;
242 }
243
milind-u3f5f83c2023-01-29 15:23:51 -0800244 const TargetMapper::TargetPose target_pose =
245 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800246
milind-uee67abd2023-02-23 18:26:55 -0800247 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800248 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800249 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800250 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800251
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800252 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800253 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800254 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800255 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800256
milind-u09fb1252023-01-28 19:21:41 -0800257 CHECK(map.has_monotonic_timestamp_ns())
258 << "Need detection timestamps for mapping";
259
milind-u2ab4db12023-03-25 21:59:23 -0700260 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800261 DataAdapter::TimestampedDetection{
262 .time = pi_distributed_time,
263 .H_robot_target = H_robot_target,
264 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800265 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800266 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700267
milind-u8f4e43e2023-04-09 17:11:19 -0700268 if (FLAGS_visualize_solver) {
milind-ua30a4a12023-03-24 20:49:41 -0700269 // If we've already drawn in the current image,
270 // display it before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700271 if (drawn_nodes_.count(node_name) != 0) {
272 display_count_++;
273 cv::putText(vis_robot_.image_,
274 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700275 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
276 cv::Scalar(255, 255, 255));
277
milind-u2ab4db12023-03-25 21:59:23 -0700278 if (display_count_ >= FLAGS_skip_to) {
279 cv::imshow("View", vis_robot_.image_);
milind-u8cc03da2023-03-25 23:00:39 -0700280 cv::waitKey(max_delta_T_world_robot_ > FLAGS_pause_on_distance
281 ? 0
282 : FLAGS_wait_key);
283 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700284 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700285 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700286 }
milind-u2ab4db12023-03-25 21:59:23 -0700287 vis_robot_.ClearImage();
288 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700289 }
290
Jim Ostrowski49be8232023-03-23 01:00:14 -0700291 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700292 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700293 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700294 VLOG(2) << node_name << ", " << target_pose_fbs->id()
295 << ", t = " << pi_distributed_time
296 << ", pose_error = " << target_pose_fbs->pose_error()
297 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
298 << ", robot_pos (x,y,z) + "
299 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700300
301 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700302 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
303 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700304
milind-u2ab4db12023-03-25 21:59:23 -0700305 vis_robot_.DrawRobotOutline(H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -0700306 std::to_string(target_pose_fbs->id()),
307 kPiColors.at(node_name));
308
milind-u2ab4db12023-03-25 21:59:23 -0700309 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700310 std::to_string(target_pose_fbs->id()),
311 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700312
313 double delta_T_world_robot =
314 (H_world_robot.translation() - last_H_world_robot_.translation())
315 .norm();
316 max_delta_T_world_robot_ =
317 std::max(delta_T_world_robot, max_delta_T_world_robot_);
318
milind-ua30a4a12023-03-24 20:49:41 -0700319 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700320 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700321 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700322 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800323 }
milind-ua30a4a12023-03-24 20:49:41 -0700324 if (drew) {
325 size_t pi_number =
326 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
milind-u2ab4db12023-03-25 21:59:23 -0700327 cv::putText(vis_robot_.image_, label.str(),
milind-ua30a4a12023-03-24 20:49:41 -0700328 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
329 kPiColors.at(node_name));
330
milind-u2ab4db12023-03-25 21:59:23 -0700331 drawn_nodes_.emplace(node_name);
332 } else if (pi_distributed_time - last_draw_time_ >
milind-u52db3362023-03-25 20:09:22 -0700333 std::chrono::milliseconds(30) &&
milind-u2ab4db12023-03-25 21:59:23 -0700334 display_count_ >= FLAGS_skip_to) {
milind-u52db3362023-03-25 20:09:22 -0700335 // Clear the image if we haven't draw in a while
milind-u2ab4db12023-03-25 21:59:23 -0700336 vis_robot_.ClearImage();
337 cv::imshow("View", vis_robot_.image_);
milind-u52db3362023-03-25 20:09:22 -0700338 cv::waitKey(FLAGS_wait_key);
milind-u8cc03da2023-03-25 23:00:39 -0700339 max_delta_T_world_robot_ = 0.0;
milind-ua30a4a12023-03-24 20:49:41 -0700340 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800341}
342
milind-u8b0f4782023-04-15 13:59:29 -0700343void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) {
milind-uf2a4e322023-02-01 19:33:10 -0800344 // Get the camera extrinsics
milind-u8b0f4782023-04-15 13:59:29 -0700345 const frc971::constants::ConstantsFetcher<Constants> constants(
346 mapping_event_loop);
347 const auto *calibration = FindCameraCalibration(
348 constants.constants(), mapping_event_loop->node()->name()->string_view());
349 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
milind-uf2a4e322023-02-01 19:33:10 -0800350 Eigen::Matrix4d extrinsics_matrix;
351 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
352 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
353
milind-uf3ab8ba2023-02-04 17:56:16 -0800354 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800355 aos::distributed_clock::time_point pi_distributed_time =
milind-u2ab4db12023-03-25 21:59:23 -0700356 reader_->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800357 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800358 ->ToDistributedClock(aos::monotonic_clock::time_point(
359 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800360
milind-u8b0f4782023-04-15 13:59:29 -0700361 std::string node_name = mapping_event_loop->node()->name()->str();
milind-u2ab4db12023-03-25 21:59:23 -0700362 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
milind-u09fb1252023-01-28 19:21:41 -0800363 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800364}
365
milind-u2ab4db12023-03-25 21:59:23 -0700366void TargetMapperReplay::MaybeSolve() {
367 if (FLAGS_solve) {
368 auto target_constraints =
369 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
370
milind-ufbc5c812023-04-06 21:24:29 -0700371 // Remove constraints between the two sides of the field - these are
372 // basically garbage because of how far the camera is. We will use seeding
373 // below to connect the two sides
374 target_constraints.erase(
375 std::remove_if(target_constraints.begin(), target_constraints.end(),
376 [](const auto &constraint) {
377 constexpr TargetMapper::TargetId kMaxRedId = 4;
378 TargetMapper::TargetId min_id =
379 std::min(constraint.id_begin, constraint.id_end);
380 TargetMapper::TargetId max_id =
381 std::max(constraint.id_begin, constraint.id_end);
382 return (min_id <= kMaxRedId && max_id > kMaxRedId);
383 }),
384 target_constraints.end());
385
milind-u2ab4db12023-03-25 21:59:23 -0700386 TargetMapper mapper(FLAGS_json_path, target_constraints);
387 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
milind-u401de982023-04-14 17:32:03 -0700388
389 if (!FLAGS_dump_constraints_to.empty()) {
390 mapper.DumpConstraints(FLAGS_dump_constraints_to);
391 }
392 if (!FLAGS_dump_stats_to.empty()) {
393 mapper.DumpStats(FLAGS_dump_stats_to);
394 }
milind-u2ab4db12023-03-25 21:59:23 -0700395 }
396}
397
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800398void MappingMain(int argc, char *argv[]) {
399 std::vector<std::string> unsorted_logfiles =
400 aos::logger::FindLogs(argc, argv);
401
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800402 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
403
milind-u4a5ef8a2023-03-05 14:10:23 -0800404 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
405 (FLAGS_config.empty()
406 ? std::nullopt
407 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800408
milind-u2ab4db12023-03-25 21:59:23 -0700409 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800410 aos::logger::LogReader reader(
411 aos::logger::SortParts(unsorted_logfiles),
412 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800413
milind-u2ab4db12023-03-25 21:59:23 -0700414 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800415 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700416 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800417}
418
419} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800420} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800421
422int main(int argc, char **argv) {
423 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800424 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800425}