blob: ba5f5d9132a511b100b8d49dad09dec094c12783 [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-ufbc5c812023-04-06 21:24:29 -070050DEFINE_string(dump_constraints_to, "/tmp/constraints.txt",
51 "Write the target constraints to this path");
52DECLARE_uint64(frozen_target_id);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080053
milind-u16e3a082023-01-21 13:53:43 -080054namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080055namespace vision {
56using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080057using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080058using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080059using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080060using frc971::vision::TargetMapper;
milind-ua30a4a12023-03-24 20:49:41 -070061using frc971::vision::VisualizeRobot;
milind-u16e3a082023-01-21 13:53:43 -080062namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080063
milind-ufbc5c812023-04-06 21:24:29 -070064constexpr TargetMapper::TargetId kMinTargetId = 1;
65constexpr TargetMapper::TargetId kMaxTargetId = 8;
66
milind-u2ab4db12023-03-25 21:59:23 -070067// Class to handle reading target poses from a replayed log,
68// displaying various debug info, and passing the poses to
69// frc971::vision::TargetMapper for field mapping.
70class TargetMapperReplay {
71 public:
72 TargetMapperReplay(aos::logger::LogReader *reader);
73 ~TargetMapperReplay();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080074
milind-u2ab4db12023-03-25 21:59:23 -070075 // Solves for the target poses with the accumulated detections if FLAGS_solve.
76 void MaybeSolve();
77
78 private:
79 static constexpr int kImageWidth = 1280;
80 // Map from pi node name to color for drawing
81 static const std::map<std::string, cv::Scalar> kPiColors;
82 // Contains fixed target poses without solving, for use with visualization
83 static const TargetMapper kFixedTargetMapper;
84
85 // Change reference frame from camera to robot
86 static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
87 Eigen::Affine3d extrinsics);
88
89 // Adds april tag detections into the detection list, and handles
90 // visualization
91 void HandleAprilTags(const TargetMap &map,
92 aos::distributed_clock::time_point pi_distributed_time,
93 std::string node_name, Eigen::Affine3d extrinsics);
94
95 // Gets images from the given pi and passes apriltag positions to
96 // HandleAprilTags()
97 void HandlePiCaptures(aos::EventLoop *detection_event_loop,
98 aos::EventLoop *mapping_event_loop);
99
100 aos::logger::LogReader *reader_;
101 // April tag detections from all pis
102 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_;
103 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_;
104
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>> detection_event_loops_;
122 std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_;
123
124 std::unique_ptr<aos::EventLoop> mcap_event_loop_;
125 std::unique_ptr<aos::McapLogger> relogger_;
126};
127
128const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{
milind-ua30a4a12023-03-24 20:49:41 -0700129 {"pi1", cv::Scalar(255, 0, 255)},
130 {"pi2", cv::Scalar(255, 255, 0)},
131 {"pi3", cv::Scalar(0, 255, 255)},
132 {"pi4", cv::Scalar(255, 165, 0)},
133};
Jim Ostrowski49be8232023-03-23 01:00:14 -0700134
milind-u2ab4db12023-03-25 21:59:23 -0700135const auto TargetMapperReplay::kFixedTargetMapper =
136 TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{});
137
138Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection(
139 Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) {
140 const Eigen::Affine3d H_robot_camera = extrinsics;
141 const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
142 return H_robot_target;
143}
144
145TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader)
146 : reader_(reader),
147 timestamped_target_detections_(),
148 detectors_(),
149 vis_robot_(cv::Size(1280, 1000)),
150 drawn_nodes_(),
151 display_count_(0),
milind-u8cc03da2023-03-25 23:00:39 -0700152 last_draw_time_(aos::distributed_clock::min_time),
153 last_H_world_robot_(Eigen::Matrix4d::Identity()),
154 max_delta_T_world_robot_(0.0) {
milind-u2ab4db12023-03-25 21:59:23 -0700155 // Send new april tag poses. This allows us to take a log of images, then
156 // play with the april detection code and see those changes take effect in
157 // mapping
158 constexpr size_t kNumPis = 4;
159 for (size_t i = 1; i <= kNumPis; i++) {
160 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
161 "frc971.vision.TargetMap");
162 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i),
163 "foxglove.ImageAnnotations");
164 reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
165 "y2023.Constants");
166 }
167
168 reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants");
169
170 reader_->Register();
171
172 SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number,
173 FLAGS_constants_path);
174
175 for (size_t i = 1; i < kNumPis; i++) {
176 std::string node_name = "pi" + std::to_string(i);
177 const aos::Node *pi =
178 aos::configuration::GetNode(reader_->configuration(), node_name);
179 detection_event_loops_.emplace_back(
180 reader_->event_loop_factory()->MakeEventLoop(node_name + "_detection",
181 pi));
182 mapping_event_loops_.emplace_back(
183 reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping",
184 pi));
185 HandlePiCaptures(
186 detection_event_loops_[detection_event_loops_.size() - 1].get(),
187 mapping_event_loops_[mapping_event_loops_.size() - 1].get());
188 }
189
190 if (!FLAGS_mcap_output_path.empty()) {
191 LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path;
192 const aos::Node *node =
193 aos::configuration::GetNode(reader_->configuration(), FLAGS_pi);
194 reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup(
195 [this, node]() {
196 mcap_event_loop_ =
197 reader_->event_loop_factory()->MakeEventLoop("mcap", node);
198 relogger_ = std::make_unique<aos::McapLogger>(
199 mcap_event_loop_.get(), FLAGS_mcap_output_path,
200 aos::McapLogger::Serialization::kFlatbuffer,
201 aos::McapLogger::CanonicalChannelNames::kShortened,
202 aos::McapLogger::Compression::kLz4);
203 });
204 }
205
206 if (FLAGS_visualize) {
207 vis_robot_.ClearImage();
208 const double kFocalLength = 500.0;
209 vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
210 }
211}
212
213TargetMapperReplay::~TargetMapperReplay() {
214 // Clean up all the pointers
215 for (auto &detector_ptr : detectors_) {
216 detector_ptr.reset();
217 }
218}
219
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800220// Add detected apriltag poses relative to the robot to
221// timestamped_target_detections
milind-u2ab4db12023-03-25 21:59:23 -0700222void TargetMapperReplay::HandleAprilTags(
223 const TargetMap &map,
224 aos::distributed_clock::time_point pi_distributed_time,
225 std::string node_name, Eigen::Affine3d extrinsics) {
milind-ua30a4a12023-03-24 20:49:41 -0700226 bool drew = false;
227 std::stringstream label;
228 label << node_name << " - ";
229
milind-u3f5f83c2023-01-29 15:23:51 -0800230 for (const auto *target_pose_fbs : *map.target_poses()) {
milind-ufbc5c812023-04-06 21:24:29 -0700231 // Skip detections with invalid ids
232 if (target_pose_fbs->id() < kMinTargetId ||
233 target_pose_fbs->id() > kMaxTargetId) {
234 LOG(WARNING) << "Skipping tag with invalid id of "
235 << target_pose_fbs->id();
236 continue;
237 }
238
milind-u5ddd5152023-03-04 15:19:17 -0800239 // Skip detections with high pose errors
240 if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
milind-ude9045f2023-03-25 18:17:12 -0700241 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
242 << " due to pose error of " << target_pose_fbs->pose_error();
243 continue;
244 }
245 // Skip detections with high pose error ratios
246 if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
247 VLOG(1) << " Skipping tag " << target_pose_fbs->id()
248 << " due to pose error ratio of "
249 << target_pose_fbs->pose_error_ratio();
milind-u5ddd5152023-03-04 15:19:17 -0800250 continue;
251 }
252
milind-u3f5f83c2023-01-29 15:23:51 -0800253 const TargetMapper::TargetPose target_pose =
254 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800255
milind-uee67abd2023-02-23 18:26:55 -0800256 Eigen::Affine3d H_camera_target =
milind-u3f5f83c2023-01-29 15:23:51 -0800257 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800258 Eigen::Affine3d H_robot_target =
milind-uee67abd2023-02-23 18:26:55 -0800259 CameraToRobotDetection(H_camera_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800260
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800261 ceres::examples::Pose3d target_pose_camera =
milind-uee67abd2023-02-23 18:26:55 -0800262 PoseUtils::Affine3dToPose3d(H_camera_target);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800263 double distance_from_camera = target_pose_camera.p.norm();
milind-ud62f80a2023-03-04 16:37:09 -0800264 double distortion_factor = target_pose_fbs->distortion_factor();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800265
milind-u09fb1252023-01-28 19:21:41 -0800266 CHECK(map.has_monotonic_timestamp_ns())
267 << "Need detection timestamps for mapping";
268
milind-u2ab4db12023-03-25 21:59:23 -0700269 timestamped_target_detections_.emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -0800270 DataAdapter::TimestampedDetection{
271 .time = pi_distributed_time,
272 .H_robot_target = H_robot_target,
273 .distance_from_camera = distance_from_camera,
milind-ud62f80a2023-03-04 16:37:09 -0800274 .distortion_factor = distortion_factor,
milind-u3f5f83c2023-01-29 15:23:51 -0800275 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Jim Ostrowski49be8232023-03-23 01:00:14 -0700276
277 if (FLAGS_visualize) {
milind-ua30a4a12023-03-24 20:49:41 -0700278 // If we've already drawn in the current image,
279 // display it before clearing and adding the new poses
milind-u2ab4db12023-03-25 21:59:23 -0700280 if (drawn_nodes_.count(node_name) != 0) {
281 display_count_++;
282 cv::putText(vis_robot_.image_,
283 "Poses #" + std::to_string(display_count_),
milind-ua30a4a12023-03-24 20:49:41 -0700284 cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0,
285 cv::Scalar(255, 255, 255));
286
milind-u2ab4db12023-03-25 21:59:23 -0700287 if (display_count_ >= FLAGS_skip_to) {
288 cv::imshow("View", vis_robot_.image_);
milind-u8cc03da2023-03-25 23:00:39 -0700289 cv::waitKey(max_delta_T_world_robot_ > FLAGS_pause_on_distance
290 ? 0
291 : FLAGS_wait_key);
292 max_delta_T_world_robot_ = 0.0;
milind-ude9045f2023-03-25 18:17:12 -0700293 } else {
milind-u2ab4db12023-03-25 21:59:23 -0700294 VLOG(1) << "At poses #" << std::to_string(display_count_);
milind-ude9045f2023-03-25 18:17:12 -0700295 }
milind-u2ab4db12023-03-25 21:59:23 -0700296 vis_robot_.ClearImage();
297 drawn_nodes_.clear();
milind-ua30a4a12023-03-24 20:49:41 -0700298 }
299
Jim Ostrowski49be8232023-03-23 01:00:14 -0700300 Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d(
milind-u2ab4db12023-03-25 21:59:23 -0700301 kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose);
Jim Ostrowski49be8232023-03-23 01:00:14 -0700302 Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse();
milind-ude9045f2023-03-25 18:17:12 -0700303 VLOG(2) << node_name << ", " << target_pose_fbs->id()
304 << ", t = " << pi_distributed_time
305 << ", pose_error = " << target_pose_fbs->pose_error()
306 << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio()
307 << ", robot_pos (x,y,z) + "
308 << H_world_robot.translation().transpose();
milind-ua30a4a12023-03-24 20:49:41 -0700309
310 label << "id " << target_pose_fbs->id() << ": err "
milind-ude9045f2023-03-25 18:17:12 -0700311 << (target_pose_fbs->pose_error() / FLAGS_max_pose_error)
312 << " ratio " << target_pose_fbs->pose_error_ratio() << " ";
milind-ua30a4a12023-03-24 20:49:41 -0700313
milind-u2ab4db12023-03-25 21:59:23 -0700314 vis_robot_.DrawRobotOutline(H_world_robot,
milind-ua30a4a12023-03-24 20:49:41 -0700315 std::to_string(target_pose_fbs->id()),
316 kPiColors.at(node_name));
317
milind-u2ab4db12023-03-25 21:59:23 -0700318 vis_robot_.DrawFrameAxes(H_world_target,
milind-ua30a4a12023-03-24 20:49:41 -0700319 std::to_string(target_pose_fbs->id()),
320 kPiColors.at(node_name));
milind-u8cc03da2023-03-25 23:00:39 -0700321
322 double delta_T_world_robot =
323 (H_world_robot.translation() - last_H_world_robot_.translation())
324 .norm();
325 max_delta_T_world_robot_ =
326 std::max(delta_T_world_robot, max_delta_T_world_robot_);
327
milind-ua30a4a12023-03-24 20:49:41 -0700328 drew = true;
milind-u2ab4db12023-03-25 21:59:23 -0700329 last_draw_time_ = pi_distributed_time;
milind-u8cc03da2023-03-25 23:00:39 -0700330 last_H_world_robot_ = H_world_robot;
Jim Ostrowski49be8232023-03-23 01:00:14 -0700331 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800332 }
milind-ua30a4a12023-03-24 20:49:41 -0700333 if (drew) {
334 size_t pi_number =
335 static_cast<size_t>(node_name[node_name.size() - 1] - '0');
milind-u2ab4db12023-03-25 21:59:23 -0700336 cv::putText(vis_robot_.image_, label.str(),
milind-ua30a4a12023-03-24 20:49:41 -0700337 cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0,
338 kPiColors.at(node_name));
339
milind-u2ab4db12023-03-25 21:59:23 -0700340 drawn_nodes_.emplace(node_name);
341 } else if (pi_distributed_time - last_draw_time_ >
milind-u52db3362023-03-25 20:09:22 -0700342 std::chrono::milliseconds(30) &&
milind-u2ab4db12023-03-25 21:59:23 -0700343 display_count_ >= FLAGS_skip_to) {
milind-u52db3362023-03-25 20:09:22 -0700344 // Clear the image if we haven't draw in a while
milind-u2ab4db12023-03-25 21:59:23 -0700345 vis_robot_.ClearImage();
346 cv::imshow("View", vis_robot_.image_);
milind-u52db3362023-03-25 20:09:22 -0700347 cv::waitKey(FLAGS_wait_key);
milind-u8cc03da2023-03-25 23:00:39 -0700348 max_delta_T_world_robot_ = 0.0;
milind-ua30a4a12023-03-24 20:49:41 -0700349 }
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800350}
351
milind-u2ab4db12023-03-25 21:59:23 -0700352void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *detection_event_loop,
353 aos::EventLoop *mapping_event_loop) {
milind-uf3ab8ba2023-02-04 17:56:16 -0800354 static constexpr std::string_view kImageChannel = "/camera";
milind-ua30a4a12023-03-24 20:49:41 -0700355 // For the robots, we need to flip the image since the cameras are rolled by
356 // 180 degrees
357 bool flip_image = (FLAGS_team_number != 7971);
milind-uf3ab8ba2023-02-04 17:56:16 -0800358 auto detector_ptr = std::make_unique<AprilRoboticsDetector>(
milind-ua30a4a12023-03-24 20:49:41 -0700359 detection_event_loop, kImageChannel, flip_image);
milind-uf2a4e322023-02-01 19:33:10 -0800360 // Get the camera extrinsics
James Kuszmaul258e4ee2023-02-23 14:22:30 -0800361 cv::Mat extrinsics_cv = detector_ptr->extrinsics().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
milind-u2ab4db12023-03-25 21:59:23 -0700366 detectors_.emplace_back(std::move(detector_ptr));
Jim Ostrowski49be8232023-03-23 01:00:14 -0700367
milind-uf3ab8ba2023-02-04 17:56:16 -0800368 mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
milind-u09fb1252023-01-28 19:21:41 -0800369 aos::distributed_clock::time_point pi_distributed_time =
milind-u2ab4db12023-03-25 21:59:23 -0700370 reader_->event_loop_factory()
milind-uf3ab8ba2023-02-04 17:56:16 -0800371 ->GetNodeEventLoopFactory(mapping_event_loop->node())
milind-u09fb1252023-01-28 19:21:41 -0800372 ->ToDistributedClock(aos::monotonic_clock::time_point(
373 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800374
Jim Ostrowski49be8232023-03-23 01:00:14 -0700375 std::string node_name = detection_event_loop->node()->name()->str();
milind-u2ab4db12023-03-25 21:59:23 -0700376 HandleAprilTags(map, pi_distributed_time, node_name, extrinsics);
milind-u09fb1252023-01-28 19:21:41 -0800377 });
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
400 if (!FLAGS_dump_constraints_to.empty()) {
401 std::ofstream fout(FLAGS_dump_constraints_to);
402 for (const auto &constraint : target_constraints) {
403 fout << constraint << std::endl;
404 }
405 fout.flush();
406 fout.close();
407 }
408
409 // Give seed constraints with a higher confidence to ground the solver.
410 // This "distance from camera" controls the noise of the seed measurement
411 constexpr double kSeedDistanceFromCamera = 1.0;
412
413 constexpr double kSeedDistortionFactor = 0.0;
414 const DataAdapter::TimestampedDetection frozen_detection_seed = {
415 .time = aos::distributed_clock::min_time,
416 .H_robot_target = PoseUtils::Pose3dToAffine3d(
417 kFixedTargetMapper.GetTargetPoseById(FLAGS_frozen_target_id)
418 .value()
419 .pose),
420 .distance_from_camera = kSeedDistanceFromCamera,
421 .distortion_factor = kSeedDistortionFactor,
422 .id = kMinTargetId};
423
424 for (TargetMapper::TargetId id = kMinTargetId; id <= kMaxTargetId; id++) {
425 if (id == static_cast<TargetMapper::TargetId>(FLAGS_frozen_target_id)) {
426 continue;
427 }
428
429 const DataAdapter::TimestampedDetection detection_seed = {
430 .time = aos::distributed_clock::min_time,
431 .H_robot_target = PoseUtils::Pose3dToAffine3d(
432 kFixedTargetMapper.GetTargetPoseById(id).value().pose),
433 .distance_from_camera = kSeedDistanceFromCamera,
434 .distortion_factor = kSeedDistortionFactor,
435 .id = id};
436 target_constraints.emplace_back(DataAdapter::ComputeTargetConstraint(
437 frozen_detection_seed, detection_seed,
438 DataAdapter::ComputeConfidence(frozen_detection_seed,
439 detection_seed)));
440 }
441
milind-u2ab4db12023-03-25 21:59:23 -0700442 TargetMapper mapper(FLAGS_json_path, target_constraints);
443 mapper.Solve(FLAGS_field_name, FLAGS_output_dir);
444 }
445}
446
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800447void MappingMain(int argc, char *argv[]) {
448 std::vector<std::string> unsorted_logfiles =
449 aos::logger::FindLogs(argc, argv);
450
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800451 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
452
milind-u4a5ef8a2023-03-05 14:10:23 -0800453 std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
454 (FLAGS_config.empty()
455 ? std::nullopt
456 : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
Jim Ostrowskiaec5dd22023-02-27 22:17:53 -0800457
milind-u2ab4db12023-03-25 21:59:23 -0700458 // Open logfiles
milind-u4a5ef8a2023-03-05 14:10:23 -0800459 aos::logger::LogReader reader(
460 aos::logger::SortParts(unsorted_logfiles),
461 config.has_value() ? &config->message() : nullptr);
milind-uf3ab8ba2023-02-04 17:56:16 -0800462
milind-u2ab4db12023-03-25 21:59:23 -0700463 TargetMapperReplay mapper_replay(&reader);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800464 reader.event_loop_factory()->Run();
milind-u2ab4db12023-03-25 21:59:23 -0700465 mapper_replay.MaybeSolve();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800466}
467
468} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800469} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800470
471int main(int argc, char **argv) {
472 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800473 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800474}