blob: ac4cfa38a3daf38db285e2fe2a7a3fd8e7ec10ee [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-ude9045f2023-03-25 18:17:12 -070044DEFINE_uint64(skip_to, 1,
45 "Start at combined image of this number (1 is the first image)");
milind-ua30a4a12023-03-24 20:49:41 -070046DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080047
milind-u16e3a082023-01-21 13:53:43 -080048namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080049namespace vision {
50using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080051using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080052using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080053using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080054using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070055using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080056namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080057
milind-u2ab4db12023-03-25 21:59:23 -070058// Class to handle reading target poses from a replayed log,
59// displaying various debug info, and passing the poses to
60// frc971::vision::TargetMapper for field mapping.
61class TargetMapperReplay {
62 public:
63 TargetMapperReplay(aos::logger::LogReader *reader);
64 ~TargetMapperReplay();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080065
milind-u2ab4db12023-03-25 21:59:23 -070066 // Solves for the target poses with the accumulated detections if FLAGS_solve.
67 void MaybeSolve();
68
69 private:
70 static constexpr int kImageWidth = 1280;
71 // Map from pi node name to color for drawing
72 static const std::map<std::string, cv::Scalar> kPiColors;
73 // Contains fixed target poses without solving, for use with visualization
74 static const TargetMapper kFixedTargetMapper;
75
76 // Change reference frame from camera to robot
77 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
78 Eigen::Affine3d extrinsics);
79
80 // Adds april tag detections into the detection list, and handles
81 // visualization
82 void HandleAprilTags(const TargetMap &map,
83 aos::distributed_clock::time_point pi_distributed_time,
84 std::string node_name, Eigen::Affine3d extrinsics);
85
86 // Gets images from the given pi and passes apriltag positions to
87 // HandleAprilTags()
88 void HandlePiCaptures(aos::EventLoop *detection_event_loop,
89 aos::EventLoop *mapping_event_loop);
90
91 aos::logger::LogReader *reader_;
92 // April tag detections from all pis
93 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
94 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_;
95
96 VisualizeRobot vis_robot_;
97 // Set of node names which are currently drawn on the display
98 std::set<std::string> drawn_nodes_;
99 // Number of frames displayed
100 size_t display_count_;
101 // Last time we drew onto the display image.
102 // This is different from when we actually call imshow() to update
103 // the display window
104 aos::distributed_clock::time_point last_draw_time_;
105
106 std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops_;
107 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
108
109 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
110 std::unique_ptr<aos::McapLogger> relogger_;
111};
112
113const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700114 {"pi1", cv::Scalar(255, 0, 255)},
115 {"pi2", cv::Scalar(255, 255, 0)},
116 {"pi3", cv::Scalar(0, 255, 255)},
117 {"pi4", cv::Scalar(255, 165, 0)},
118};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700119
milind-u2ab4db12023-03-25 21:59:23 -0700120const auto TargetMapperReplay::kFixedTargetMapper =
121 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
122
123Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
124 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
125 const Eigen::Affine3d H_robot_camera = extrinsics;
126 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
127 return H_robot_target;
128}
129
130TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
131 : reader_(reader),
132 timestamped_target_detections_(),
133 detectors_(),
134 vis_robot_(cv::Size(1280, 1000)),
135 drawn_nodes_(),
136 display_count_(0),
137 last_draw_time_(aos::distributed_clock::min_time) {
138 // Send new april tag poses. This allows us to take a log of images, then
139 // play with the april detection code and see those changes take effect in
140 // mapping
141 constexpr size_t kNumPis = 4;
142 for (size_t i = 1; i <= kNumPis; i++) {
143 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
144 "frc971.vision.TargetMap");
145 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
146 "foxglove.ImageAnnotations");
147 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
148 "y2023.Constants");
149 }
150
151 reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants");
152
153 reader_->Register();
154
155 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
156 FLAGS_constants_path);
157
158 for (size_t i = 1; i < kNumPis; i++) {
159 std::string node_name = "pi" + std::to_string(i);
160 const aos::Node *pi =
161 aos::configuration::GetNode(reader_->configuration(), node_name);
162 detection_event_loops_.emplace_back(
163 reader_->event_loop_factory()->MakeEventLoop(node_name + "_detection",
164 pi));
165 mapping_event_loops_.emplace_back(
166 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
167 pi));
168 HandlePiCaptures(
169 detection_event_loops_[detection_event_loops_.size() - 1].get(),
170 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
171 }
172
173 if (!FLAGS_mcap_output_path.empty()) {
174 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
175 const aos::Node *node =
176 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
177 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
178 [this, node]() {
179 mcap_event_loop_ =
180 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
181 relogger_ = std::make_unique<aos::McapLogger>(
182 mcap_event_loop_.get(), FLAGS_mcap_output_path,
183 aos::McapLogger::Serialization::kFlatbuffer,
184 aos::McapLogger::CanonicalChannelNames::kShortened,
185 aos::McapLogger::Compression::kLz4);
186 });
187 }
188
189 if (FLAGS_visualize) {
190 vis_robot_.ClearImage();
191 const double kFocalLength = 500.0;
192 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
193 }
194}
195
196TargetMapperReplay::~TargetMapperReplay() {
197 // Clean up all the pointers
198 for (auto &detector_ptr : detectors_) {
199 detector_ptr.reset();
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-u5ddd5152023-03-04 15:19:17 -0800214 // Skip detections with high pose errors
215 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-ude9045f2023-03-25 18:17:12 -0700216 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
217 << " due to pose error of " << target_pose_fbs->pose_error();
218 continue;
219 }
220 // Skip detections with high pose error ratios
221 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
222 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
223 << " due to pose error ratio of "
224 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800225 continue;
226 }
227
milind-u3f5f83c2023-01-29 15:23:51 -0800228 const TargetMapper::TargetPose target_pose =
229 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800230
milind-uee67abd2023-02-23 18:26:55 -0800231 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800232 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800233 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800234 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800235
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800236 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800237 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800238 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800239 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800240
milind-u09fb1252023-01-28 19:21:41 -0800241 CHECK(map.has_monotonic_timestamp_ns())
242 << "Need detection timestamps for mapping";
243
milind-u2ab4db12023-03-25 21:59:23 -0700244 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800245 DataAdapter::TimestampedDetection{
246 .time = pi_distributed_time,
247 .H_robot_target = H_robot_target,
248 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800249 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800250 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700251
252 if (FLAGS_visualize) {
milind-ua30a4a12023-03-24 20:49:41 -0700253 // If we've already drawn in the current image,
254 // display it before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700255 if (drawn_nodes_.count(node_name) != 0) {
256 display_count_++;
257 cv::putText(vis_robot_.image_,
258 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700259 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
260 cv::Scalar(255, 255, 255));
261
milind-u2ab4db12023-03-25 21:59:23 -0700262 if (display_count_ >= FLAGS_skip_to) {
263 cv::imshow("View", vis_robot_.image_);
milind-ude9045f2023-03-25 18:17:12 -0700264 cv::waitKey(FLAGS_wait_key);
265 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700266 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700267 }
milind-u2ab4db12023-03-25 21:59:23 -0700268 vis_robot_.ClearImage();
269 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700270 }
271
Jim Ostrowski49be8232023-03-23 01:00:14 -0700272 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700273 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700274 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700275 VLOG(2) << node_name << ", " << target_pose_fbs->id()
276 << ", t = " << pi_distributed_time
277 << ", pose_error = " << target_pose_fbs->pose_error()
278 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
279 << ", robot_pos (x,y,z) + "
280 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700281
282 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700283 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
284 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700285
milind-u2ab4db12023-03-25 21:59:23 -0700286 vis_robot_.DrawRobotOutline(H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -0700287 std::to_string(target_pose_fbs->id()),
288 kPiColors.at(node_name));
289
milind-u2ab4db12023-03-25 21:59:23 -0700290 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700291 std::to_string(target_pose_fbs->id()),
292 kPiColors.at(node_name));
293 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700294 last_draw_time_ = pi_distributed_time;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700295 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800296 }
milind-ua30a4a12023-03-24 20:49:41 -0700297 if (drew) {
298 size_t pi_number =
299 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
milind-u2ab4db12023-03-25 21:59:23 -0700300 cv::putText(vis_robot_.image_, label.str(),
milind-ua30a4a12023-03-24 20:49:41 -0700301 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
302 kPiColors.at(node_name));
303
milind-u2ab4db12023-03-25 21:59:23 -0700304 drawn_nodes_.emplace(node_name);
305 } else if (pi_distributed_time - last_draw_time_ >
milind-u52db3362023-03-25 20:09:22 -0700306 std::chrono::milliseconds(30) &&
milind-u2ab4db12023-03-25 21:59:23 -0700307 display_count_ >= FLAGS_skip_to) {
milind-u52db3362023-03-25 20:09:22 -0700308 // Clear the image if we haven't draw in a while
milind-u2ab4db12023-03-25 21:59:23 -0700309 vis_robot_.ClearImage();
310 cv::imshow("View", vis_robot_.image_);
milind-u52db3362023-03-25 20:09:22 -0700311 cv::waitKey(FLAGS_wait_key);
milind-ua30a4a12023-03-24 20:49:41 -0700312 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800313}
314
milind-u2ab4db12023-03-25 21:59:23 -0700315void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *detection_event_loop,
316 aos::EventLoop *mapping_event_loop) {
milind-uf3ab8ba2023-02-04 17:56:16 -0800317 static constexpr std::string_view kImageChannel = "/camera";
milind-ua30a4a12023-03-24 20:49:41 -0700318 // For the robots, we need to flip the image since the cameras are rolled by
319 // 180 degrees
320 bool flip_image = (FLAGS_team_number != 7971);
milind-uf3ab8ba2023-02-04 17:56:16 -0800321 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
milind-ua30a4a12023-03-24 20:49:41 -0700322 detection_event_loop, kImageChannel, flip_image);
milind-uf2a4e322023-02-01 19:33:10 -0800323 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -0800324 cv::Mat extrinsics_cv = detector_ptr->extrinsics().value();
milind-uf2a4e322023-02-01 19:33:10 -0800325 Eigen::Matrix4d extrinsics_matrix;
326 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
327 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
328
milind-u2ab4db12023-03-25 21:59:23 -0700329 detectors_.emplace_back(std::move(detector_ptr));
Jim Ostrowski49be8232023-03-23 01:00:14 -0700330
milind-uf3ab8ba2023-02-04 17:56:16 -0800331 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800332 aos::distributed_clock::time_point pi_distributed_time =
milind-u2ab4db12023-03-25 21:59:23 -0700333 reader_->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800334 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800335 ->ToDistributedClock(aos::monotonic_clock::time_point(
336 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800337
Jim Ostrowski49be8232023-03-23 01:00:14 -0700338 std::string node_name = detection_event_loop->node()->name()->str();
milind-u2ab4db12023-03-25 21:59:23 -0700339 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
milind-u09fb1252023-01-28 19:21:41 -0800340 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800341}
342
milind-u2ab4db12023-03-25 21:59:23 -0700343void TargetMapperReplay::MaybeSolve() {
344 if (FLAGS_solve) {
345 auto target_constraints =
346 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
347
348 TargetMapper mapper(FLAGS_json_path, target_constraints);
349 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
350 }
351}
352
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800353void MappingMain(int argc, char *argv[]) {
354 std::vector<std::string> unsorted_logfiles =
355 aos::logger::FindLogs(argc, argv);
356
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800357 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
358
milind-u4a5ef8a2023-03-05 14:10:23 -0800359 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
360 (FLAGS_config.empty()
361 ? std::nullopt
362 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800363
milind-u2ab4db12023-03-25 21:59:23 -0700364 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800365 aos::logger::LogReader reader(
366 aos::logger::SortParts(unsorted_logfiles),
367 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800368
milind-u2ab4db12023-03-25 21:59:23 -0700369 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800370 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700371 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800372}
373
374} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800375} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800376
377int main(int argc, char **argv) {
378 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800379 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800380}