blob: af4c36c74f13ab95af61cd8a14f8b0b0445ab1ab [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-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");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070027DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt",
28 "Write the target constraints to this path");
29DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt",
30 "Write the mapping stats to this path");
milind-uc5a494f2023-02-24 15:39:22 -080031DEFINE_string(field_name, "charged_up",
32 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070033DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
34 "Specify path for json with initial pose guesses.");
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");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070040DEFINE_string(mcap_output_path, "", "Log to output.");
41DEFINE_string(output_dir, "y2023/vision/maps",
42 "Directory to write solved target map to");
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");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070046DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
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.");
Jim Ostrowski2f2685f2023-03-25 11:57:54 -070050DEFINE_int32(team_number, 0,
51 "Required: Use the calibration for a node with this team number");
52DEFINE_uint64(wait_key, 1,
53 "Time in ms to wait between images, if no click (0 to wait "
54 "indefinitely until click).");
55
milind-u8f4e43e2023-04-09 17:11:19 -070056DECLARE_int32(frozen_target_id);
57DECLARE_int32(min_target_id);
58DECLARE_int32(max_target_id);
59DECLARE_bool(visualize_solver);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080060
Stephan Pleinesf63bde82024-01-13 15:59:33 -080061namespace y2023::vision {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080062using 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);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080076
milind-u2ab4db12023-03-25 21:59:23 -070077 // Solves for the target poses with the accumulated detections if FLAGS_solve.
78 void MaybeSolve();
79
80 private:
81 static constexpr int kImageWidth = 1280;
82 // Map from pi node name to color for drawing
83 static const std::map<std::string, cv::Scalar> kPiColors;
84 // Contains fixed target poses without solving, for use with visualization
85 static const TargetMapper kFixedTargetMapper;
86
87 // Change reference frame from camera to robot
88 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
89 Eigen::Affine3d extrinsics);
90
91 // Adds april tag detections into the detection list, and handles
92 // visualization
93 void HandleAprilTags(const TargetMap &map,
94 aos::distributed_clock::time_point pi_distributed_time,
95 std::string node_name, Eigen::Affine3d extrinsics);
96
97 // Gets images from the given pi and passes apriltag positions to
98 // HandleAprilTags()
milind-u8b0f4782023-04-15 13:59:29 -070099 void HandlePiCaptures(aos::EventLoop *mapping_event_loop);
milind-u2ab4db12023-03-25 21:59:23 -0700100
101 aos::logger::LogReader *reader_;
102 // April tag detections from all pis
103 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
milind-u2ab4db12023-03-25 21:59:23 -0700104
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_(),
milind-u2ab4db12023-03-25 21:59:23 -0700147 vis_robot_(cv::Size(1280, 1000)),
148 drawn_nodes_(),
149 display_count_(0),
milind-u8cc03da2023-03-25 23:00:39 -0700150 last_draw_time_(aos::distributed_clock::min_time),
151 last_H_world_robot_(Eigen::Matrix4d::Identity()),
152 max_delta_T_world_robot_(0.0) {
milind-u2ab4db12023-03-25 21:59:23 -0700153 constexpr size_t kNumPis = 4;
milind-u8b0f4782023-04-15 13:59:29 -0700154 // TODO(milind): add a flag to support replaying april detection from full
155 // logs as well.
milind-u2ab4db12023-03-25 21:59:23 -0700156 for (size_t i = 1; i <= kNumPis; i++) {
milind-u2ab4db12023-03-25 21:59:23 -0700157 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
158 "y2023.Constants");
159 }
160
161 reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants");
Jim Ostrowski68c321d2023-11-14 21:36:28 -0800162 reader_->RemapLoggedChannel("/logger/constants", "y2023.Constants");
163 reader_->RemapLoggedChannel("/roborio/constants", "y2023.Constants");
milind-u2ab4db12023-03-25 21:59:23 -0700164
165 reader_->Register();
166
167 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
168 FLAGS_constants_path);
169
170 for (size_t i = 1; i < kNumPis; i++) {
171 std::string node_name = "pi" + std::to_string(i);
172 const aos::Node *pi =
173 aos::configuration::GetNode(reader_->configuration(), node_name);
milind-u2ab4db12023-03-25 21:59:23 -0700174 mapping_event_loops_.emplace_back(
175 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
176 pi));
177 HandlePiCaptures(
milind-u2ab4db12023-03-25 21:59:23 -0700178 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
179 }
180
181 if (!FLAGS_mcap_output_path.empty()) {
182 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
183 const aos::Node *node =
184 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
185 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
186 [this, node]() {
187 mcap_event_loop_ =
188 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
189 relogger_ = std::make_unique<aos::McapLogger>(
190 mcap_event_loop_.get(), FLAGS_mcap_output_path,
191 aos::McapLogger::Serialization::kFlatbuffer,
192 aos::McapLogger::CanonicalChannelNames::kShortened,
193 aos::McapLogger::Compression::kLz4);
194 });
195 }
196
milind-u8f4e43e2023-04-09 17:11:19 -0700197 if (FLAGS_visualize_solver) {
milind-u2ab4db12023-03-25 21:59:23 -0700198 vis_robot_.ClearImage();
199 const double kFocalLength = 500.0;
200 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
201 }
202}
203
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800204// Add detected apriltag poses relative to the robot to
205// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700206void TargetMapperReplay::HandleAprilTags(
207 const TargetMap &map,
208 aos::distributed_clock::time_point pi_distributed_time,
209 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700210 bool drew = false;
211 std::stringstream label;
212 label << node_name << " - ";
213
milind-u3f5f83c2023-01-29 15:23:51 -0800214 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700215 // Skip detections with invalid ids
milind-u8f4e43e2023-04-09 17:11:19 -0700216 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
217 FLAGS_min_target_id ||
218 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
219 FLAGS_max_target_id) {
220 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
milind-ufbc5c812023-04-06 21:24:29 -0700221 continue;
222 }
223
milind-u5ddd5152023-03-04 15:19:17 -0800224 // Skip detections with high pose errors
225 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-u8f4e43e2023-04-09 17:11:19 -0700226 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700227 << " due to pose error of " << target_pose_fbs->pose_error();
228 continue;
229 }
230 // Skip detections with high pose error ratios
231 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
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 ratio of "
234 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800235 continue;
236 }
237
milind-u3f5f83c2023-01-29 15:23:51 -0800238 const TargetMapper::TargetPose target_pose =
239 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800240
milind-uee67abd2023-02-23 18:26:55 -0800241 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800242 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800243 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800244 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800245
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800246 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800247 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800248 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800249 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800250
milind-u09fb1252023-01-28 19:21:41 -0800251 CHECK(map.has_monotonic_timestamp_ns())
252 << "Need detection timestamps for mapping";
253
milind-u2ab4db12023-03-25 21:59:23 -0700254 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800255 DataAdapter::TimestampedDetection{
256 .time = pi_distributed_time,
257 .H_robot_target = H_robot_target,
258 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800259 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800260 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700261
milind-u8f4e43e2023-04-09 17:11:19 -0700262 if (FLAGS_visualize_solver) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700263 // If we've already drawn this node_name in the current image,
264 // display the image before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700265 if (drawn_nodes_.count(node_name) != 0) {
266 display_count_++;
267 cv::putText(vis_robot_.image_,
268 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700269 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
270 cv::Scalar(255, 255, 255));
271
milind-u2ab4db12023-03-25 21:59:23 -0700272 if (display_count_ >= FLAGS_skip_to) {
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700273 VLOG(1) << "Showing image for node " << node_name
274 << " since we've drawn it already";
milind-u2ab4db12023-03-25 21:59:23 -0700275 cv::imshow("View", vis_robot_.image_);
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700276 // Pause if delta_T is too large, but only after first image (to make
277 // sure the delta's are correct
278 if (max_delta_T_world_robot_ > FLAGS_pause_on_distance &&
279 display_count_ > 1) {
280 LOG(INFO) << "Pausing since the delta between robot estimates is "
281 << max_delta_T_world_robot_ << " which is > threshold of "
282 << FLAGS_pause_on_distance;
283 cv::waitKey(0);
284 } else {
285 cv::waitKey(FLAGS_wait_key);
286 }
milind-u8cc03da2023-03-25 23:00:39 -0700287 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700288 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700289 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700290 }
milind-u2ab4db12023-03-25 21:59:23 -0700291 vis_robot_.ClearImage();
292 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700293 }
294
Jim Ostrowski49be8232023-03-23 01:00:14 -0700295 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700296 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700297 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700298 VLOG(2) << node_name << ", id " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700299 << ", t = " << pi_distributed_time
300 << ", pose_error = " << target_pose_fbs->pose_error()
301 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700302 << ", robot_pos (x,y,z) = "
milind-ude9045f2023-03-25 18:17:12 -0700303 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700304
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700305 label << "id " << target_pose_fbs->id() << ": err (% of max): "
milind-ude9045f2023-03-25 18:17:12 -0700306 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700307 << " err_ratio: " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700308
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700309 vis_robot_.DrawRobotOutline(H_world_robot, node_name,
milind-ua30a4a12023-03-24 20:49:41 -0700310 kPiColors.at(node_name));
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
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700321 VLOG(1) << "Drew in info for robot " << node_name << " and target #"
322 << target_pose_fbs->id();
milind-ua30a4a12023-03-24 20:49:41 -0700323 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700324 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700325 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700326 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800327 }
milind-ua30a4a12023-03-24 20:49:41 -0700328
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700329 if (FLAGS_visualize_solver) {
330 if (drew) {
331 // Collect all the labels from a given node, and add the text
332 size_t pi_number =
333 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
334 cv::putText(vis_robot_.image_, label.str(),
335 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN,
336 1.0, kPiColors.at(node_name));
337
338 drawn_nodes_.emplace(node_name);
339 } else if (pi_distributed_time - last_draw_time_ >
340 std::chrono::milliseconds(30) &&
341 display_count_ >= FLAGS_skip_to) {
342 cv::putText(vis_robot_.image_, "No detections", cv::Point(10, 0),
343 cv::FONT_HERSHEY_PLAIN, 1.0, kPiColors.at(node_name));
344 // Display and clear the image if we haven't draw in a while
345 VLOG(1) << "Displaying image due to time lapse";
346 cv::imshow("View", vis_robot_.image_);
347 cv::waitKey(FLAGS_wait_key);
348 vis_robot_.ClearImage();
349 max_delta_T_world_robot_ = 0.0;
350 drawn_nodes_.clear();
351 }
milind-ua30a4a12023-03-24 20:49:41 -0700352 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800353}
354
milind-u8b0f4782023-04-15 13:59:29 -0700355void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) {
milind-uf2a4e322023-02-01 19:33:10 -0800356 // Get the camera extrinsics
milind-u8b0f4782023-04-15 13:59:29 -0700357 const frc971::constants::ConstantsFetcher<Constants> constants(
358 mapping_event_loop);
359 const auto *calibration = FindCameraCalibration(
360 constants.constants(), mapping_event_loop->node()->name()->string_view());
361 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value();
milind-uf2a4e322023-02-01 19:33:10 -0800362 Eigen::Matrix4d extrinsics_matrix;
363 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
364 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
365
Austin Schuh612d95d2023-10-21 00:01:40 -0700366 mapping_event_loop->MakeWatcher(
367 "/camera", [this, mapping_event_loop, extrinsics](const TargetMap &map) {
368 aos::distributed_clock::time_point pi_distributed_time =
369 reader_->event_loop_factory()
370 ->GetNodeEventLoopFactory(mapping_event_loop->node())
371 ->ToDistributedClock(aos::monotonic_clock::time_point(
372 aos::monotonic_clock::duration(
373 map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800374
Austin Schuh612d95d2023-10-21 00:01:40 -0700375 std::string node_name = mapping_event_loop->node()->name()->str();
376 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
377 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800378}
379
milind-u2ab4db12023-03-25 21:59:23 -0700380void TargetMapperReplay::MaybeSolve() {
381 if (FLAGS_solve) {
382 auto target_constraints =
383 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
384
milind-ufbc5c812023-04-06 21:24:29 -0700385 // Remove constraints between the two sides of the field - these are
386 // basically garbage because of how far the camera is. We will use seeding
387 // below to connect the two sides
388 target_constraints.erase(
389 std::remove_if(target_constraints.begin(), target_constraints.end(),
390 [](const auto &constraint) {
391 constexpr TargetMapper::TargetId kMaxRedId = 4;
392 TargetMapper::TargetId min_id =
393 std::min(constraint.id_begin, constraint.id_end);
394 TargetMapper::TargetId max_id =
395 std::max(constraint.id_begin, constraint.id_end);
396 return (min_id <= kMaxRedId && max_id > kMaxRedId);
397 }),
398 target_constraints.end());
399
Jim Ostrowski7fde9b02023-09-09 23:33:58 -0700400 LOG(INFO) << "Solving for locations of tags with "
401 << target_constraints.size() << " constraints";
milind-u2ab4db12023-03-25 21:59:23 -0700402 TargetMapper mapper(FLAGS_json_path, target_constraints);
403 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
milind-u401de982023-04-14 17:32:03 -0700404
405 if (!FLAGS_dump_constraints_to.empty()) {
406 mapper.DumpConstraints(FLAGS_dump_constraints_to);
407 }
408 if (!FLAGS_dump_stats_to.empty()) {
409 mapper.DumpStats(FLAGS_dump_stats_to);
410 }
milind-u2ab4db12023-03-25 21:59:23 -0700411 }
412}
413
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800414void MappingMain(int argc, char *argv[]) {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800415 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
416
milind-u4a5ef8a2023-03-05 14:10:23 -0800417 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
418 (FLAGS_config.empty()
419 ? std::nullopt
420 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800421
milind-u2ab4db12023-03-25 21:59:23 -0700422 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800423 aos::logger::LogReader reader(
Austin Schuhc1609732023-06-26 11:51:28 -0700424 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
milind-u4a5ef8a2023-03-05 14:10:23 -0800425 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800426
milind-u2ab4db12023-03-25 21:59:23 -0700427 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800428 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700429 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800430}
431
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800432} // namespace y2023::vision
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800433
434int main(int argc, char **argv) {
435 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800436 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800437}