blob: b8b1f6282b5e23a55d458c866ba186551a02f5de [file] [log] [blame]
Yash Maheshwarie0b25c52024-05-22 20:23:36 -07001#include <string>
2
3#include "Eigen/Dense"
Austin Schuh99f7c6a2024-06-25 22:07:44 -07004#include "absl/flags/flag.h"
Yash Maheshwarie0b25c52024-05-22 20:23:36 -07005#include "opencv2/aruco.hpp"
6#include "opencv2/calib3d.hpp"
7#include "opencv2/core/eigen.hpp"
8#include "opencv2/features2d.hpp"
9#include "opencv2/highgui.hpp"
10#include "opencv2/highgui/highgui.hpp"
11#include "opencv2/imgproc.hpp"
12
13#include "aos/configuration.h"
14#include "aos/events/logging/log_reader.h"
15#include "aos/events/simulated_event_loop.h"
16#include "aos/init.h"
17#include "aos/util/mcap_logger.h"
18#include "frc971/constants/constants_sender_lib.h"
19#include "frc971/control_loops/pose.h"
20#include "frc971/vision/calibration_generated.h"
21#include "frc971/vision/charuco_lib.h"
22#include "frc971/vision/target_mapper.h"
23#include "frc971/vision/vision_generated.h"
24#include "frc971/vision/vision_util_lib.h"
25#include "frc971/vision/visualize_robot.h"
26#include "y2024_swerve/constants/simulated_constants_sender.h"
27#include "y2024_swerve/vision/vision_util.h"
28
Austin Schuh99f7c6a2024-06-25 22:07:44 -070029ABSL_FLAG(std::string, config, "",
30 "If set, override the log's config file with this one.");
31ABSL_FLAG(std::string, constants_path, "y2024_swerve/constants/constants.json",
32 "Path to the constant file");
33ABSL_FLAG(std::string, dump_constraints_to, "/tmp/mapping_constraints.txt",
34 "Write the target constraints to this path");
35ABSL_FLAG(std::string, dump_stats_to, "/tmp/mapping_stats.txt",
36 "Write the mapping stats to this path");
37ABSL_FLAG(std::string, field_name, "crescendo",
38 "Field name, for the output json filename and flatbuffer field");
39ABSL_FLAG(std::string, json_path, "y2024_swerve/vision/maps/target_map.json",
40 "Specify path for json with initial pose guesses.");
41ABSL_FLAG(double, max_pose_error, 1e-6,
42 "Throw out target poses with a higher pose error than this");
43ABSL_FLAG(double, max_pose_error_ratio, 0.4,
44 "Throw out target poses with a higher pose error ratio than this");
45ABSL_FLAG(std::string, mcap_output_path, "", "Log to output.");
46ABSL_FLAG(std::string, output_dir, "y2024_swerve/vision/maps",
47 "Directory to write solved target map to");
48ABSL_FLAG(double, pause_on_distance, 2.0,
49 "Pause if two consecutive implied robot positions differ by more "
50 "than this many meters");
51ABSL_FLAG(std::string, orin, "orin1",
52 "Orin name to generate mcap log for; defaults to orin1.");
53ABSL_FLAG(uint64_t, skip_to, 1,
54 "Start at combined image of this number (1 is the first image)");
55ABSL_FLAG(bool, solve, true, "Whether to solve for the field's target map.");
56ABSL_FLAG(bool, split_field, false,
57 "Whether to break solve into two sides of field");
58ABSL_FLAG(int32_t, team_number, 0,
59 "Required: Use the calibration for a node with this team number");
60ABSL_FLAG(uint64_t, wait_key, 1,
61 "Time in ms to wait between images, if no click (0 to wait "
62 "indefinitely until click).");
Yash Maheshwarie0b25c52024-05-22 20:23:36 -070063
Austin Schuh99f7c6a2024-06-25 22:07:44 -070064ABSL_DECLARE_FLAG(int32_t, frozen_target_id);
65ABSL_DECLARE_FLAG(int32_t, min_target_id);
66ABSL_DECLARE_FLAG(int32_t, max_target_id);
67ABSL_DECLARE_FLAG(bool, visualize_solver);
Yash Maheshwarie0b25c52024-05-22 20:23:36 -070068
69namespace y2024_swerve::vision {
70using frc971::vision::DataAdapter;
71using frc971::vision::ImageCallback;
72using frc971::vision::PoseUtils;
73using frc971::vision::TargetMap;
74using frc971::vision::TargetMapper;
75using frc971::vision::VisualizeRobot;
76namespace calibration = frc971::vision::calibration;
77
78// Class to handle reading target poses from a replayed log,
79// displaying various debug info, and passing the poses to
80// frc971::vision::TargetMapper for field mapping.
81class TargetMapperReplay {
82 public:
83 TargetMapperReplay(aos::logger::LogReader *reader);
84
85 // Solves for the target poses with the accumulated detections if FLAGS_solve.
86 void MaybeSolve();
87
88 private:
89 static constexpr int kImageWidth = 1280;
90
91 // Contains fixed target poses without solving, for use with visualization
92 static const TargetMapper kFixedTargetMapper;
93
94 // Map of TargetId to alliance "color" for splitting field
95 static std::map<uint, std::string> kIdAllianceMap;
96
97 // Change reference frame from camera to robot
98 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
99 Eigen::Affine3d extrinsics);
100
101 // Adds april tag detections into the detection list, and handles
102 // visualization
103 void HandleAprilTags(const TargetMap &map,
104 aos::distributed_clock::time_point node_distributed_time,
105 std::string camera_name, Eigen::Affine3d extrinsics);
106 // Gets images from the given pi and passes apriltag positions to
107 // HandleAprilTags()
108 void HandleNodeCaptures(
109 aos::EventLoop *mapping_event_loop,
110 frc971::constants::ConstantsFetcher<y2024_swerve::Constants>
111 *constants_fetcher,
112 int camera_number);
113
114 aos::logger::LogReader *reader_;
115 // April tag detections from all pis
116 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
117
118 VisualizeRobot vis_robot_;
119 // Set of camera names which are currently drawn on the display
120 std::set<std::string> drawn_cameras_;
121 // Number of frames displayed
122 size_t display_count_;
123 // Last time we drew onto the display image.
124 // This is different from when we actually call imshow() to update
125 // the display window
126 aos::distributed_clock::time_point last_draw_time_;
127
128 Eigen::Affine3d last_H_world_robot_;
129 // Maximum distance between consecutive T_world_robot's in one display frame,
130 // used to determine if we need to pause for the user to see this frame
131 // clearly
132 double max_delta_T_world_robot_;
133 double ignore_count_;
134
135 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
136
137 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
138 std::unique_ptr<aos::McapLogger> relogger_;
139};
140
141std::vector<CameraNode> node_list(y2024_swerve::vision::CreateNodeList());
142
143std::map<std::string, int> camera_ordering_map(
144 y2024_swerve::vision::CreateOrderingMap(node_list));
145
146std::map<uint, std::string> TargetMapperReplay::kIdAllianceMap = {
147 {1, "red"}, {2, "red"}, {3, "red"}, {4, "red"},
148 {5, "red"}, {6, "blue"}, {7, "blue"}, {8, "blue"},
149 {9, "blue"}, {10, "blue"}, {11, "red"}, {12, "red"},
150 {13, "red"}, {14, "blue"}, {15, "blue"}, {16, "blue"}};
151
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700152const auto TargetMapperReplay::kFixedTargetMapper = TargetMapper(
153 absl::GetFlag(FLAGS_json_path), ceres::examples::VectorOfConstraints{});
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700154
155Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
156 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
157 const Eigen::Affine3d H_robot_camera = extrinsics;
158 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
159 return H_robot_target;
160}
161
162TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
163 : reader_(reader),
164 timestamped_target_detections_(),
165 vis_robot_(cv::Size(1280, 1000)),
166 drawn_cameras_(),
167 display_count_(0),
168 last_draw_time_(aos::distributed_clock::min_time),
169 last_H_world_robot_(Eigen::Matrix4d::Identity()),
170 max_delta_T_world_robot_(0.0) {
171 reader_->RemapLoggedChannel("/orin1/constants", "y2024_swerve.Constants");
172 reader_->RemapLoggedChannel("/imu/constants", "y2024_swerve.Constants");
173 // If it's Box of Orins, don't remap roborio constants
174 reader_->MaybeRemapLoggedChannel<Constants>("/roborio/constants");
175 reader_->Register();
176
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700177 SendSimulationConstants(reader_->event_loop_factory(),
178 absl::GetFlag(FLAGS_team_number),
179 absl::GetFlag(FLAGS_constants_path));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700180
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700181 if (absl::GetFlag(FLAGS_visualize_solver)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700182 vis_robot_.ClearImage();
183 // Set focal length to zoomed in, to view extrinsics
184 const double kFocalLength = 1500.0;
185 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
186 }
187
188 for (const CameraNode &camera_node : node_list) {
189 const aos::Node *node = aos::configuration::GetNode(
190 reader_->configuration(), camera_node.node_name.c_str());
191
192 mapping_event_loops_.emplace_back(
193 reader_->event_loop_factory()->MakeEventLoop(
194 camera_node.node_name + "mapping", node));
195
196 frc971::constants::ConstantsFetcher<y2024_swerve::Constants>
197 constants_fetcher(
198 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
199 HandleNodeCaptures(
200 mapping_event_loops_[mapping_event_loops_.size() - 1].get(),
201 &constants_fetcher, camera_node.camera_number);
202
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700203 if (absl::GetFlag(FLAGS_visualize_solver)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700204 // Show the extrinsics calibration to start, for reference to confirm
205 const auto *calibration = FindCameraCalibration(
206 constants_fetcher.constants(),
207 mapping_event_loops_.back()->node()->name()->string_view(),
208 camera_node.camera_number);
209 cv::Mat extrinsics_cv =
210 frc971::vision::CameraExtrinsics(calibration).value();
211 Eigen::Matrix4d extrinsics_matrix;
212 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
213 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
214
215 vis_robot_.DrawRobotOutline(extrinsics, camera_node.camera_name(),
216 kOrinColors.at(camera_node.camera_name()));
217 }
218 }
219
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700220 if (absl::GetFlag(FLAGS_visualize_solver)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700221 cv::imshow("Extrinsics", vis_robot_.image_);
222 cv::waitKey(0);
223 vis_robot_.ClearImage();
224 // Reset focal length to more zoomed out view for field
225 const double kFocalLength = 500.0;
226 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
227 }
228}
229
230// Add detected apriltag poses relative to the robot to
231// timestamped_target_detections
232void TargetMapperReplay::HandleAprilTags(
233 const TargetMap &map,
234 aos::distributed_clock::time_point node_distributed_time,
235 std::string camera_name, Eigen::Affine3d extrinsics) {
236 bool drew = false;
237 std::stringstream label;
238 label << camera_name << " - ";
239
240 if (map.target_poses()->size() == 0) {
241 VLOG(2) << "Got 0 AprilTags for camera " << camera_name;
242 return;
243 }
244
245 for (const auto *target_pose_fbs : *map.target_poses()) {
246 // Skip detections with invalid ids
247 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700248 absl::GetFlag(FLAGS_min_target_id) ||
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700249 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700250 absl::GetFlag(FLAGS_max_target_id)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700251 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
252 continue;
253 }
254
255 // Skip detections with high pose errors
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700256 if (target_pose_fbs->pose_error() > absl::GetFlag(FLAGS_max_pose_error)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700257 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
258 << " due to pose error of " << target_pose_fbs->pose_error();
259 continue;
260 }
261 // Skip detections with high pose error ratios
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700262 if (target_pose_fbs->pose_error_ratio() >
263 absl::GetFlag(FLAGS_max_pose_error_ratio)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700264 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
265 << " due to pose error ratio of "
266 << target_pose_fbs->pose_error_ratio();
267 continue;
268 }
269
270 const TargetMapper::TargetPose target_pose =
271 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
272
273 Eigen::Affine3d H_camera_target =
274 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
275 Eigen::Affine3d H_robot_target =
276 CameraToRobotDetection(H_camera_target, extrinsics);
277
278 ceres::examples::Pose3d target_pose_camera =
279 PoseUtils::Affine3dToPose3d(H_camera_target);
280 double distance_from_camera = target_pose_camera.p.norm();
281 double distortion_factor = target_pose_fbs->distortion_factor();
282
283 double distance_threshold = 5.0;
284 if (distance_from_camera > distance_threshold) {
285 ignore_count_++;
286 LOG(INFO) << "Ignored " << ignore_count_ << " AprilTags with distance "
287 << distance_from_camera << " > " << distance_threshold;
288 continue;
289 }
290
291 CHECK(map.has_monotonic_timestamp_ns())
292 << "Need detection timestamps for mapping";
293
294 // Detection is usable, so store it
295 timestamped_target_detections_.emplace_back(
296 DataAdapter::TimestampedDetection{
297 .time = node_distributed_time,
298 .H_robot_target = H_robot_target,
299 .distance_from_camera = distance_from_camera,
300 .distortion_factor = distortion_factor,
301 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
302
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700303 if (absl::GetFlag(FLAGS_visualize_solver)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700304 // If we've already drawn this camera_name in the current image,
305 // display the image before clearing and adding the new poses
306 if (drawn_cameras_.count(camera_name) != 0) {
307 display_count_++;
308 cv::putText(vis_robot_.image_,
309 "Poses #" + std::to_string(display_count_),
310 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
311 cv::Scalar(255, 255, 255));
312
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700313 if (display_count_ >= absl::GetFlag(FLAGS_skip_to)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700314 VLOG(1) << "Showing image for camera " << camera_name
315 << " since we've drawn it already";
316 cv::imshow("View", vis_robot_.image_);
317 // Pause if delta_T is too large, but only after first image (to make
318 // sure the delta's are correct)
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700319 if (max_delta_T_world_robot_ >
320 absl::GetFlag(FLAGS_pause_on_distance) &&
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700321 display_count_ > 1) {
322 LOG(INFO) << "Pausing since the delta between robot estimates is "
323 << max_delta_T_world_robot_ << " which is > threshold of "
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700324 << absl::GetFlag(FLAGS_pause_on_distance);
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700325 cv::waitKey(0);
326 } else {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700327 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700328 }
329 max_delta_T_world_robot_ = 0.0;
330 } else {
331 VLOG(2) << "At poses #" << std::to_string(display_count_);
332 }
333 vis_robot_.ClearImage();
334 drawn_cameras_.clear();
335 }
336
337 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
338 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
339 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
340 VLOG(2) << camera_name << ", id " << target_pose_fbs->id()
341 << ", t = " << node_distributed_time
342 << ", pose_error = " << target_pose_fbs->pose_error()
343 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
344 << ", robot_pos (x,y,z) = "
345 << H_world_robot.translation().transpose();
346
347 label << "id " << target_pose_fbs->id()
348 << ": err (% of max): " << target_pose_fbs->pose_error() << " ("
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700349 << (target_pose_fbs->pose_error() /
350 absl::GetFlag(FLAGS_max_pose_error))
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700351 << ") err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
352
353 vis_robot_.DrawRobotOutline(H_world_robot, camera_name,
354 kOrinColors.at(camera_name));
355 vis_robot_.DrawFrameAxes(H_world_target,
356 std::to_string(target_pose_fbs->id()),
357 kOrinColors.at(camera_name));
358
359 double delta_T_world_robot =
360 (H_world_robot.translation() - last_H_world_robot_.translation())
361 .norm();
362 max_delta_T_world_robot_ =
363 std::max(delta_T_world_robot, max_delta_T_world_robot_);
364
365 VLOG(1) << "Drew in info for camera " << camera_name << " and target #"
366 << target_pose_fbs->id();
367 drew = true;
368 last_draw_time_ = node_distributed_time;
369 last_H_world_robot_ = H_world_robot;
370 }
371 }
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700372 if (absl::GetFlag(FLAGS_visualize_solver)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700373 if (drew) {
374 // Collect all the labels from a given camera, and add the text
375 // TODO: Need to fix this one
376 int position_number = camera_ordering_map[camera_name];
377 cv::putText(vis_robot_.image_, label.str(),
378 cv::Point(10, 30 + 20 * position_number),
379 cv::FONT_HERSHEY_PLAIN, 1.0, kOrinColors.at(camera_name));
380 drawn_cameras_.emplace(camera_name);
381 } else if (node_distributed_time - last_draw_time_ >
382 std::chrono::milliseconds(30) &&
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700383 display_count_ >= absl::GetFlag(FLAGS_skip_to) && drew) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700384 // TODO: Check on 30ms value-- does this make sense?
385 double delta_t = (node_distributed_time - last_draw_time_).count() / 1e6;
386 VLOG(1) << "Last result was " << delta_t << "ms ago";
387 cv::putText(vis_robot_.image_, "No detections in last 30ms",
388 cv::Point(10, 0), cv::FONT_HERSHEY_PLAIN, 1.0,
389 kOrinColors.at(camera_name));
390 // Display and clear the image if we haven't draw in a while
391 VLOG(1) << "Displaying image due to time lapse";
392 cv::imshow("View", vis_robot_.image_);
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700393 cv::waitKey(absl::GetFlag(FLAGS_wait_key));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700394 max_delta_T_world_robot_ = 0.0;
395 drawn_cameras_.clear();
396 }
397 }
398}
399
400void TargetMapperReplay::HandleNodeCaptures(
401 aos::EventLoop *mapping_event_loop,
402 frc971::constants::ConstantsFetcher<y2024_swerve::Constants>
403 *constants_fetcher,
404 int camera_number) {
405 // Get the camera extrinsics
406 std::string node_name =
407 std::string(mapping_event_loop->node()->name()->string_view());
408 const auto *calibration = FindCameraCalibration(
409 constants_fetcher->constants(), node_name, camera_number);
410 cv::Mat extrinsics_cv = frc971::vision::CameraExtrinsics(calibration).value();
411 Eigen::Matrix4d extrinsics_matrix;
412 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
413 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
414 std::string camera_name = absl::StrFormat(
415 "/%s/camera%d", mapping_event_loop->node()->name()->str(), camera_number);
416
417 mapping_event_loop->MakeWatcher(
418 camera_name.c_str(), [this, mapping_event_loop, extrinsics,
419 camera_name](const TargetMap &map) {
420 aos::distributed_clock::time_point node_distributed_time =
421 reader_->event_loop_factory()
422 ->GetNodeEventLoopFactory(mapping_event_loop->node())
423 ->ToDistributedClock(aos::monotonic_clock::time_point(
424 aos::monotonic_clock::duration(
425 map.monotonic_timestamp_ns())));
426
427 HandleAprilTags(map, node_distributed_time, camera_name, extrinsics);
428 });
429}
430
431void TargetMapperReplay::MaybeSolve() {
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700432 if (absl::GetFlag(FLAGS_solve)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700433 auto target_constraints =
434 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
435
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700436 if (absl::GetFlag(FLAGS_split_field)) {
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700437 // Remove constraints between the two sides of the field - these are
438 // basically garbage because of how far the camera is. We will use seeding
439 // below to connect the two sides
440 target_constraints.erase(
441 std::remove_if(
442 target_constraints.begin(), target_constraints.end(),
443 [](const auto &constraint) {
444 return (
445 kIdAllianceMap[static_cast<uint>(constraint.id_begin)] !=
446 kIdAllianceMap[static_cast<uint>(constraint.id_end)]);
447 }),
448 target_constraints.end());
449 }
450
451 LOG(INFO) << "Solving for locations of tags with "
452 << target_constraints.size() << " constraints";
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700453 TargetMapper mapper(absl::GetFlag(FLAGS_json_path), target_constraints);
454 mapper.Solve(absl::GetFlag(FLAGS_field_name),
455 absl::GetFlag(FLAGS_output_dir));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700456
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700457 if (!absl::GetFlag(FLAGS_dump_constraints_to).empty()) {
458 mapper.DumpConstraints(absl::GetFlag(FLAGS_dump_constraints_to));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700459 }
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700460 if (!absl::GetFlag(FLAGS_dump_stats_to).empty()) {
461 mapper.DumpStats(absl::GetFlag(FLAGS_dump_stats_to));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700462 }
463 mapper.PrintDiffs();
464 }
465}
466
467void MappingMain(int argc, char *argv[]) {
468 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
469
470 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700471 (absl::GetFlag(FLAGS_config).empty()
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700472 ? std::nullopt
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700473 : std::make_optional(
474 aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config))));
Yash Maheshwarie0b25c52024-05-22 20:23:36 -0700475
476 // Open logfiles
477 aos::logger::LogReader reader(
478 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
479 config.has_value() ? &config->message() : nullptr);
480
481 TargetMapperReplay mapper_replay(&reader);
482 reader.event_loop_factory()->Run();
483 mapper_replay.MaybeSolve();
484}
485
486} // namespace y2024_swerve::vision
487
488int main(int argc, char **argv) {
489 aos::InitGoogle(&argc, &argv);
490 y2024_swerve::vision::MappingMain(argc, argv);
491}