blob: 3f5355a7ccf595d8ea4a54b142319d5fd3268a61 [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/charuco_lib.h"
9#include "frc971/vision/target_mapper.h"
Jim Ostrowski49be8232023-03-23 01:00:14 -070010#include "frc971/vision/visualize_robot.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080011#include "opencv2/aruco.hpp"
12#include "opencv2/calib3d.hpp"
13#include "opencv2/core/eigen.hpp"
14#include "opencv2/features2d.hpp"
15#include "opencv2/highgui.hpp"
16#include "opencv2/highgui/highgui.hpp"
17#include "opencv2/imgproc.hpp"
milind-uc5a494f2023-02-24 15:39:22 -080018#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080019#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080020#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080021
milind-uc5a494f2023-02-24 15:39:22 -080022DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080023 "Specify path for json with initial pose guesses.");
milind-u4a5ef8a2023-03-05 14:10:23 -080024DEFINE_string(config, "",
25 "If set, override the log's config file with this one.");
milind-uc5a494f2023-02-24 15:39:22 -080026DEFINE_string(constants_path, "y2023/constants/constants.json",
27 "Path to the constant file");
28DEFINE_string(output_dir, "y2023/vision/maps",
29 "Directory to write solved target map to");
30DEFINE_string(field_name, "charged_up",
31 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski49be8232023-03-23 01:00:14 -070032DEFINE_int32(team_number, 0,
33 "Required: Use the calibration for a node with this team number");
Jim Ostrowski68965cd2023-03-01 20:32:51 -080034DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output.");
35DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
milind-u5ddd5152023-03-04 15:19:17 -080036DEFINE_double(max_pose_error, 1e-6,
37 "Throw out target poses with a higher pose error than this");
milind-ude9045f2023-03-25 18:17:12 -070038DEFINE_double(
39 max_pose_error_ratio, 0.4,
40 "Throw out target poses with a higher pose error ratio than this");
milind-ua30a4a12023-03-24 20:49:41 -070041DEFINE_uint64(wait_key, 0,
42 "Time in ms to wait between images, if no click (0 to wait "
43 "indefinitely until click).");
milind-u8cc03da2023-03-25 23:00:39 -070044DEFINE_double(pause_on_distance, 1.0,
45 "Pause if two consecutive implied robot positions differ by more "
46 "than this many meters");
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.");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080050
milind-u16e3a082023-01-21 13:53:43 -080051namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080052namespace vision {
53using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080054using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080055using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080056using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080057using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070058using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080059namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080060
milind-u2ab4db12023-03-25 21:59:23 -070061// Class to handle reading target poses from a replayed log,
62// displaying various debug info, and passing the poses to
63// frc971::vision::TargetMapper for field mapping.
64class TargetMapperReplay {
65 public:
66 TargetMapperReplay(aos::logger::LogReader *reader);
67 ~TargetMapperReplay();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080068
milind-u2ab4db12023-03-25 21:59:23 -070069 // Solves for the target poses with the accumulated detections if FLAGS_solve.
70 void MaybeSolve();
71
72 private:
73 static constexpr int kImageWidth = 1280;
74 // Map from pi node name to color for drawing
75 static const std::map<std::string, cv::Scalar> kPiColors;
76 // Contains fixed target poses without solving, for use with visualization
77 static const TargetMapper kFixedTargetMapper;
78
79 // Change reference frame from camera to robot
80 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
81 Eigen::Affine3d extrinsics);
82
83 // Adds april tag detections into the detection list, and handles
84 // visualization
85 void HandleAprilTags(const TargetMap &map,
86 aos::distributed_clock::time_point pi_distributed_time,
87 std::string node_name, Eigen::Affine3d extrinsics);
88
89 // Gets images from the given pi and passes apriltag positions to
90 // HandleAprilTags()
91 void HandlePiCaptures(aos::EventLoop *detection_event_loop,
92 aos::EventLoop *mapping_event_loop);
93
94 aos::logger::LogReader *reader_;
95 // April tag detections from all pis
96 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
97 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_;
98
99 VisualizeRobot vis_robot_;
100 // Set of node names which are currently drawn on the display
101 std::set<std::string> drawn_nodes_;
102 // Number of frames displayed
103 size_t display_count_;
104 // Last time we drew onto the display image.
105 // This is different from when we actually call imshow() to update
106 // the display window
107 aos::distributed_clock::time_point last_draw_time_;
108
milind-u8cc03da2023-03-25 23:00:39 -0700109 Eigen::Affine3d last_H_world_robot_;
110 // Maximum distance between consecutive T_world_robot's in one display frame,
111 // used to determine if we need to pause for the user to see this frame
112 // clearly
113 double max_delta_T_world_robot_;
114
milind-u2ab4db12023-03-25 21:59:23 -0700115 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops_;
116 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
117
118 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
119 std::unique_ptr<aos::McapLogger> relogger_;
120};
121
122const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700123 {"pi1", cv::Scalar(255, 0, 255)},
124 {"pi2", cv::Scalar(255, 255, 0)},
125 {"pi3", cv::Scalar(0, 255, 255)},
126 {"pi4", cv::Scalar(255, 165, 0)},
127};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700128
milind-u2ab4db12023-03-25 21:59:23 -0700129const auto TargetMapperReplay::kFixedTargetMapper =
130 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
131
132Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
133 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
134 const Eigen::Affine3d H_robot_camera = extrinsics;
135 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
136 return H_robot_target;
137}
138
139TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
140 : reader_(reader),
141 timestamped_target_detections_(),
142 detectors_(),
143 vis_robot_(cv::Size(1280, 1000)),
144 drawn_nodes_(),
145 display_count_(0),
milind-u8cc03da2023-03-25 23:00:39 -0700146 last_draw_time_(aos::distributed_clock::min_time),
147 last_H_world_robot_(Eigen::Matrix4d::Identity()),
148 max_delta_T_world_robot_(0.0) {
milind-u2ab4db12023-03-25 21:59:23 -0700149 // Send new april tag poses. This allows us to take a log of images, then
150 // play with the april detection code and see those changes take effect in
151 // mapping
152 constexpr size_t kNumPis = 4;
153 for (size_t i = 1; i <= kNumPis; i++) {
154 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
155 "frc971.vision.TargetMap");
156 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
157 "foxglove.ImageAnnotations");
158 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);
173 detection_event_loops_.emplace_back(
174 reader_->event_loop_factory()->MakeEventLoop(node_name + "_detection",
175 pi));
176 mapping_event_loops_.emplace_back(
177 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
178 pi));
179 HandlePiCaptures(
180 detection_event_loops_[detection_event_loops_.size() - 1].get(),
181 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
182 }
183
184 if (!FLAGS_mcap_output_path.empty()) {
185 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
186 const aos::Node *node =
187 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
188 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>(
193 mcap_event_loop_.get(), FLAGS_mcap_output_path,
194 aos::McapLogger::Serialization::kFlatbuffer,
195 aos::McapLogger::CanonicalChannelNames::kShortened,
196 aos::McapLogger::Compression::kLz4);
197 });
198 }
199
200 if (FLAGS_visualize) {
201 vis_robot_.ClearImage();
202 const double kFocalLength = 500.0;
203 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
204 }
205}
206
207TargetMapperReplay::~TargetMapperReplay() {
208 // Clean up all the pointers
209 for (auto &detector_ptr : detectors_) {
210 detector_ptr.reset();
211 }
212}
213
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800214// Add detected apriltag poses relative to the robot to
215// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700216void TargetMapperReplay::HandleAprilTags(
217 const TargetMap &map,
218 aos::distributed_clock::time_point pi_distributed_time,
219 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700220 bool drew = false;
221 std::stringstream label;
222 label << node_name << " - ";
223
milind-u3f5f83c2023-01-29 15:23:51 -0800224 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-u5ddd5152023-03-04 15:19:17 -0800225 // Skip detections with high pose errors
226 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-ude9045f2023-03-25 18:17:12 -0700227 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
228 << " due to pose error of " << target_pose_fbs->pose_error();
229 continue;
230 }
231 // Skip detections with high pose error ratios
232 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
233 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
234 << " due to pose error ratio of "
235 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800236 continue;
237 }
238
milind-u3f5f83c2023-01-29 15:23:51 -0800239 const TargetMapper::TargetPose target_pose =
240 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800241
milind-uee67abd2023-02-23 18:26:55 -0800242 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800243 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800244 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800245 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800246
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800247 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800248 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800249 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800250 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800251
milind-u09fb1252023-01-28 19:21:41 -0800252 CHECK(map.has_monotonic_timestamp_ns())
253 << "Need detection timestamps for mapping";
254
milind-u2ab4db12023-03-25 21:59:23 -0700255 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800256 DataAdapter::TimestampedDetection{
257 .time = pi_distributed_time,
258 .H_robot_target = H_robot_target,
259 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800260 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800261 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700262
263 if (FLAGS_visualize) {
milind-ua30a4a12023-03-24 20:49:41 -0700264 // If we've already drawn in the current image,
265 // display it before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700266 if (drawn_nodes_.count(node_name) != 0) {
267 display_count_++;
268 cv::putText(vis_robot_.image_,
269 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700270 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
271 cv::Scalar(255, 255, 255));
272
milind-u2ab4db12023-03-25 21:59:23 -0700273 if (display_count_ >= FLAGS_skip_to) {
274 cv::imshow("View", vis_robot_.image_);
milind-u8cc03da2023-03-25 23:00:39 -0700275 cv::waitKey(max_delta_T_world_robot_ > FLAGS_pause_on_distance
276 ? 0
277 : FLAGS_wait_key);
278 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700279 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700280 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700281 }
milind-u2ab4db12023-03-25 21:59:23 -0700282 vis_robot_.ClearImage();
283 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700284 }
285
Jim Ostrowski49be8232023-03-23 01:00:14 -0700286 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700287 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700288 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700289 VLOG(2) << node_name << ", " << target_pose_fbs->id()
290 << ", t = " << pi_distributed_time
291 << ", pose_error = " << target_pose_fbs->pose_error()
292 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
293 << ", robot_pos (x,y,z) + "
294 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700295
296 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700297 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
298 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700299
milind-u2ab4db12023-03-25 21:59:23 -0700300 vis_robot_.DrawRobotOutline(H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -0700301 std::to_string(target_pose_fbs->id()),
302 kPiColors.at(node_name));
303
milind-u2ab4db12023-03-25 21:59:23 -0700304 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700305 std::to_string(target_pose_fbs->id()),
306 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700307
308 double delta_T_world_robot =
309 (H_world_robot.translation() - last_H_world_robot_.translation())
310 .norm();
311 max_delta_T_world_robot_ =
312 std::max(delta_T_world_robot, max_delta_T_world_robot_);
313
milind-ua30a4a12023-03-24 20:49:41 -0700314 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700315 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700316 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700317 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800318 }
milind-ua30a4a12023-03-24 20:49:41 -0700319 if (drew) {
320 size_t pi_number =
321 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
milind-u2ab4db12023-03-25 21:59:23 -0700322 cv::putText(vis_robot_.image_, label.str(),
milind-ua30a4a12023-03-24 20:49:41 -0700323 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
324 kPiColors.at(node_name));
325
milind-u2ab4db12023-03-25 21:59:23 -0700326 drawn_nodes_.emplace(node_name);
327 } else if (pi_distributed_time - last_draw_time_ >
milind-u52db3362023-03-25 20:09:22 -0700328 std::chrono::milliseconds(30) &&
milind-u2ab4db12023-03-25 21:59:23 -0700329 display_count_ >= FLAGS_skip_to) {
milind-u52db3362023-03-25 20:09:22 -0700330 // Clear the image if we haven't draw in a while
milind-u2ab4db12023-03-25 21:59:23 -0700331 vis_robot_.ClearImage();
332 cv::imshow("View", vis_robot_.image_);
milind-u52db3362023-03-25 20:09:22 -0700333 cv::waitKey(FLAGS_wait_key);
milind-u8cc03da2023-03-25 23:00:39 -0700334 max_delta_T_world_robot_ = 0.0;
milind-ua30a4a12023-03-24 20:49:41 -0700335 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800336}
337
milind-u2ab4db12023-03-25 21:59:23 -0700338void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *detection_event_loop,
339 aos::EventLoop *mapping_event_loop) {
milind-uf3ab8ba2023-02-04 17:56:16 -0800340 static constexpr std::string_view kImageChannel = "/camera";
milind-ua30a4a12023-03-24 20:49:41 -0700341 // For the robots, we need to flip the image since the cameras are rolled by
342 // 180 degrees
343 bool flip_image = (FLAGS_team_number != 7971);
milind-uf3ab8ba2023-02-04 17:56:16 -0800344 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
milind-ua30a4a12023-03-24 20:49:41 -0700345 detection_event_loop, kImageChannel, flip_image);
milind-uf2a4e322023-02-01 19:33:10 -0800346 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -0800347 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -0800348 Eigen::Matrix4d extrinsics_matrix;
349 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
350 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
351
milind-u2ab4db12023-03-25 21:59:23 -0700352 detectors_.emplace_back(std::move(detector_ptr));
Jim Ostrowski49be8232023-03-23 01:00:14 -0700353
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
Jim Ostrowski49be8232023-03-23 01:00:14 -0700361 std::string node_name = detection_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
371 TargetMapper mapper(FLAGS_json_path, target_constraints);
372 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
373 }
374}
375
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800376void MappingMain(int argc, char *argv[]) {
377 std::vector<std::string> unsorted_logfiles =
378 aos::logger::FindLogs(argc, argv);
379
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800380 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
381
milind-u4a5ef8a2023-03-05 14:10:23 -0800382 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
383 (FLAGS_config.empty()
384 ? std::nullopt
385 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800386
milind-u2ab4db12023-03-25 21:59:23 -0700387 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800388 aos::logger::LogReader reader(
389 aos::logger::SortParts(unsorted_logfiles),
390 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800391
milind-u2ab4db12023-03-25 21:59:23 -0700392 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800393 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700394 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800395}
396
397} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800398} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800399
400int main(int argc, char **argv) {
401 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800402 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800403}