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/target_mapper.h" |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 9 | #include "frc971/vision/visualize_robot.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 10 | #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-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 17 | #include "y2023/constants/simulated_constants_sender.h" |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 18 | #include "y2023/vision/aprilrobotics.h" |
James Kuszmaul | d67f6d2 | 2023-02-05 17:37:25 -0800 | [diff] [blame] | 19 | #include "y2023/vision/vision_util.h" |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 20 | |
milind-u | c5a494f | 2023-02-24 15:39:22 -0800 | [diff] [blame] | 21 | DEFINE_string(json_path, "y2023/vision/maps/target_map.json", |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 22 | "Specify path for json with initial pose guesses."); |
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"); |
| 27 | DEFINE_string(output_dir, "y2023/vision/maps", |
| 28 | "Directory to write solved target map to"); |
| 29 | DEFINE_string(field_name, "charged_up", |
| 30 | "Field name, for the output json filename and flatbuffer field"); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 31 | DEFINE_int32(team_number, 0, |
| 32 | "Required: Use the calibration for a node with this team number"); |
Jim Ostrowski | 68965cd | 2023-03-01 20:32:51 -0800 | [diff] [blame] | 33 | DEFINE_string(mcap_output_path, "/tmp/log.mcap", "Log to output."); |
| 34 | 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] | 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"); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 40 | DEFINE_uint64(wait_key, 0, |
| 41 | "Time in ms to wait between images, if no click (0 to wait " |
| 42 | "indefinitely until click)."); |
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"); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 46 | DEFINE_uint64(skip_to, 1, |
| 47 | "Start at combined image of this number (1 is the first image)"); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 48 | DEFINE_bool(solve, true, "Whether to solve for the field's target map."); |
milind-u | 401de98 | 2023-04-14 17:32:03 -0700 | [diff] [blame^] | 49 | DEFINE_string(dump_constraints_to, "/tmp/mapping_constraints.txt", |
| 50 | "Write the target constraints to this path"); |
| 51 | DEFINE_string(dump_stats_to, "/tmp/mapping_stats.txt", |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 52 | "Write the target constraints to this path"); |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 53 | DECLARE_int32(frozen_target_id); |
| 54 | DECLARE_int32(min_target_id); |
| 55 | DECLARE_int32(max_target_id); |
| 56 | DECLARE_bool(visualize_solver); |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 57 | |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 58 | namespace y2023 { |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 59 | namespace vision { |
| 60 | using frc971::vision::DataAdapter; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 61 | using frc971::vision::ImageCallback; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 62 | using frc971::vision::PoseUtils; |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 63 | using frc971::vision::TargetMap; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 64 | using frc971::vision::TargetMapper; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 65 | using frc971::vision::VisualizeRobot; |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 66 | namespace calibration = frc971::vision::calibration; |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 67 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 68 | // Class to handle reading target poses from a replayed log, |
| 69 | // displaying various debug info, and passing the poses to |
| 70 | // frc971::vision::TargetMapper for field mapping. |
| 71 | class TargetMapperReplay { |
| 72 | public: |
| 73 | TargetMapperReplay(aos::logger::LogReader *reader); |
| 74 | ~TargetMapperReplay(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 75 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 76 | // Solves for the target poses with the accumulated detections if FLAGS_solve. |
| 77 | void MaybeSolve(); |
| 78 | |
| 79 | private: |
| 80 | static constexpr int kImageWidth = 1280; |
| 81 | // Map from pi node name to color for drawing |
| 82 | static const std::map<std::string, cv::Scalar> kPiColors; |
| 83 | // Contains fixed target poses without solving, for use with visualization |
| 84 | static const TargetMapper kFixedTargetMapper; |
| 85 | |
| 86 | // Change reference frame from camera to robot |
| 87 | static Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target, |
| 88 | Eigen::Affine3d extrinsics); |
| 89 | |
| 90 | // Adds april tag detections into the detection list, and handles |
| 91 | // visualization |
| 92 | void HandleAprilTags(const TargetMap &map, |
| 93 | aos::distributed_clock::time_point pi_distributed_time, |
| 94 | std::string node_name, Eigen::Affine3d extrinsics); |
| 95 | |
| 96 | // Gets images from the given pi and passes apriltag positions to |
| 97 | // HandleAprilTags() |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 98 | void HandlePiCaptures(aos::EventLoop *mapping_event_loop); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 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-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_(), |
| 147 | detectors_(), |
| 148 | vis_robot_(cv::Size(1280, 1000)), |
| 149 | drawn_nodes_(), |
| 150 | display_count_(0), |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 151 | last_draw_time_(aos::distributed_clock::min_time), |
| 152 | last_H_world_robot_(Eigen::Matrix4d::Identity()), |
| 153 | max_delta_T_world_robot_(0.0) { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 154 | constexpr size_t kNumPis = 4; |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 155 | // TODO(milind): add a flag to support replaying april detection from full |
| 156 | // logs as well. |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 157 | for (size_t i = 1; i <= kNumPis; i++) { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 158 | reader_->RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i), |
| 159 | "y2023.Constants"); |
| 160 | } |
| 161 | |
| 162 | reader_->RemapLoggedChannel("/imu/constants", "y2023.Constants"); |
| 163 | |
| 164 | reader_->Register(); |
| 165 | |
| 166 | SendSimulationConstants(reader_->event_loop_factory(), FLAGS_team_number, |
| 167 | FLAGS_constants_path); |
| 168 | |
| 169 | for (size_t i = 1; i < kNumPis; i++) { |
| 170 | std::string node_name = "pi" + std::to_string(i); |
| 171 | const aos::Node *pi = |
| 172 | aos::configuration::GetNode(reader_->configuration(), node_name); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 173 | mapping_event_loops_.emplace_back( |
| 174 | reader_->event_loop_factory()->MakeEventLoop(node_name + "_mapping", |
| 175 | pi)); |
| 176 | HandlePiCaptures( |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 177 | mapping_event_loops_[mapping_event_loops_.size() - 1].get()); |
| 178 | } |
| 179 | |
| 180 | if (!FLAGS_mcap_output_path.empty()) { |
| 181 | LOG(INFO) << "Writing out mcap file to " << FLAGS_mcap_output_path; |
| 182 | const aos::Node *node = |
| 183 | aos::configuration::GetNode(reader_->configuration(), FLAGS_pi); |
| 184 | reader_->event_loop_factory()->GetNodeEventLoopFactory(node)->OnStartup( |
| 185 | [this, node]() { |
| 186 | mcap_event_loop_ = |
| 187 | reader_->event_loop_factory()->MakeEventLoop("mcap", node); |
| 188 | relogger_ = std::make_unique<aos::McapLogger>( |
| 189 | mcap_event_loop_.get(), FLAGS_mcap_output_path, |
| 190 | aos::McapLogger::Serialization::kFlatbuffer, |
| 191 | aos::McapLogger::CanonicalChannelNames::kShortened, |
| 192 | aos::McapLogger::Compression::kLz4); |
| 193 | }); |
| 194 | } |
| 195 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 196 | if (FLAGS_visualize_solver) { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 197 | vis_robot_.ClearImage(); |
| 198 | const double kFocalLength = 500.0; |
| 199 | vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength); |
| 200 | } |
| 201 | } |
| 202 | |
| 203 | TargetMapperReplay::~TargetMapperReplay() { |
| 204 | // Clean up all the pointers |
| 205 | for (auto &detector_ptr : detectors_) { |
| 206 | detector_ptr.reset(); |
| 207 | } |
| 208 | } |
| 209 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 210 | // Add detected apriltag poses relative to the robot to |
| 211 | // timestamped_target_detections |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 212 | void TargetMapperReplay::HandleAprilTags( |
| 213 | const TargetMap &map, |
| 214 | aos::distributed_clock::time_point pi_distributed_time, |
| 215 | std::string node_name, Eigen::Affine3d extrinsics) { |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 216 | bool drew = false; |
| 217 | std::stringstream label; |
| 218 | label << node_name << " - "; |
| 219 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 220 | for (const auto *target_pose_fbs : *map.target_poses()) { |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 221 | // Skip detections with invalid ids |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 222 | if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) < |
| 223 | FLAGS_min_target_id || |
| 224 | static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) > |
| 225 | FLAGS_max_target_id) { |
| 226 | VLOG(1) << "Skipping tag with invalid id of " << target_pose_fbs->id(); |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 227 | continue; |
| 228 | } |
| 229 | |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 230 | // Skip detections with high pose errors |
| 231 | if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) { |
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 of " << target_pose_fbs->pose_error(); |
| 234 | continue; |
| 235 | } |
| 236 | // Skip detections with high pose error ratios |
| 237 | if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) { |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 238 | VLOG(1) << "Skipping tag " << target_pose_fbs->id() |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 239 | << " due to pose error ratio of " |
| 240 | << target_pose_fbs->pose_error_ratio(); |
milind-u | 5ddd515 | 2023-03-04 15:19:17 -0800 | [diff] [blame] | 241 | continue; |
| 242 | } |
| 243 | |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 244 | const TargetMapper::TargetPose target_pose = |
| 245 | PoseUtils::TargetPoseFromFbs(*target_pose_fbs); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 246 | |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 247 | Eigen::Affine3d H_camera_target = |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 248 | Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q; |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 249 | Eigen::Affine3d H_robot_target = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 250 | CameraToRobotDetection(H_camera_target, extrinsics); |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 251 | |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 252 | ceres::examples::Pose3d target_pose_camera = |
milind-u | ee67abd | 2023-02-23 18:26:55 -0800 | [diff] [blame] | 253 | PoseUtils::Affine3dToPose3d(H_camera_target); |
Milind Upadhyay | c5beba1 | 2022-12-17 17:41:20 -0800 | [diff] [blame] | 254 | double distance_from_camera = target_pose_camera.p.norm(); |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 255 | double distortion_factor = target_pose_fbs->distortion_factor(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 256 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 257 | CHECK(map.has_monotonic_timestamp_ns()) |
| 258 | << "Need detection timestamps for mapping"; |
| 259 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 260 | timestamped_target_detections_.emplace_back( |
Milind Upadhyay | ebf93ee | 2023-01-05 14:12:58 -0800 | [diff] [blame] | 261 | DataAdapter::TimestampedDetection{ |
| 262 | .time = pi_distributed_time, |
| 263 | .H_robot_target = H_robot_target, |
| 264 | .distance_from_camera = distance_from_camera, |
milind-u | d62f80a | 2023-03-04 16:37:09 -0800 | [diff] [blame] | 265 | .distortion_factor = distortion_factor, |
milind-u | 3f5f83c | 2023-01-29 15:23:51 -0800 | [diff] [blame] | 266 | .id = static_cast<TargetMapper::TargetId>(target_pose.id)}); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 267 | |
milind-u | 8f4e43e | 2023-04-09 17:11:19 -0700 | [diff] [blame] | 268 | if (FLAGS_visualize_solver) { |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 269 | // If we've already drawn in the current image, |
| 270 | // display it before clearing and adding the new poses |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 271 | if (drawn_nodes_.count(node_name) != 0) { |
| 272 | display_count_++; |
| 273 | cv::putText(vis_robot_.image_, |
| 274 | "Poses #" + std::to_string(display_count_), |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 275 | cv::Point(600, 10), cv::FONT_HERSHEY_PLAIN, 1.0, |
| 276 | cv::Scalar(255, 255, 255)); |
| 277 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 278 | if (display_count_ >= FLAGS_skip_to) { |
| 279 | cv::imshow("View", vis_robot_.image_); |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 280 | cv::waitKey(max_delta_T_world_robot_ > FLAGS_pause_on_distance |
| 281 | ? 0 |
| 282 | : FLAGS_wait_key); |
| 283 | max_delta_T_world_robot_ = 0.0; |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 284 | } else { |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 285 | VLOG(1) << "At poses #" << std::to_string(display_count_); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 286 | } |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 287 | vis_robot_.ClearImage(); |
| 288 | drawn_nodes_.clear(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 289 | } |
| 290 | |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 291 | Eigen::Affine3d H_world_target = PoseUtils::Pose3dToAffine3d( |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 292 | kFixedTargetMapper.GetTargetPoseById(target_pose_fbs->id())->pose); |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 293 | Eigen::Affine3d H_world_robot = H_world_target * H_robot_target.inverse(); |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 294 | VLOG(2) << node_name << ", " << target_pose_fbs->id() |
| 295 | << ", t = " << pi_distributed_time |
| 296 | << ", pose_error = " << target_pose_fbs->pose_error() |
| 297 | << ", pose_error_ratio = " << target_pose_fbs->pose_error_ratio() |
| 298 | << ", robot_pos (x,y,z) + " |
| 299 | << H_world_robot.translation().transpose(); |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 300 | |
| 301 | label << "id " << target_pose_fbs->id() << ": err " |
milind-u | de9045f | 2023-03-25 18:17:12 -0700 | [diff] [blame] | 302 | << (target_pose_fbs->pose_error() / FLAGS_max_pose_error) |
| 303 | << " ratio " << target_pose_fbs->pose_error_ratio() << " "; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 304 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 305 | vis_robot_.DrawRobotOutline(H_world_robot, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 306 | std::to_string(target_pose_fbs->id()), |
| 307 | kPiColors.at(node_name)); |
| 308 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 309 | vis_robot_.DrawFrameAxes(H_world_target, |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 310 | std::to_string(target_pose_fbs->id()), |
| 311 | kPiColors.at(node_name)); |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 312 | |
| 313 | double delta_T_world_robot = |
| 314 | (H_world_robot.translation() - last_H_world_robot_.translation()) |
| 315 | .norm(); |
| 316 | max_delta_T_world_robot_ = |
| 317 | std::max(delta_T_world_robot, max_delta_T_world_robot_); |
| 318 | |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 319 | drew = true; |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 320 | last_draw_time_ = pi_distributed_time; |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 321 | last_H_world_robot_ = H_world_robot; |
Jim Ostrowski | 49be823 | 2023-03-23 01:00:14 -0700 | [diff] [blame] | 322 | } |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 323 | } |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 324 | if (drew) { |
| 325 | size_t pi_number = |
| 326 | static_cast<size_t>(node_name[node_name.size() - 1] - '0'); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 327 | cv::putText(vis_robot_.image_, label.str(), |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 328 | cv::Point(10, 10 + 20 * pi_number), cv::FONT_HERSHEY_PLAIN, 1.0, |
| 329 | kPiColors.at(node_name)); |
| 330 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 331 | drawn_nodes_.emplace(node_name); |
| 332 | } else if (pi_distributed_time - last_draw_time_ > |
milind-u | 52db336 | 2023-03-25 20:09:22 -0700 | [diff] [blame] | 333 | std::chrono::milliseconds(30) && |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 334 | display_count_ >= FLAGS_skip_to) { |
milind-u | 52db336 | 2023-03-25 20:09:22 -0700 | [diff] [blame] | 335 | // Clear the image if we haven't draw in a while |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 336 | vis_robot_.ClearImage(); |
| 337 | cv::imshow("View", vis_robot_.image_); |
milind-u | 52db336 | 2023-03-25 20:09:22 -0700 | [diff] [blame] | 338 | cv::waitKey(FLAGS_wait_key); |
milind-u | 8cc03da | 2023-03-25 23:00:39 -0700 | [diff] [blame] | 339 | max_delta_T_world_robot_ = 0.0; |
milind-u | a30a4a1 | 2023-03-24 20:49:41 -0700 | [diff] [blame] | 340 | } |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 341 | } |
| 342 | |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 343 | void TargetMapperReplay::HandlePiCaptures(aos::EventLoop *mapping_event_loop) { |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 344 | // Get the camera extrinsics |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 345 | const frc971::constants::ConstantsFetcher<Constants> constants( |
| 346 | mapping_event_loop); |
| 347 | const auto *calibration = FindCameraCalibration( |
| 348 | constants.constants(), mapping_event_loop->node()->name()->string_view()); |
| 349 | cv::Mat extrinsics_cv = CameraExtrinsics(calibration).value(); |
milind-u | f2a4e32 | 2023-02-01 19:33:10 -0800 | [diff] [blame] | 350 | Eigen::Matrix4d extrinsics_matrix; |
| 351 | cv::cv2eigen(extrinsics_cv, extrinsics_matrix); |
| 352 | const auto extrinsics = Eigen::Affine3d(extrinsics_matrix); |
| 353 | |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 354 | mapping_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) { |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 355 | aos::distributed_clock::time_point pi_distributed_time = |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 356 | reader_->event_loop_factory() |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 357 | ->GetNodeEventLoopFactory(mapping_event_loop->node()) |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 358 | ->ToDistributedClock(aos::monotonic_clock::time_point( |
| 359 | aos::monotonic_clock::duration(map.monotonic_timestamp_ns()))); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 360 | |
milind-u | 8b0f478 | 2023-04-15 13:59:29 -0700 | [diff] [blame] | 361 | std::string node_name = mapping_event_loop->node()->name()->str(); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 362 | HandleAprilTags(map, pi_distributed_time, node_name, extrinsics); |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 363 | }); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 364 | } |
| 365 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 366 | void TargetMapperReplay::MaybeSolve() { |
| 367 | if (FLAGS_solve) { |
| 368 | auto target_constraints = |
| 369 | DataAdapter::MatchTargetDetections(timestamped_target_detections_); |
| 370 | |
milind-u | fbc5c81 | 2023-04-06 21:24:29 -0700 | [diff] [blame] | 371 | // Remove constraints between the two sides of the field - these are |
| 372 | // basically garbage because of how far the camera is. We will use seeding |
| 373 | // below to connect the two sides |
| 374 | target_constraints.erase( |
| 375 | std::remove_if(target_constraints.begin(), target_constraints.end(), |
| 376 | [](const auto &constraint) { |
| 377 | constexpr TargetMapper::TargetId kMaxRedId = 4; |
| 378 | TargetMapper::TargetId min_id = |
| 379 | std::min(constraint.id_begin, constraint.id_end); |
| 380 | TargetMapper::TargetId max_id = |
| 381 | std::max(constraint.id_begin, constraint.id_end); |
| 382 | return (min_id <= kMaxRedId && max_id > kMaxRedId); |
| 383 | }), |
| 384 | target_constraints.end()); |
| 385 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 386 | TargetMapper mapper(FLAGS_json_path, target_constraints); |
| 387 | mapper.Solve(FLAGS_field_name, FLAGS_output_dir); |
milind-u | 401de98 | 2023-04-14 17:32:03 -0700 | [diff] [blame^] | 388 | |
| 389 | if (!FLAGS_dump_constraints_to.empty()) { |
| 390 | mapper.DumpConstraints(FLAGS_dump_constraints_to); |
| 391 | } |
| 392 | if (!FLAGS_dump_stats_to.empty()) { |
| 393 | mapper.DumpStats(FLAGS_dump_stats_to); |
| 394 | } |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 395 | } |
| 396 | } |
| 397 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 398 | void MappingMain(int argc, char *argv[]) { |
| 399 | std::vector<std::string> unsorted_logfiles = |
| 400 | aos::logger::FindLogs(argc, argv); |
| 401 | |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 402 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 403 | |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 404 | std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config = |
| 405 | (FLAGS_config.empty() |
| 406 | ? std::nullopt |
| 407 | : std::make_optional(aos::configuration::ReadConfig(FLAGS_config))); |
Jim Ostrowski | aec5dd2 | 2023-02-27 22:17:53 -0800 | [diff] [blame] | 408 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 409 | // Open logfiles |
milind-u | 4a5ef8a | 2023-03-05 14:10:23 -0800 | [diff] [blame] | 410 | aos::logger::LogReader reader( |
| 411 | aos::logger::SortParts(unsorted_logfiles), |
| 412 | config.has_value() ? &config->message() : nullptr); |
milind-u | f3ab8ba | 2023-02-04 17:56:16 -0800 | [diff] [blame] | 413 | |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 414 | TargetMapperReplay mapper_replay(&reader); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 415 | reader.event_loop_factory()->Run(); |
milind-u | 2ab4db1 | 2023-03-25 21:59:23 -0700 | [diff] [blame] | 416 | mapper_replay.MaybeSolve(); |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 417 | } |
| 418 | |
| 419 | } // namespace vision |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 420 | } // namespace y2023 |
Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 421 | |
| 422 | int main(int argc, char **argv) { |
| 423 | aos::InitGoogle(&argc, &argv); |
milind-u | 16e3a08 | 2023-01-21 13:53:43 -0800 | [diff] [blame] | 424 | y2023::vision::MappingMain(argc, argv); |
Milind Upadhyay | 915d600 | 2022-12-26 20:37:43 -0800 | [diff] [blame] | 425 | } |