Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 1 | #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 Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 10 | #include "aos/configuration.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 11 | #include "aos/events/logging/log_reader.h" |
| 12 | #include "aos/events/simulated_event_loop.h" |
| 13 | #include "aos/init.h" |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 14 | #include "aos/util/mcap_logger.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 15 | #include "frc971/control_loops/pose.h" |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 16 | #include "frc971/vision/calibration_generated.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 17 | #include "frc971/vision/target_mapper.h" |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 18 | #include "frc971/vision/visualize_robot.h" |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 19 | #include "y2023/constants/simulated_constants_sender.h" |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 20 | #include "y2023/vision/aprilrobotics.h" |
James Kuszmaul | d67f6d2 | 2023-02-05 17:37:25 -0800 | [diff] [blame] | 21 | #include "y2023/vision/vision_util.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 22 | |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 23 | DEFINE_string(config, "", |
| 24 | "If set, override the log's config file with this one."); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 25 | DEFINE_string(constants_path, "y2023/constants/constants.json", |
| 26 | "Path to the constant file"); |
Jim Ostrowski | 2f2685f | 2023-03-25 11:57:54 -0700 | [diff] [blame] | 27 | DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt", |
| 28 | "Write the target constraints to this path"); |
| 29 | DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt", |
| 30 | "Write the mapping stats to this path"); |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 31 | DEFINE_string(field_name, "charged_up", |
| 32 | "Field name, for the output json filename and flatbuffer field"); |
Jim Ostrowski | 2f2685f | 2023-03-25 11:57:54 -0700 | [diff] [blame] | 33 | DEFINE_string(json_path, "y2023/vision/maps/target_map.json", |
| 34 | "Specify path for json with initial pose guesses."); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 35 | DEFINE_double(max_pose_error, 1e-6, |
| 36 | "Throw out target poses with a higher pose error than this"); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 37 | DEFINE_double( |
| 38 | max_pose_error_ratio, 0.4, |
| 39 | "Throw out target poses with a higher pose error ratio than this"); |
Jim Ostrowski | 2f2685f | 2023-03-25 11:57:54 -0700 | [diff] [blame] | 40 | DEFINE_string(mcap_output_path, "", "Log to output."); |
| 41 | DEFINE_string(output_dir, "y2023/vision/maps", |
| 42 | "Directory to write solved target map to"); |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 43 | DEFINE_double(pause_on_distance, 1.0, |
| 44 | "Pause if two consecutive implied robot positions differ by more " |
| 45 | "than this many meters"); |
Jim Ostrowski | 2f2685f | 2023-03-25 11:57:54 -0700 | [diff] [blame] | 46 | DEFINE_string(pi, "pi1", "Pi name to generate mcap log for; defaults to pi1."); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 47 | DEFINE_uint64(skip_to, 1, |
| 48 | "Start at combined image of this number (1 is the first image)"); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 49 | DEFINE_bool(solve, true, "Whether to solve for the field's target map."); |
Jim Ostrowski | 2f2685f | 2023-03-25 11:57:54 -0700 | [diff] [blame] | 50 | DEFINE_int32(team_number, 0, |
| 51 | "Required: Use the calibration for a node with this team number"); |
| 52 | DEFINE_uint64(wait_key, 1, |
| 53 | "Time in ms to wait between images, if no click (0 to wait " |
| 54 | "indefinitely until click)."); |
| 55 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 56 | DECLARE_int32(frozen_target_id); |
| 57 | DECLARE_int32(min_target_id); |
| 58 | DECLARE_int32(max_target_id); |
| 59 | DECLARE_bool(visualize_solver); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 60 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 61 | namespace y2023::vision { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 62 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 63 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 64 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 65 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 66 | using frc971::vision::TargetMapper; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 67 | using frc971::vision::VisualizeRobot; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 68 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 69 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 70 | // 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. |
| 73 | class TargetMapperReplay { |
| 74 | public: |
| 75 | TargetMapperReplay(aos::logger::LogReader *reader); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 76 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 77 | // 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-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 99 | void HandlePiCaptures(aos::EventLoop *mapping_event_loop); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 100 | |
| 101 | aos::logger::LogReader *reader_; |
| 102 | // April tag detections from all pis |
| 103 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections_; |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 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-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 115 | 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-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 121 | 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 | |
| 127 | const auto TargetMapperReplay::kPiColors = std::map<std::string, cv::Scalar>{ |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 128 | {"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 Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 133 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 134 | const auto TargetMapperReplay::kFixedTargetMapper = |
| 135 | TargetMapper(FLAGS_json_path, ceres::examples::VectorOfConstraints{}); |
| 136 | |
| 137 | Eigen::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 | |
| 144 | TargetMapperReplay::TargetMapperReplay(aos::logger::LogReader *reader) |
| 145 | : reader_(reader), |
| 146 | timestamped_target_detections_(), |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 147 | vis_robot_(cv::Size(1280, 1000)), |
| 148 | drawn_nodes_(), |
| 149 | display_count_(0), |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 150 | 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-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 153 | constexpr size_t kNumPis = 4; |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 154 | // TODO(milind): add a flag to support replaying april detection from full |
| 155 | // logs as well. |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 156 | for (size_t i = 1; i <= kNumPis; i++) { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 157 | reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i), |
| 158 | "y2023.Constants"); |
| 159 | } |
| 160 | |
| 161 | reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants"); |
Jim Ostrowski | 68c321d | 2023-11-14 21:36:28 -0800 | [diff] [blame] | 162 | reader_->RemapLoggedChannel("/logger/constants", "y2023.Constants"); |
| 163 | reader_->RemapLoggedChannel("/roborio/constants", "y2023.Constants"); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 164 | |
| 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-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 174 | mapping_event_loops_.emplace_back( |
| 175 | reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping", |
| 176 | pi)); |
| 177 | HandlePiCaptures( |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 178 | 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-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 197 | if (FLAGS_visualize_solver) { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 198 | vis_robot_.ClearImage(); |
| 199 | const double kFocalLength = 500.0; |
| 200 | vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength); |
| 201 | } |
| 202 | } |
| 203 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 204 | // Add detected apriltag poses relative to the robot to |
| 205 | // timestamped_target_detections |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 206 | void TargetMapperReplay::HandleAprilTags( |
| 207 | const TargetMap &map, |
| 208 | aos::distributed_clock::time_point pi_distributed_time, |
| 209 | std::string node_name, Eigen::Affine3d extrinsics) { |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 210 | bool drew = false; |
| 211 | std::stringstream label; |
| 212 | label << node_name << " - "; |
| 213 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 214 | for (const auto *target_pose_fbs : *map.target_poses()) { |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 215 | // Skip detections with invalid ids |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 216 | 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-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 221 | continue; |
| 222 | } |
| 223 | |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 224 | // Skip detections with high pose errors |
| 225 | if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 226 | VLOG(1) << "Skipping tag " << target_pose_fbs->id() |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 227 | << " 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-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 232 | VLOG(1) << "Skipping tag " << target_pose_fbs->id() |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 233 | << " due to pose error ratio of " |
| 234 | << target_pose_fbs->pose_error_ratio(); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 235 | continue; |
| 236 | } |
| 237 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 238 | const TargetMapper::TargetPose target_pose = |
| 239 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 240 | |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 241 | Eigen::Affine3d H_camera_target = |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 242 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 243 | Eigen::Affine3d H_robot_target = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 244 | CameraToRobotDetection(H_camera_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 245 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 246 | ceres::examples::Pose3d target_pose_camera = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 247 | PoseUtils::Affine3dToPose3d(H_camera_target); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 248 | double distance_from_camera = target_pose_camera.p.norm(); |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 249 | double distortion_factor = target_pose_fbs->distortion_factor(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 250 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 251 | CHECK(map.has_monotonic_timestamp_ns()) |
| 252 | << "Need detection timestamps for mapping"; |
| 253 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 254 | timestamped_target_detections_.emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 255 | DataAdapter::TimestampedDetection{ |
| 256 | .time = pi_distributed_time, |
| 257 | .H_robot_target = H_robot_target, |
| 258 | .distance_from_camera = distance_from_camera, |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 259 | .distortion_factor = distortion_factor, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 260 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 261 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 262 | if (FLAGS_visualize_solver) { |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 263 | // If we've already drawn this node_name in the current image, |
| 264 | // display the image before clearing and adding the new poses |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 265 | if (drawn_nodes_.count(node_name) != 0) { |
| 266 | display_count_++; |
| 267 | cv::putText(vis_robot_.image_, |
| 268 | "Poses #" + std::to_string(display_count_), |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 269 | cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0, |
| 270 | cv::Scalar(255, 255, 255)); |
| 271 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 272 | if (display_count_ >= FLAGS_skip_to) { |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 273 | VLOG(1) << "Showing image for node " << node_name |
| 274 | << " since we've drawn it already"; |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 275 | cv::imshow("View", vis_robot_.image_); |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 276 | // 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-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 287 | max_delta_T_world_robot_ = 0.0; |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 288 | } else { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 289 | VLOG(1) << "At poses #" << std::to_string(display_count_); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 290 | } |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 291 | vis_robot_.ClearImage(); |
| 292 | drawn_nodes_.clear(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 293 | } |
| 294 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 295 | Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d( |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 296 | kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 297 | Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse(); |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 298 | VLOG(2) << node_name << ", id " << target_pose_fbs->id() |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 299 | << ", t = " << pi_distributed_time |
| 300 | << ", pose_error = " << target_pose_fbs->pose_error() |
| 301 | << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio() |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 302 | << ", robot_pos (x,y,z) = " |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 303 | << H_world_robot.translation().transpose(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 304 | |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 305 | label << "id " << target_pose_fbs->id() << ": err (% of max): " |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 306 | << (target_pose_fbs->pose_error() / FLAGS_max_pose_error) |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 307 | << " err_ratio: " << target_pose_fbs->pose_error_ratio() << " "; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 308 | |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 309 | vis_robot_.DrawRobotOutline(H_world_robot, node_name, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 310 | kPiColors.at(node_name)); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 311 | vis_robot_.DrawFrameAxes(H_world_target, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 312 | std::to_string(target_pose_fbs->id()), |
| 313 | kPiColors.at(node_name)); |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 314 | |
| 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 Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 321 | VLOG(1) << "Drew in info for robot " << node_name << " and target #" |
| 322 | << target_pose_fbs->id(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 323 | drew = true; |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 324 | last_draw_time_ = pi_distributed_time; |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 325 | last_H_world_robot_ = H_world_robot; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 326 | } |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 327 | } |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 328 | |
Jim Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 329 | 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-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 352 | } |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 353 | } |
| 354 | |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 355 | void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) { |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 356 | // Get the camera extrinsics |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 357 | 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-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 362 | Eigen::Matrix4d extrinsics_matrix; |
| 363 | cv::cv2eigen(extrinsics_cv, extrinsics_matrix); |
| 364 | const auto extrinsics = Eigen::Affine3d(extrinsics_matrix); |
| 365 | |
Austin Schuh | 612d95d | 2023-10-21 00:01:40 -0700 | [diff] [blame] | 366 | 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 Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 374 | |
Austin Schuh | 612d95d | 2023-10-21 00:01:40 -0700 | [diff] [blame] | 375 | std::string node_name = mapping_event_loop->node()->name()->str(); |
| 376 | HandleAprilTags(map, pi_distributed_time, node_name, extrinsics); |
| 377 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 378 | } |
| 379 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 380 | void TargetMapperReplay::MaybeSolve() { |
| 381 | if (FLAGS_solve) { |
| 382 | auto target_constraints = |
| 383 | DataAdapter::MatchTargetDetections(timestamped_target_detections_); |
| 384 | |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 385 | // 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 Ostrowski | 7fde9b0 | 2023-09-09 23:33:58 -0700 | [diff] [blame] | 400 | LOG(INFO) << "Solving for locations of tags with " |
| 401 | << target_constraints.size() << " constraints"; |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 402 | TargetMapper mapper(FLAGS_json_path, target_constraints); |
| 403 | mapper.Solve(FLAGS_field_name, FLAGS_output_dir); |
milind-u | 401de98 | 2023-04-14 17:32:03 -0700 | [diff] [blame] | 404 | |
| 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-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 411 | } |
| 412 | } |
| 413 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 414 | void MappingMain(int argc, char *argv[]) { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 415 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 416 | |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 417 | std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config = |
| 418 | (FLAGS_config.empty() |
| 419 | ? std::nullopt |
| 420 | : std::make_optional(aos::configuration::ReadConfig(FLAGS_config))); |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 421 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 422 | // Open logfiles |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 423 | aos::logger::LogReader reader( |
Austin Schuh | c160973 | 2023-06-26 11:51:28 -0700 | [diff] [blame] | 424 | aos::logger::SortParts(aos::logger::FindLogs(argc, argv)), |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 425 | config.has_value() ? &config->message() : nullptr); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 426 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 427 | TargetMapperReplay mapper_replay(&reader); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 428 | reader.event_loop_factory()->Run(); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 429 | mapper_replay.MaybeSolve(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 430 | } |
| 431 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 432 | } // namespace y2023::vision |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 433 | |
| 434 | int main(int argc, char **argv) { |
| 435 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 436 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 437 | } |