Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 1 | #include "aos/configuration.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 2 | #include "aos/events/logging/log_reader.h" |
| 3 | #include "aos/events/simulated_event_loop.h" |
| 4 | #include "aos/init.h" |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 5 | #include "aos/util/mcap_logger.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 6 | #include "frc971/control_loops/pose.h" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 7 | #include "frc971/vision/calibration_generated.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 8 | #include "frc971/vision/charuco_lib.h" |
| 9 | #include "frc971/vision/target_mapper.h" |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 10 | #include "frc971/vision/visualize_robot.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 11 | #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-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 18 | #include "y2023/constants/simulated_constants_sender.h" |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 19 | #include "y2023/vision/aprilrobotics.h" |
James Kuszmaul | d67f6d2 | 2023-02-05 17:37:25 -0800 | [diff] [blame] | 20 | #include "y2023/vision/vision_util.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 21 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 22 | DEFINE_string(json_path, "y2023/vision/maps/target_map.json", |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 23 | "Specify path for json with initial pose guesses."); |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 24 | DEFINE_string(config, "", |
| 25 | "If set, override the log's config file with this one."); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 26 | DEFINE_string(constants_path, "y2023/constants/constants.json", |
| 27 | "Path to the constant file"); |
| 28 | DEFINE_string(output_dir, "y2023/vision/maps", |
| 29 | "Directory to write solved target map to"); |
| 30 | DEFINE_string(field_name, "charged_up", |
| 31 | "Field name, for the output json filename and flatbuffer field"); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 32 | DEFINE_int32(team_number, 0, |
| 33 | "Required: Use the calibration for a node with this team number"); |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 34 | DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output."); |
| 35 | DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1."); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 36 | DEFINE_double(max_pose_error, 1e-6, |
| 37 | "Throw out target poses with a higher pose error than this"); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 38 | DEFINE_double( |
| 39 | max_pose_error_ratio, 0.4, |
| 40 | "Throw out target poses with a higher pose error ratio than this"); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 41 | DEFINE_uint64(wait_key, 0, |
| 42 | "Time in ms to wait between images, if no click (0 to wait " |
| 43 | "indefinitely until click)."); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 44 | DEFINE_uint64(skip_to, 1, |
| 45 | "Start at combined image of this number (1 is the first image)"); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 46 | DEFINE_bool(solve, true, "Whether to solve for the field's target map."); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 47 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 48 | namespace y2023 { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 49 | namespace vision { |
| 50 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 51 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 52 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 53 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 54 | using frc971::vision::TargetMapper; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 55 | using frc971::vision::VisualizeRobot; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 56 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 57 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 58 | // Class to handle reading target poses from a replayed log, |
| 59 | // displaying various debug info, and passing the poses to |
| 60 | // frc971::vision::TargetMapper for field mapping. |
| 61 | class TargetMapperReplay { |
| 62 | public: |
| 63 | TargetMapperReplay(aos::logger::LogReader *reader); |
| 64 | ~TargetMapperReplay(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 65 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 66 | // Solves for the target poses with the accumulated detections if FLAGS_solve. |
| 67 | void MaybeSolve(); |
| 68 | |
| 69 | private: |
| 70 | static constexpr int kImageWidth = 1280; |
| 71 | // Map from pi node name to color for drawing |
| 72 | static const std::map<std::string, cv::Scalar> kPiColors; |
| 73 | // Contains fixed target poses without solving, for use with visualization |
| 74 | static const TargetMapper kFixedTargetMapper; |
| 75 | |
| 76 | // Change reference frame from camera to robot |
| 77 | static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target, |
| 78 | Eigen::Affine3d extrinsics); |
| 79 | |
| 80 | // Adds april tag detections into the detection list, and handles |
| 81 | // visualization |
| 82 | void HandleAprilTags(const TargetMap &map, |
| 83 | aos::distributed_clock::time_point pi_distributed_time, |
| 84 | std::string node_name, Eigen::Affine3d extrinsics); |
| 85 | |
| 86 | // Gets images from the given pi and passes apriltag positions to |
| 87 | // HandleAprilTags() |
| 88 | void HandlePiCaptures(aos::EventLoop *detection_event_loop, |
| 89 | aos::EventLoop *mapping_event_loop); |
| 90 | |
| 91 | aos::logger::LogReader *reader_; |
| 92 | // April tag detections from all pis |
| 93 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_; |
| 94 | std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors_; |
| 95 | |
| 96 | VisualizeRobot vis_robot_; |
| 97 | // Set of node names which are currently drawn on the display |
| 98 | std::set<std::string> drawn_nodes_; |
| 99 | // Number of frames displayed |
| 100 | size_t display_count_; |
| 101 | // Last time we drew onto the display image. |
| 102 | // This is different from when we actually call imshow() to update |
| 103 | // the display window |
| 104 | aos::distributed_clock::time_point last_draw_time_; |
| 105 | |
| 106 | std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops_; |
| 107 | std::vector<std::unique_ptr<aos::EventLoop>> mapping_event_loops_; |
| 108 | |
| 109 | std::unique_ptr<aos::EventLoop> mcap_event_loop_; |
| 110 | std::unique_ptr<aos::McapLogger> relogger_; |
| 111 | }; |
| 112 | |
| 113 | const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{ |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 114 | {"pi1", cv::Scalar(255, 0, 255)}, |
| 115 | {"pi2", cv::Scalar(255, 255, 0)}, |
| 116 | {"pi3", cv::Scalar(0, 255, 255)}, |
| 117 | {"pi4", cv::Scalar(255, 165, 0)}, |
| 118 | }; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 119 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 120 | const auto TargetMapperReplay::kFixedTargetMapper = |
| 121 | TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{}); |
| 122 | |
| 123 | Eigen::Affine3d TargetMapperReplay::CameraToRobotDetection( |
| 124 | Eigen::Affine3d H_camera_target, Eigen::Affine3d extrinsics) { |
| 125 | const Eigen::Affine3d H_robot_camera = extrinsics; |
| 126 | const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target; |
| 127 | return H_robot_target; |
| 128 | } |
| 129 | |
| 130 | TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader) |
| 131 | : reader_(reader), |
| 132 | timestamped_target_detections_(), |
| 133 | detectors_(), |
| 134 | vis_robot_(cv::Size(1280, 1000)), |
| 135 | drawn_nodes_(), |
| 136 | display_count_(0), |
| 137 | last_draw_time_(aos::distributed_clock::min_time) { |
| 138 | // Send new april tag poses. This allows us to take a log of images, then |
| 139 | // play with the april detection code and see those changes take effect in |
| 140 | // mapping |
| 141 | constexpr size_t kNumPis = 4; |
| 142 | for (size_t i = 1; i <= kNumPis; i++) { |
| 143 | reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i), |
| 144 | "frc971.vision.TargetMap"); |
| 145 | reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/camera", i), |
| 146 | "foxglove.ImageAnnotations"); |
| 147 | reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i), |
| 148 | "y2023.Constants"); |
| 149 | } |
| 150 | |
| 151 | reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants"); |
| 152 | |
| 153 | reader_->Register(); |
| 154 | |
| 155 | SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number, |
| 156 | FLAGS_constants_path); |
| 157 | |
| 158 | for (size_t i = 1; i < kNumPis; i++) { |
| 159 | std::string node_name = "pi" + std::to_string(i); |
| 160 | const aos::Node *pi = |
| 161 | aos::configuration::GetNode(reader_->configuration(), node_name); |
| 162 | detection_event_loops_.emplace_back( |
| 163 | reader_->event_loop_factory()->MakeEventLoop(node_name + "_detection", |
| 164 | pi)); |
| 165 | mapping_event_loops_.emplace_back( |
| 166 | reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping", |
| 167 | pi)); |
| 168 | HandlePiCaptures( |
| 169 | detection_event_loops_[detection_event_loops_.size() - 1].get(), |
| 170 | mapping_event_loops_[mapping_event_loops_.size() - 1].get()); |
| 171 | } |
| 172 | |
| 173 | if (!FLAGS_mcap_output_path.empty()) { |
| 174 | LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path; |
| 175 | const aos::Node *node = |
| 176 | aos::configuration::GetNode(reader_->configuration(), FLAGS_pi); |
| 177 | reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup( |
| 178 | [this, node]() { |
| 179 | mcap_event_loop_ = |
| 180 | reader_->event_loop_factory()->MakeEventLoop("mcap", node); |
| 181 | relogger_ = std::make_unique<aos::McapLogger>( |
| 182 | mcap_event_loop_.get(), FLAGS_mcap_output_path, |
| 183 | aos::McapLogger::Serialization::kFlatbuffer, |
| 184 | aos::McapLogger::CanonicalChannelNames::kShortened, |
| 185 | aos::McapLogger::Compression::kLz4); |
| 186 | }); |
| 187 | } |
| 188 | |
| 189 | if (FLAGS_visualize) { |
| 190 | vis_robot_.ClearImage(); |
| 191 | const double kFocalLength = 500.0; |
| 192 | vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength); |
| 193 | } |
| 194 | } |
| 195 | |
| 196 | TargetMapperReplay::~TargetMapperReplay() { |
| 197 | // Clean up all the pointers |
| 198 | for (auto &detector_ptr : detectors_) { |
| 199 | detector_ptr.reset(); |
| 200 | } |
| 201 | } |
| 202 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 203 | // Add detected apriltag poses relative to the robot to |
| 204 | // timestamped_target_detections |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 205 | void TargetMapperReplay::HandleAprilTags( |
| 206 | const TargetMap &map, |
| 207 | aos::distributed_clock::time_point pi_distributed_time, |
| 208 | std::string node_name, Eigen::Affine3d extrinsics) { |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 209 | bool drew = false; |
| 210 | std::stringstream label; |
| 211 | label << node_name << " - "; |
| 212 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 213 | for (const auto *target_pose_fbs : *map.target_poses()) { |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 214 | // Skip detections with high pose errors |
| 215 | if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) { |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 216 | VLOG(1) << " Skipping tag " << target_pose_fbs->id() |
| 217 | << " due to pose error of " << target_pose_fbs->pose_error(); |
| 218 | continue; |
| 219 | } |
| 220 | // Skip detections with high pose error ratios |
| 221 | if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) { |
| 222 | VLOG(1) << " Skipping tag " << target_pose_fbs->id() |
| 223 | << " due to pose error ratio of " |
| 224 | << target_pose_fbs->pose_error_ratio(); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 225 | continue; |
| 226 | } |
| 227 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 228 | const TargetMapper::TargetPose target_pose = |
| 229 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 230 | |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 231 | Eigen::Affine3d H_camera_target = |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 232 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 233 | Eigen::Affine3d H_robot_target = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 234 | CameraToRobotDetection(H_camera_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 235 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 236 | ceres::examples::Pose3d target_pose_camera = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 237 | PoseUtils::Affine3dToPose3d(H_camera_target); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 238 | double distance_from_camera = target_pose_camera.p.norm(); |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 239 | double distortion_factor = target_pose_fbs->distortion_factor(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 240 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 241 | CHECK(map.has_monotonic_timestamp_ns()) |
| 242 | << "Need detection timestamps for mapping"; |
| 243 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 244 | timestamped_target_detections_.emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 245 | DataAdapter::TimestampedDetection{ |
| 246 | .time = pi_distributed_time, |
| 247 | .H_robot_target = H_robot_target, |
| 248 | .distance_from_camera = distance_from_camera, |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 249 | .distortion_factor = distortion_factor, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 250 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 251 | |
| 252 | if (FLAGS_visualize) { |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 253 | // If we've already drawn in the current image, |
| 254 | // display it before clearing and adding the new poses |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 255 | if (drawn_nodes_.count(node_name) != 0) { |
| 256 | display_count_++; |
| 257 | cv::putText(vis_robot_.image_, |
| 258 | "Poses #" + std::to_string(display_count_), |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 259 | cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0, |
| 260 | cv::Scalar(255, 255, 255)); |
| 261 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 262 | if (display_count_ >= FLAGS_skip_to) { |
| 263 | cv::imshow("View", vis_robot_.image_); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 264 | cv::waitKey(FLAGS_wait_key); |
| 265 | } else { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 266 | VLOG(1) << "At poses #" << std::to_string(display_count_); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 267 | } |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 268 | vis_robot_.ClearImage(); |
| 269 | drawn_nodes_.clear(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 270 | } |
| 271 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 272 | Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d( |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 273 | kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 274 | Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse(); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 275 | VLOG(2) << node_name << ", " << target_pose_fbs->id() |
| 276 | << ", t = " << pi_distributed_time |
| 277 | << ", pose_error = " << target_pose_fbs->pose_error() |
| 278 | << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio() |
| 279 | << ", robot_pos (x,y,z) + " |
| 280 | << H_world_robot.translation().transpose(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 281 | |
| 282 | label << "id " << target_pose_fbs->id() << ": err " |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 283 | << (target_pose_fbs->pose_error() / FLAGS_max_pose_error) |
| 284 | << " ratio " << target_pose_fbs->pose_error_ratio() << " "; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 285 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 286 | vis_robot_.DrawRobotOutline(H_world_robot, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 287 | std::to_string(target_pose_fbs->id()), |
| 288 | kPiColors.at(node_name)); |
| 289 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 290 | vis_robot_.DrawFrameAxes(H_world_target, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 291 | std::to_string(target_pose_fbs->id()), |
| 292 | kPiColors.at(node_name)); |
| 293 | drew = true; |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 294 | last_draw_time_ = pi_distributed_time; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 295 | } |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 296 | } |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 297 | if (drew) { |
| 298 | size_t pi_number = |
| 299 | static_cast<size_t>(node_name[node_name.size() - 1] - '0'); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 300 | cv::putText(vis_robot_.image_, label.str(), |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 301 | cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0, |
| 302 | kPiColors.at(node_name)); |
| 303 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 304 | drawn_nodes_.emplace(node_name); |
| 305 | } else if (pi_distributed_time - last_draw_time_ > |
milind-u | 52db336 | 2023-03-25 20:09:22 -0700 | [diff] [blame] | 306 | std::chrono::milliseconds(30) && |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 307 | display_count_ >= FLAGS_skip_to) { |
milind-u | 52db336 | 2023-03-25 20:09:22 -0700 | [diff] [blame] | 308 | // Clear the image if we haven't draw in a while |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 309 | vis_robot_.ClearImage(); |
| 310 | cv::imshow("View", vis_robot_.image_); |
milind-u | 52db336 | 2023-03-25 20:09:22 -0700 | [diff] [blame] | 311 | cv::waitKey(FLAGS_wait_key); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 312 | } |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 313 | } |
| 314 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 315 | void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *detection_event_loop, |
| 316 | aos::EventLoop *mapping_event_loop) { |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 317 | static constexpr std::string_view kImageChannel = "/camera"; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 318 | // For the robots, we need to flip the image since the cameras are rolled by |
| 319 | // 180 degrees |
| 320 | bool flip_image = (FLAGS_team_number != 7971); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 321 | auto detector_ptr = std::make_unique<AprilRoboticsDetector>( |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 322 | detection_event_loop, kImageChannel, flip_image); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 323 | // Get the camera extrinsics |
James Kuszmaul | 258e4ee | 2023-02-23 14:22:30 -0800 | [diff] [blame] | 324 | cv::Mat extrinsics_cv = detector_ptr->extrinsics().value(); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 325 | Eigen::Matrix4d extrinsics_matrix; |
| 326 | cv::cv2eigen(extrinsics_cv, extrinsics_matrix); |
| 327 | const auto extrinsics = Eigen::Affine3d(extrinsics_matrix); |
| 328 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 329 | detectors_.emplace_back(std::move(detector_ptr)); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 330 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 331 | mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) { |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 332 | aos::distributed_clock::time_point pi_distributed_time = |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 333 | reader_->event_loop_factory() |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 334 | ->GetNodeEventLoopFactory(mapping_event_loop->node()) |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 335 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 336 | aos::monotonic_clock::duration(map.monotonic_timestamp_ns()))); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 337 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 338 | std::string node_name = detection_event_loop->node()->name()->str(); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 339 | HandleAprilTags(map, pi_distributed_time, node_name, extrinsics); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 340 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 341 | } |
| 342 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 343 | void TargetMapperReplay::MaybeSolve() { |
| 344 | if (FLAGS_solve) { |
| 345 | auto target_constraints = |
| 346 | DataAdapter::MatchTargetDetections(timestamped_target_detections_); |
| 347 | |
| 348 | TargetMapper mapper(FLAGS_json_path, target_constraints); |
| 349 | mapper.Solve(FLAGS_field_name, FLAGS_output_dir); |
| 350 | } |
| 351 | } |
| 352 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 353 | void MappingMain(int argc, char *argv[]) { |
| 354 | std::vector<std::string> unsorted_logfiles = |
| 355 | aos::logger::FindLogs(argc, argv); |
| 356 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 357 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 358 | |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 359 | std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config = |
| 360 | (FLAGS_config.empty() |
| 361 | ? std::nullopt |
| 362 | : std::make_optional(aos::configuration::ReadConfig(FLAGS_config))); |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 363 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 364 | // Open logfiles |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 365 | aos::logger::LogReader reader( |
| 366 | aos::logger::SortParts(unsorted_logfiles), |
| 367 | config.has_value() ? &config->message() : nullptr); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 368 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 369 | TargetMapperReplay mapper_replay(&reader); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 370 | reader.event_loop_factory()->Run(); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame^] | 371 | mapper_replay.MaybeSolve(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 372 | } |
| 373 | |
| 374 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 375 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 376 | |
| 377 | int main(int argc, char **argv) { |
| 378 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 379 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 380 | } |