blob: 45c00ceaeb350b3eb946538b58f2fec56084b54c [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/target_mapper.h"
Jim Ostrowski49be8232023-03-23 01:00:14 -07009#include "frc971/vision/visualize_robot.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080010#include "opencv2/aruco.hpp"
11#include "opencv2/calib3d.hpp"
12#include "opencv2/core/eigen.hpp"
13#include "opencv2/features2d.hpp"
14#include "opencv2/highgui.hpp"
15#include "opencv2/highgui/highgui.hpp"
16#include "opencv2/imgproc.hpp"
milind-uc5a494f2023-02-24 15:39:22 -080017#include "y2023/constants/simulated_constants_sender.h"
milind-u09fb1252023-01-28 19:21:41 -080018#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080019#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080020
milind-uc5a494f2023-02-24 15:39:22 -080021DEFINE_string(json_path, "y2023/vision/maps/target_map.json",
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080022 "Specify path for json with initial pose guesses.");
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");
27DEFINE_string(output_dir, "y2023/vision/maps",
28 "Directory to write solved target map to");
29DEFINE_string(field_name, "charged_up",
30 "Field name, for the output json filename and flatbuffer field");
Jim Ostrowski49be8232023-03-23 01:00:14 -070031DEFINE_int32(team_number, 0,
32 "Required: Use the calibration for a node with this team number");
Jim Ostrowski68965cd2023-03-01 20:32:51 -080033DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output.");
34DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1.");
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");
milind-ua30a4a12023-03-24 20:49:41 -070040DEFINE_uint64(wait_key, 0,
41 "Time in ms to wait between images, if no click (0 to wait "
42 "indefinitely until click).");
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");
milind-ude9045f2023-03-25 18:17:12 -070046DEFINE_uint64(skip_to, 1,
47 "Start at combined image of this number (1 is the first image)");
milind-ua30a4a12023-03-24 20:49:41 -070048DEFINE_bool(solve, true, "Whether to solve for the field's target map.");
milind-ufbc5c812023-04-06 21:24:29 -070049DEFINE_string(dump_constraints_to, "/tmp/constraints.txt",
50 "Write the target constraints to this path");
milind-u8f4e43e2023-04-09 17:11:19 -070051DECLARE_int32(frozen_target_id);
52DECLARE_int32(min_target_id);
53DECLARE_int32(max_target_id);
54DECLARE_bool(visualize_solver);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080055
milind-u16e3a082023-01-21 13:53:43 -080056namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080057namespace vision {
58using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080059using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080060using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080061using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080062using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070063using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080064namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080065
milind-u2ab4db12023-03-25 21:59:23 -070066// Class to handle reading target poses from a replayed log,
67// displaying various debug info, and passing the poses to
68// frc971::vision::TargetMapper for field mapping.
69class TargetMapperReplay {
70 public:
71 TargetMapperReplay(aos::logger::LogReader *reader);
72 ~TargetMapperReplay();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080073
milind-u2ab4db12023-03-25 21:59:23 -070074 // Solves for the target poses with the accumulated detections if FLAGS_solve.
75 void MaybeSolve();
76
77 private:
78 static constexpr int kImageWidth = 1280;
79 // Map from pi node name to color for drawing
80 static const std::map<std::string, cv::Scalar> kPiColors;
81 // Contains fixed target poses without solving, for use with visualization
82 static const TargetMapper kFixedTargetMapper;
83
84 // Change reference frame from camera to robot
85 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
86 Eigen::Affine3d extrinsics);
87
88 // Adds april tag detections into the detection list, and handles
89 // visualization
90 void HandleAprilTags(const TargetMap &map,
91 aos::distributed_clock::time_point pi_distributed_time,
92 std::string node_name, Eigen::Affine3d extrinsics);
93
94 // Gets images from the given pi and passes apriltag positions to
95 // HandleAprilTags()
milind-u8b0f4782023-04-15 13:59:29 -070096 void HandlePiCaptures(aos::EventLoop *mapping_event_loop);
milind-u2ab4db12023-03-25 21:59:23 -070097
98 aos::logger::LogReader *reader_;
99 // April tag detections from all pis
100 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
101 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_;
102
103 VisualizeRobot vis_robot_;
104 // Set of node names which are currently drawn on the display
105 std::set<std::string> drawn_nodes_;
106 // Number of frames displayed
107 size_t display_count_;
108 // Last time we drew onto the display image.
109 // This is different from when we actually call imshow() to update
110 // the display window
111 aos::distributed_clock::time_point last_draw_time_;
112
milind-u8cc03da2023-03-25 23:00:39 -0700113 Eigen::Affine3d last_H_world_robot_;
114 // Maximum distance between consecutive T_world_robot's in one display frame,
115 // used to determine if we need to pause for the user to see this frame
116 // clearly
117 double max_delta_T_world_robot_;
118
milind-u2ab4db12023-03-25 21:59:23 -0700119 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
120
121 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
122 std::unique_ptr<aos::McapLogger> relogger_;
123};
124
125const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700126 {"pi1", cv::Scalar(255, 0, 255)},
127 {"pi2", cv::Scalar(255, 255, 0)},
128 {"pi3", cv::Scalar(0, 255, 255)},
129 {"pi4", cv::Scalar(255, 165, 0)},
130};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700131
milind-u2ab4db12023-03-25 21:59:23 -0700132const auto TargetMapperReplay::kFixedTargetMapper =
133 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
134
135Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
136 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
137 const Eigen::Affine3d H_robot_camera = extrinsics;
138 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
139 return H_robot_target;
140}
141
142TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
143 : reader_(reader),
144 timestamped_target_detections_(),
145 detectors_(),
146 vis_robot_(cv::Size(1280, 1000)),
147 drawn_nodes_(),
148 display_count_(0),
milind-u8cc03da2023-03-25 23:00:39 -0700149 last_draw_time_(aos::distributed_clock::min_time),
150 last_H_world_robot_(Eigen::Matrix4d::Identity()),
151 max_delta_T_world_robot_(0.0) {
milind-u2ab4db12023-03-25 21:59:23 -0700152 constexpr size_t kNumPis = 4;
milind-u8b0f4782023-04-15 13:59:29 -0700153 // TODO(milind): add a flag to support replaying april detection from full
154 // logs as well.
milind-u2ab4db12023-03-25 21:59:23 -0700155 for (size_t i = 1; i <= kNumPis; i++) {
milind-u2ab4db12023-03-25 21:59:23 -0700156 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
157 "y2023.Constants");
158 }
159
160 reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants");
161
162 reader_->Register();
163
164 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
165 FLAGS_constants_path);
166
167 for (size_t i = 1; i < kNumPis; i++) {
168 std::string node_name = "pi" + std::to_string(i);
169 const aos::Node *pi =
170 aos::configuration::GetNode(reader_->configuration(), node_name);
milind-u2ab4db12023-03-25 21:59:23 -0700171 mapping_event_loops_.emplace_back(
172 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
173 pi));
174 HandlePiCaptures(
milind-u2ab4db12023-03-25 21:59:23 -0700175 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
176 }
177
178 if (!FLAGS_mcap_output_path.empty()) {
179 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
180 const aos::Node *node =
181 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
182 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
183 [this, node]() {
184 mcap_event_loop_ =
185 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
186 relogger_ = std::make_unique<aos::McapLogger>(
187 mcap_event_loop_.get(), FLAGS_mcap_output_path,
188 aos::McapLogger::Serialization::kFlatbuffer,
189 aos::McapLogger::CanonicalChannelNames::kShortened,
190 aos::McapLogger::Compression::kLz4);
191 });
192 }
193
milind-u8f4e43e2023-04-09 17:11:19 -0700194 if (FLAGS_visualize_solver) {
milind-u2ab4db12023-03-25 21:59:23 -0700195 vis_robot_.ClearImage();
196 const double kFocalLength = 500.0;
197 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
198 }
199}
200
201TargetMapperReplay::~TargetMapperReplay() {
202 // Clean up all the pointers
203 for (auto &detector_ptr : detectors_) {
204 detector_ptr.reset();
205 }
206}
207
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800208// Add detected apriltag poses relative to the robot to
209// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700210void TargetMapperReplay::HandleAprilTags(
211 const TargetMap &map,
212 aos::distributed_clock::time_point pi_distributed_time,
213 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700214 bool drew = false;
215 std::stringstream label;
216 label << node_name << " - ";
217
milind-u3f5f83c2023-01-29 15:23:51 -0800218 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700219 // Skip detections with invalid ids
milind-u8f4e43e2023-04-09 17:11:19 -0700220 if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
221 FLAGS_min_target_id ||
222 static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
223 FLAGS_max_target_id) {
224 VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id();
milind-ufbc5c812023-04-06 21:24:29 -0700225 continue;
226 }
227
milind-u5ddd5152023-03-04 15:19:17 -0800228 // Skip detections with high pose errors
229 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-u8f4e43e2023-04-09 17:11:19 -0700230 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700231 << " due to pose error of " << target_pose_fbs->pose_error();
232 continue;
233 }
234 // Skip detections with high pose error ratios
235 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
milind-u8f4e43e2023-04-09 17:11:19 -0700236 VLOG(1) << "Skipping tag " << target_pose_fbs->id()
milind-ude9045f2023-03-25 18:17:12 -0700237 << " due to pose error ratio of "
238 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800239 continue;
240 }
241
milind-u3f5f83c2023-01-29 15:23:51 -0800242 const TargetMapper::TargetPose target_pose =
243 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800244
milind-uee67abd2023-02-23 18:26:55 -0800245 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800246 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800247 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800248 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800249
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800250 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800251 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800252 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800253 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800254
milind-u09fb1252023-01-28 19:21:41 -0800255 CHECK(map.has_monotonic_timestamp_ns())
256 << "Need detection timestamps for mapping";
257
milind-u2ab4db12023-03-25 21:59:23 -0700258 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800259 DataAdapter::TimestampedDetection{
260 .time = pi_distributed_time,
261 .H_robot_target = H_robot_target,
262 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800263 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800264 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700265
milind-u8f4e43e2023-04-09 17:11:19 -0700266 if (FLAGS_visualize_solver) {
milind-ua30a4a12023-03-24 20:49:41 -0700267 // If we've already drawn in the current image,
268 // display it before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700269 if (drawn_nodes_.count(node_name) != 0) {
270 display_count_++;
271 cv::putText(vis_robot_.image_,
272 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700273 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
274 cv::Scalar(255, 255, 255));
275
milind-u2ab4db12023-03-25 21:59:23 -0700276 if (display_count_ >= FLAGS_skip_to) {
277 cv::imshow("View", vis_robot_.image_);
milind-u8cc03da2023-03-25 23:00:39 -0700278 cv::waitKey(max_delta_T_world_robot_ > FLAGS_pause_on_distance
279 ? 0
280 : FLAGS_wait_key);
281 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700282 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700283 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700284 }
milind-u2ab4db12023-03-25 21:59:23 -0700285 vis_robot_.ClearImage();
286 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700287 }
288
Jim Ostrowski49be8232023-03-23 01:00:14 -0700289 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700290 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700291 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700292 VLOG(2) << node_name << ", " << target_pose_fbs->id()
293 << ", t = " << pi_distributed_time
294 << ", pose_error = " << target_pose_fbs->pose_error()
295 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
296 << ", robot_pos (x,y,z) + "
297 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700298
299 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700300 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
301 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700302
milind-u2ab4db12023-03-25 21:59:23 -0700303 vis_robot_.DrawRobotOutline(H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -0700304 std::to_string(target_pose_fbs->id()),
305 kPiColors.at(node_name));
306
milind-u2ab4db12023-03-25 21:59:23 -0700307 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700308 std::to_string(target_pose_fbs->id()),
309 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700310
311 double delta_T_world_robot =
312 (H_world_robot.translation() - last_H_world_robot_.translation())
313 .norm();
314 max_delta_T_world_robot_ =
315 std::max(delta_T_world_robot, max_delta_T_world_robot_);
316
milind-ua30a4a12023-03-24 20:49:41 -0700317 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700318 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700319 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700320 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800321 }
milind-ua30a4a12023-03-24 20:49:41 -0700322 if (drew) {
323 size_t pi_number =
324 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
milind-u2ab4db12023-03-25 21:59:23 -0700325 cv::putText(vis_robot_.image_, label.str(),
milind-ua30a4a12023-03-24 20:49:41 -0700326 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
327 kPiColors.at(node_name));
328
milind-u2ab4db12023-03-25 21:59:23 -0700329 drawn_nodes_.emplace(node_name);
330 } else if (pi_distributed_time - last_draw_time_ >
milind-u52db3362023-03-25 20:09:22 -0700331 std::chrono::milliseconds(30) &&
milind-u2ab4db12023-03-25 21:59:23 -0700332 display_count_ >= FLAGS_skip_to) {
milind-u52db3362023-03-25 20:09:22 -0700333 // Clear the image if we haven't draw in a while
milind-u2ab4db12023-03-25 21:59:23 -0700334 vis_robot_.ClearImage();
335 cv::imshow("View", vis_robot_.image_);
milind-u52db3362023-03-25 20:09:22 -0700336 cv::waitKey(FLAGS_wait_key);
milind-u8cc03da2023-03-25 23:00:39 -0700337 max_delta_T_world_robot_ = 0.0;
milind-ua30a4a12023-03-24 20:49:41 -0700338 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800339}
340
milind-u8b0f4782023-04-15 13:59:29 -0700341void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) {
milind-uf2a4e322023-02-01 19:33:10 -0800342 // Get the camera extrinsics
milind-u8b0f4782023-04-15 13:59:29 -0700343 const frc971::constants::ConstantsFetcher<Constants> constants(
344 mapping_event_loop);
345 const auto *calibration = FindCameraCalibration(
346 constants.constants(), mapping_event_loop->node()->name()->string_view());
347 cv::Mat extrinsics_cv = CameraExtrinsics(calibration).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-uf3ab8ba2023-02-04 17:56:16 -0800352 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800353 aos::distributed_clock::time_point pi_distributed_time =
milind-u2ab4db12023-03-25 21:59:23 -0700354 reader_->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800355 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800356 ->ToDistributedClock(aos::monotonic_clock::time_point(
357 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800358
milind-u8b0f4782023-04-15 13:59:29 -0700359 std::string node_name = mapping_event_loop->node()->name()->str();
milind-u2ab4db12023-03-25 21:59:23 -0700360 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
milind-u09fb1252023-01-28 19:21:41 -0800361 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800362}
363
milind-u2ab4db12023-03-25 21:59:23 -0700364void TargetMapperReplay::MaybeSolve() {
365 if (FLAGS_solve) {
366 auto target_constraints =
367 DataAdapter::MatchTargetDetections(timestamped_target_detections_);
368
milind-ufbc5c812023-04-06 21:24:29 -0700369 // Remove constraints between the two sides of the field - these are
370 // basically garbage because of how far the camera is. We will use seeding
371 // below to connect the two sides
372 target_constraints.erase(
373 std::remove_if(target_constraints.begin(), target_constraints.end(),
374 [](const auto &constraint) {
375 constexpr TargetMapper::TargetId kMaxRedId = 4;
376 TargetMapper::TargetId min_id =
377 std::min(constraint.id_begin, constraint.id_end);
378 TargetMapper::TargetId max_id =
379 std::max(constraint.id_begin, constraint.id_end);
380 return (min_id <= kMaxRedId && max_id > kMaxRedId);
381 }),
382 target_constraints.end());
383
384 if (!FLAGS_dump_constraints_to.empty()) {
385 std::ofstream fout(FLAGS_dump_constraints_to);
386 for (const auto &constraint : target_constraints) {
387 fout << constraint << std::endl;
388 }
389 fout.flush();
390 fout.close();
391 }
392
393 // Give seed constraints with a higher confidence to ground the solver.
394 // This "distance from camera" controls the noise of the seed measurement
395 constexpr double kSeedDistanceFromCamera = 1.0;
396
397 constexpr double kSeedDistortionFactor = 0.0;
398 const DataAdapter::TimestampedDetection frozen_detection_seed = {
399 .time = aos::distributed_clock::min_time,
400 .H_robot_target = PoseUtils::Pose3dToAffine3d(
401 kFixedTargetMapper.GetTargetPoseById(FLAGS_frozen_target_id)
402 .value()
403 .pose),
404 .distance_from_camera = kSeedDistanceFromCamera,
405 .distortion_factor = kSeedDistortionFactor,
milind-u8f4e43e2023-04-09 17:11:19 -0700406 .id = FLAGS_frozen_target_id};
milind-ufbc5c812023-04-06 21:24:29 -0700407
milind-u8f4e43e2023-04-09 17:11:19 -0700408 constexpr TargetMapper::TargetId kAbsMinTargetId = 1;
409 constexpr TargetMapper::TargetId kAbsMaxTargetId = 8;
410 for (TargetMapper::TargetId id = kAbsMinTargetId; id <= kAbsMaxTargetId;
411 id++) {
412 if (id == FLAGS_frozen_target_id) {
milind-ufbc5c812023-04-06 21:24:29 -0700413 continue;
414 }
415
416 const DataAdapter::TimestampedDetection detection_seed = {
417 .time = aos::distributed_clock::min_time,
418 .H_robot_target = PoseUtils::Pose3dToAffine3d(
419 kFixedTargetMapper.GetTargetPoseById(id).value().pose),
420 .distance_from_camera = kSeedDistanceFromCamera,
421 .distortion_factor = kSeedDistortionFactor,
422 .id = id};
423 target_constraints.emplace_back(DataAdapter::ComputeTargetConstraint(
424 frozen_detection_seed, detection_seed,
425 DataAdapter::ComputeConfidence(frozen_detection_seed,
426 detection_seed)));
427 }
428
milind-u2ab4db12023-03-25 21:59:23 -0700429 TargetMapper mapper(FLAGS_json_path, target_constraints);
430 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
431 }
432}
433
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800434void MappingMain(int argc, char *argv[]) {
435 std::vector<std::string> unsorted_logfiles =
436 aos::logger::FindLogs(argc, argv);
437
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800438 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
439
milind-u4a5ef8a2023-03-05 14:10:23 -0800440 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
441 (FLAGS_config.empty()
442 ? std::nullopt
443 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800444
milind-u2ab4db12023-03-25 21:59:23 -0700445 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800446 aos::logger::LogReader reader(
447 aos::logger::SortParts(unsorted_logfiles),
448 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800449
milind-u2ab4db12023-03-25 21:59:23 -0700450 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800451 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700452 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800453}
454
455} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800456} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800457
458int main(int argc, char **argv) {
459 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800460 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800461}