blob: 985a412c19f48480a1840396325773f49378bbaf [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-uc5a494f2023-02-24 15:39:22 -080023DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080024 "Specify path for json with initial pose guesses.");
milind-u4a5ef8a2023-03-05 14:10:23 -080025DEFINE_string(config, "",
26 "If set, override the log's config file with this one.");
milind-uc5a494f2023-02-24 15:39:22 -080027DEFINE_string(constants_path, "y2023/constants/constants.json",
28 "Path to the constant file");
29DEFINE_string(output_dir, "y2023/vision/maps",
30 "Directory to write solved target map to");
31DEFINE_string(field_name, "charged_up",
32 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski49be8232023-03-23 01:00:14 -070033DEFINE_int32(team_number, 0,
34 "Required: Use the calibration for a node with this team number");
Jim Ostrowski68965cd2023-03-01 20:32:51 -080035DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output.");
36DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
milind-u5ddd5152023-03-04 15:19:17 -080037DEFINE_double(max_pose_error, 1e-6,
38 "Throw out target poses with a higher pose error than this");
milind-ude9045f2023-03-25 18:17:12 -070039DEFINE_double(
40 max_pose_error_ratio, 0.4,
41 "Throw out target poses with a higher pose error ratio than this");
milind-ua30a4a12023-03-24 20:49:41 -070042DEFINE_uint64(wait_key, 0,
43 "Time in ms to wait between images, if no click (0 to wait "
44 "indefinitely until click).");
milind-u8cc03da2023-03-25 23:00:39 -070045DEFINE_double(pause_on_distance, 1.0,
46 "Pause if two consecutive implied robot positions differ by more "
47 "than this many meters");
milind-ude9045f2023-03-25 18:17:12 -070048DEFINE_uint64(skip_to, 1,
49 "Start at combined image of this number (1 is the first image)");
milind-ua30a4a12023-03-24 20:49:41 -070050DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
milind-u401de982023-04-14 17:32:03 -070051DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
52 "Write the target constraints to this path");
53DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
milind-ufbc5c812023-04-06 21:24:29 -070054 "Write the target constraints to this path");
milind-u8f4e43e2023-04-09 17:11:19 -070055DECLARE_int32(frozen_target_id);
56DECLARE_int32(min_target_id);
57DECLARE_int32(max_target_id);
58DECLARE_bool(visualize_solver);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080059
milind-u16e3a082023-01-21 13:53:43 -080060namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080061namespace vision {
62using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080063using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080064using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080065using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080066using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070067using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080068namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080069
milind-u2ab4db12023-03-25 21:59:23 -070070// Class to handle reading target poses from a replayed log,
71// displaying various debug info, and passing the poses to
72// frc971::vision::TargetMapper for field mapping.
73class TargetMapperReplay {
74 public:
75 TargetMapperReplay(aos::logger::LogReader *reader);
76 ~TargetMapperReplay();
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_;
105 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_;
106
107 VisualizeRobot vis_robot_;
108 // Set of node names which are currently drawn on the display
109 std::set<std::string> drawn_nodes_;
110 // Number of frames displayed
111 size_t display_count_;
112 // Last time we drew onto the display image.
113 // This is different from when we actually call imshow() to update
114 // the display window
115 aos::distributed_clock::time_point last_draw_time_;
116
milind-u8cc03da2023-03-25 23:00:39 -0700117 Eigen::Affine3d last_H_world_robot_;
118 // Maximum distance between consecutive T_world_robot's in one display frame,
119 // used to determine if we need to pause for the user to see this frame
120 // clearly
121 double max_delta_T_world_robot_;
122
milind-u2ab4db12023-03-25 21:59:23 -0700123 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
124
125 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
126 std::unique_ptr<aos::McapLogger> relogger_;
127};
128
129const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700130 {"pi1", cv::Scalar(255, 0, 255)},
131 {"pi2", cv::Scalar(255, 255, 0)},
132 {"pi3", cv::Scalar(0, 255, 255)},
133 {"pi4", cv::Scalar(255, 165, 0)},
134};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700135
milind-u2ab4db12023-03-25 21:59:23 -0700136const auto TargetMapperReplay::kFixedTargetMapper =
137 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
138
139Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
140 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
141 const Eigen::Affine3d H_robot_camera = extrinsics;
142 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
143 return H_robot_target;
144}
145
146TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
147 : reader_(reader),
148 timestamped_target_detections_(),
149 detectors_(),
150 vis_robot_(cv::Size(1280, 1000)),
151 drawn_nodes_(),
152 display_count_(0),
milind-u8cc03da2023-03-25 23:00:39 -0700153 last_draw_time_(aos::distributed_clock::min_time),
154 last_H_world_robot_(Eigen::Matrix4d::Identity()),
155 max_delta_T_world_robot_(0.0) {
milind-u2ab4db12023-03-25 21:59:23 -0700156 constexpr size_t kNumPis = 4;
milind-u8b0f4782023-04-15 13:59:29 -0700157 // TODO(milind): add a flag to support replaying april detection from full
158 // logs as well.
milind-u2ab4db12023-03-25 21:59:23 -0700159 for (size_t i = 1; i <= kNumPis; i++) {
milind-u2ab4db12023-03-25 21:59:23 -0700160 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
161 "y2023.Constants");
162 }
163
164 reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants");
165
166 reader_->Register();
167
168 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
169 FLAGS_constants_path);
170
171 for (size_t i = 1; i < kNumPis; i++) {
172 std::string node_name = "pi" + std::to_string(i);
173 const aos::Node *pi =
174 aos::configuration::GetNode(reader_->configuration(), node_name);
milind-u2ab4db12023-03-25 21:59:23 -0700175 mapping_event_loops_.emplace_back(
176 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
177 pi));
178 HandlePiCaptures(
milind-u2ab4db12023-03-25 21:59:23 -0700179 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
180 }
181
182 if (!FLAGS_mcap_output_path.empty()) {
183 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
184 const aos::Node *node =
185 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
186 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
187 [this, node]() {
188 mcap_event_loop_ =
189 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
190 relogger_ = std::make_unique<aos::McapLogger>(
191 mcap_event_loop_.get(), FLAGS_mcap_output_path,
192 aos::McapLogger::Serialization::kFlatbuffer,
193 aos::McapLogger::CanonicalChannelNames::kShortened,
194 aos::McapLogger::Compression::kLz4);
195 });
196 }
197
milind-u8f4e43e2023-04-09 17:11:19 -0700198 if (FLAGS_visualize_solver) {
milind-u2ab4db12023-03-25 21:59:23 -0700199 vis_robot_.ClearImage();
200 const double kFocalLength = 500.0;
201 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
202 }
203}
204
205TargetMapperReplay::~TargetMapperReplay() {
206 // Clean up all the pointers
207 for (auto &detector_ptr : detectors_) {
208 detector_ptr.reset();
209 }
210}
211
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800212// Add detected apriltag poses relative to the robot to
213// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700214void TargetMapperReplay::HandleAprilTags(
215 const TargetMap &map,
216 aos::distributed_clock::time_point pi_distributed_time,
217 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700218 bool drew = false;
219 std::stringstream label;
220 label << node_name << " - ";
221
milind-u3f5f83c2023-01-29 15:23:51 -0800222 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700223 // Skip detections with invalid ids
milind-u8f4e43e2023-04-09 17:11:19 -0700224 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
225 FLAGS_min_target_id ||
226 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
227 FLAGS_max_target_id) {
228 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
milind-ufbc5c812023-04-06 21:24:29 -0700229 continue;
230 }
231
milind-u5ddd5152023-03-04 15:19:17 -0800232 // Skip detections with high pose errors
233 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-u8f4e43e2023-04-09 17:11:19 -0700234 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700235 << " due to pose error of " << target_pose_fbs->pose_error();
236 continue;
237 }
238 // Skip detections with high pose error ratios
239 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
milind-u8f4e43e2023-04-09 17:11:19 -0700240 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700241 << " due to pose error ratio of "
242 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800243 continue;
244 }
245
milind-u3f5f83c2023-01-29 15:23:51 -0800246 const TargetMapper::TargetPose target_pose =
247 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800248
milind-uee67abd2023-02-23 18:26:55 -0800249 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800250 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800251 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800252 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800253
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800254 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800255 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800256 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800257 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800258
milind-u09fb1252023-01-28 19:21:41 -0800259 CHECK(map.has_monotonic_timestamp_ns())
260 << "Need detection timestamps for mapping";
261
milind-u2ab4db12023-03-25 21:59:23 -0700262 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800263 DataAdapter::TimestampedDetection{
264 .time = pi_distributed_time,
265 .H_robot_target = H_robot_target,
266 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800267 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800268 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700269
milind-u8f4e43e2023-04-09 17:11:19 -0700270 if (FLAGS_visualize_solver) {
milind-ua30a4a12023-03-24 20:49:41 -0700271 // If we've already drawn in the current image,
272 // display it before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700273 if (drawn_nodes_.count(node_name) != 0) {
274 display_count_++;
275 cv::putText(vis_robot_.image_,
276 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700277 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
278 cv::Scalar(255, 255, 255));
279
milind-u2ab4db12023-03-25 21:59:23 -0700280 if (display_count_ >= FLAGS_skip_to) {
281 cv::imshow("View", vis_robot_.image_);
milind-u8cc03da2023-03-25 23:00:39 -0700282 cv::waitKey(max_delta_T_world_robot_ > FLAGS_pause_on_distance
283 ? 0
284 : FLAGS_wait_key);
285 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700286 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700287 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700288 }
milind-u2ab4db12023-03-25 21:59:23 -0700289 vis_robot_.ClearImage();
290 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700291 }
292
Jim Ostrowski49be8232023-03-23 01:00:14 -0700293 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700294 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700295 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700296 VLOG(2) << node_name << ", " << target_pose_fbs->id()
297 << ", t = " << pi_distributed_time
298 << ", pose_error = " << target_pose_fbs->pose_error()
299 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
300 << ", robot_pos (x,y,z) + "
301 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700302
303 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700304 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
305 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700306
milind-u2ab4db12023-03-25 21:59:23 -0700307 vis_robot_.DrawRobotOutline(H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -0700308 std::to_string(target_pose_fbs->id()),
309 kPiColors.at(node_name));
310
milind-u2ab4db12023-03-25 21:59:23 -0700311 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700312 std::to_string(target_pose_fbs->id()),
313 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700314
315 double delta_T_world_robot =
316 (H_world_robot.translation() - last_H_world_robot_.translation())
317 .norm();
318 max_delta_T_world_robot_ =
319 std::max(delta_T_world_robot, max_delta_T_world_robot_);
320
milind-ua30a4a12023-03-24 20:49:41 -0700321 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700322 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700323 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700324 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800325 }
milind-ua30a4a12023-03-24 20:49:41 -0700326 if (drew) {
327 size_t pi_number =
328 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
milind-u2ab4db12023-03-25 21:59:23 -0700329 cv::putText(vis_robot_.image_, label.str(),
milind-ua30a4a12023-03-24 20:49:41 -0700330 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
331 kPiColors.at(node_name));
332
milind-u2ab4db12023-03-25 21:59:23 -0700333 drawn_nodes_.emplace(node_name);
334 } else if (pi_distributed_time - last_draw_time_ >
milind-u52db3362023-03-25 20:09:22 -0700335 std::chrono::milliseconds(30) &&
milind-u2ab4db12023-03-25 21:59:23 -0700336 display_count_ >= FLAGS_skip_to) {
milind-u52db3362023-03-25 20:09:22 -0700337 // Clear the image if we haven't draw in a while
milind-u2ab4db12023-03-25 21:59:23 -0700338 vis_robot_.ClearImage();
339 cv::imshow("View", vis_robot_.image_);
milind-u52db3362023-03-25 20:09:22 -0700340 cv::waitKey(FLAGS_wait_key);
milind-u8cc03da2023-03-25 23:00:39 -0700341 max_delta_T_world_robot_ = 0.0;
milind-ua30a4a12023-03-24 20:49:41 -0700342 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800343}
344
milind-u8b0f4782023-04-15 13:59:29 -0700345void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) {
milind-uf2a4e322023-02-01 19:33:10 -0800346 // Get the camera extrinsics
milind-u8b0f4782023-04-15 13:59:29 -0700347 const frc971::constants::ConstantsFetcher<Constants> constants(
348 mapping_event_loop);
349 const auto *calibration = FindCameraCalibration(
350 constants.constants(), mapping_event_loop->node()->name()->string_view());
351 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
milind-uf2a4e322023-02-01 19:33:10 -0800352 Eigen::Matrix4d extrinsics_matrix;
353 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
354 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
355
milind-uf3ab8ba2023-02-04 17:56:16 -0800356 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800357 aos::distributed_clock::time_point pi_distributed_time =
milind-u2ab4db12023-03-25 21:59:23 -0700358 reader_->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800359 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800360 ->ToDistributedClock(aos::monotonic_clock::time_point(
361 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800362
milind-u8b0f4782023-04-15 13:59:29 -0700363 std::string node_name = mapping_event_loop->node()->name()->str();
milind-u2ab4db12023-03-25 21:59:23 -0700364 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
milind-u09fb1252023-01-28 19:21:41 -0800365 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800366}
367
milind-u2ab4db12023-03-25 21:59:23 -0700368void TargetMapperReplay::MaybeSolve() {
369 if (FLAGS_solve) {
370 auto target_constraints =
371 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
372
milind-ufbc5c812023-04-06 21:24:29 -0700373 // Remove constraints between the two sides of the field - these are
374 // basically garbage because of how far the camera is. We will use seeding
375 // below to connect the two sides
376 target_constraints.erase(
377 std::remove_if(target_constraints.begin(), target_constraints.end(),
378 [](const auto &constraint) {
379 constexpr TargetMapper::TargetId kMaxRedId = 4;
380 TargetMapper::TargetId min_id =
381 std::min(constraint.id_begin, constraint.id_end);
382 TargetMapper::TargetId max_id =
383 std::max(constraint.id_begin, constraint.id_end);
384 return (min_id <= kMaxRedId && max_id > kMaxRedId);
385 }),
386 target_constraints.end());
387
milind-u2ab4db12023-03-25 21:59:23 -0700388 TargetMapper mapper(FLAGS_json_path, target_constraints);
389 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
milind-u401de982023-04-14 17:32:03 -0700390
391 if (!FLAGS_dump_constraints_to.empty()) {
392 mapper.DumpConstraints(FLAGS_dump_constraints_to);
393 }
394 if (!FLAGS_dump_stats_to.empty()) {
395 mapper.DumpStats(FLAGS_dump_stats_to);
396 }
milind-u2ab4db12023-03-25 21:59:23 -0700397 }
398}
399
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800400void MappingMain(int argc, char *argv[]) {
401 std::vector<std::string> unsorted_logfiles =
402 aos::logger::FindLogs(argc, argv);
403
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800404 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
405
milind-u4a5ef8a2023-03-05 14:10:23 -0800406 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
407 (FLAGS_config.empty()
408 ? std::nullopt
409 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800410
milind-u2ab4db12023-03-25 21:59:23 -0700411 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800412 aos::logger::LogReader reader(
413 aos::logger::SortParts(unsorted_logfiles),
414 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800415
milind-u2ab4db12023-03-25 21:59:23 -0700416 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800417 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700418 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800419}
420
421} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800422} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800423
424int main(int argc, char **argv) {
425 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800426 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800427}