Yash Chainani | d5c7f0d | 2022-11-19 17:05:57 -0800 | [diff] [blame] | 1 | #include "aos/events/logging/log_reader.h" |
| 2 | #include "aos/events/simulated_event_loop.h" |
| 3 | #include "aos/init.h" |
| 4 | #include "frc971/control_loops/pose.h" |
| 5 | #include "frc971/vision/charuco_lib.h" |
| 6 | #include "frc971/vision/target_mapper.h" |
| 7 | #include "opencv2/aruco.hpp" |
| 8 | #include "opencv2/calib3d.hpp" |
| 9 | #include "opencv2/core/eigen.hpp" |
| 10 | #include "opencv2/features2d.hpp" |
| 11 | #include "opencv2/highgui.hpp" |
| 12 | #include "opencv2/highgui/highgui.hpp" |
| 13 | #include "opencv2/imgproc.hpp" |
| 14 | #include "y2022/control_loops/superstructure/superstructure_status_generated.h" |
| 15 | #include "y2022/vision/camera_reader.h" |
| 16 | |
| 17 | DEFINE_string(json_path, "target_map.json", |
| 18 | "Specify path for json with initial pose guesses."); |
| 19 | DEFINE_int32( |
| 20 | team_number, 971, |
| 21 | "If reading locally, use the calibration for a node with this team number"); |
| 22 | |
| 23 | namespace y2022 { |
| 24 | namespace vision { |
| 25 | using frc971::vision::DataAdapter; |
| 26 | using frc971::vision::PoseUtils; |
| 27 | using frc971::vision::TargetMapper; |
| 28 | namespace superstructure = ::y2022::control_loops::superstructure; |
| 29 | |
| 30 | // Find transformation from camera to robot reference frame |
| 31 | Eigen::Affine3d CameraTransform(Eigen::Affine3d fixed_extrinsics, |
| 32 | Eigen::Affine3d turret_extrinsics, |
| 33 | double turret_position) { |
| 34 | // Calculate the pose of the camera relative to the robot origin. |
| 35 | Eigen::Affine3d H_robot_camrob = |
| 36 | fixed_extrinsics * |
| 37 | Eigen::Affine3d(frc971::control_loops::TransformationMatrixForYaw<double>( |
| 38 | turret_position)) * |
| 39 | turret_extrinsics; |
| 40 | |
| 41 | return H_robot_camrob; |
| 42 | } |
| 43 | |
| 44 | // Change reference frame from camera to robot |
| 45 | Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camcv_target, |
| 46 | Eigen::Affine3d fixed_extrinsics, |
| 47 | Eigen::Affine3d turret_extrinsics, |
| 48 | double turret_position) { |
| 49 | // With X, Y, Z being robot axes and x, y, z being camera axes, |
| 50 | // x = -Y, y = -Z, z = X |
| 51 | const Eigen::Affine3d H_camcv_camrob = |
| 52 | Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0, -1.0, |
| 53 | 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0) |
| 54 | .finished()); |
| 55 | |
| 56 | const Eigen::Affine3d H_robot_camrob = |
| 57 | CameraTransform(fixed_extrinsics, turret_extrinsics, turret_position); |
| 58 | const Eigen::Affine3d H_robot_target = |
| 59 | H_robot_camrob * H_camcv_camrob.inverse() * H_camcv_target; |
| 60 | return H_robot_target; |
| 61 | } |
| 62 | |
| 63 | // Add detected apriltag poses relative to the robot to |
| 64 | // timestamped_target_detections |
| 65 | void HandleAprilTag( |
| 66 | aos::distributed_clock::time_point pi_distributed_time, |
| 67 | std::vector<cv::Vec4i> april_ids, std::vector<Eigen::Vector3d> rvecs_eigen, |
| 68 | std::vector<Eigen::Vector3d> tvecs_eigen, |
| 69 | std::vector<DataAdapter::TimestampedDetection> |
| 70 | *timestamped_target_detections, |
| 71 | aos::Fetcher<superstructure::Status> *superstructure_status_fetcher, |
| 72 | Eigen::Affine3d fixed_extrinsics, Eigen::Affine3d turret_extrinsics) { |
| 73 | CHECK(superstructure_status_fetcher->Fetch()); |
| 74 | double turret_position = |
| 75 | superstructure_status_fetcher->get()->turret()->position(); |
| 76 | |
| 77 | for (size_t tag = 0; tag < april_ids.size(); tag++) { |
| 78 | Eigen::Translation3d T_camera_target = Eigen::Translation3d( |
| 79 | tvecs_eigen[tag][0], tvecs_eigen[tag][1], tvecs_eigen[tag][2]); |
| 80 | Eigen::AngleAxisd r_angle = Eigen::AngleAxisd( |
| 81 | rvecs_eigen[tag].norm(), rvecs_eigen[tag] / rvecs_eigen[tag].norm()); |
| 82 | CHECK(rvecs_eigen[tag].norm() != 0) << "rvecs norm = 0; divide by 0"; |
| 83 | Eigen::Affine3d H_camcv_target = T_camera_target * r_angle; |
| 84 | |
| 85 | Eigen::Affine3d H_robot_target = CameraToRobotDetection( |
| 86 | H_camcv_target, fixed_extrinsics, turret_extrinsics, turret_position); |
| 87 | |
| 88 | timestamped_target_detections->emplace_back( |
| 89 | DataAdapter::TimestampedDetection{.time = pi_distributed_time, |
| 90 | .H_robot_target = H_robot_target, |
| 91 | .id = april_ids[tag][0]}); |
| 92 | } |
| 93 | } |
| 94 | |
| 95 | Eigen::Affine3d CameraFixedExtrinsics( |
| 96 | const calibration::CameraCalibration *camera_calibration) { |
| 97 | cv::Mat extrinsics( |
| 98 | 4, 4, CV_32F, |
| 99 | const_cast<void *>(static_cast<const void *>( |
| 100 | camera_calibration->fixed_extrinsics()->data()->data()))); |
| 101 | extrinsics.convertTo(extrinsics, CV_64F); |
| 102 | CHECK_EQ(extrinsics.total(), |
| 103 | camera_calibration->fixed_extrinsics()->data()->size()); |
| 104 | Eigen::Matrix4d extrinsics_eigen; |
| 105 | cv::cv2eigen(extrinsics, extrinsics_eigen); |
| 106 | return Eigen::Affine3d(extrinsics_eigen); |
| 107 | } |
| 108 | |
| 109 | Eigen::Affine3d CameraTurretExtrinsics( |
| 110 | const calibration::CameraCalibration *camera_calibration) { |
| 111 | cv::Mat extrinsics( |
| 112 | 4, 4, CV_32F, |
| 113 | const_cast<void *>(static_cast<const void *>( |
| 114 | camera_calibration->turret_extrinsics()->data()->data()))); |
| 115 | extrinsics.convertTo(extrinsics, CV_64F); |
| 116 | CHECK_EQ(extrinsics.total(), |
| 117 | camera_calibration->turret_extrinsics()->data()->size()); |
| 118 | Eigen::Matrix4d extrinsics_eigen; |
| 119 | cv::cv2eigen(extrinsics, extrinsics_eigen); |
| 120 | return Eigen::Affine3d(extrinsics_eigen); |
| 121 | } |
| 122 | |
| 123 | // Get images from pi and pass apriltag positions to HandleAprilTag() |
| 124 | void HandlePiCaptures( |
| 125 | int pi_number, aos::EventLoop *pi_event_loop, |
| 126 | aos::logger::LogReader *reader, |
| 127 | aos::Fetcher<superstructure::Status> *superstructure_status_fetcher, |
| 128 | std::vector<DataAdapter::TimestampedDetection> |
| 129 | *timestamped_target_detections, |
| 130 | std::vector<std::unique_ptr<CharucoExtractor>> *charuco_extractors, |
| 131 | std::vector<std::unique_ptr<ImageCallback>> *image_callbacks) { |
| 132 | const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data( |
| 133 | CalibrationData()); |
| 134 | const calibration::CameraCalibration *calibration = |
| 135 | CameraReader::FindCameraCalibration(&calibration_data.message(), |
| 136 | "pi" + std::to_string(pi_number), |
| 137 | FLAGS_team_number); |
| 138 | const auto turret_extrinsics = CameraTurretExtrinsics(calibration); |
| 139 | const auto fixed_extrinsics = CameraFixedExtrinsics(calibration); |
| 140 | |
| 141 | charuco_extractors->emplace_back(std::make_unique<CharucoExtractor>( |
| 142 | pi_event_loop, |
| 143 | "pi-" + std::to_string(FLAGS_team_number) + "-" + |
| 144 | std::to_string(pi_number), |
| 145 | [=](cv::Mat /*rgb_image*/, aos::monotonic_clock::time_point eof, |
| 146 | std::vector<cv::Vec4i> april_ids, |
| 147 | std::vector<std::vector<cv::Point2f>> /*april_corners*/, bool valid, |
| 148 | std::vector<Eigen::Vector3d> rvecs_eigen, |
| 149 | std::vector<Eigen::Vector3d> tvecs_eigen) { |
| 150 | aos::distributed_clock::time_point pi_distributed_time = |
| 151 | reader->event_loop_factory() |
| 152 | ->GetNodeEventLoopFactory(pi_event_loop->node()) |
| 153 | ->ToDistributedClock(eof); |
| 154 | |
| 155 | if (valid) { |
| 156 | HandleAprilTag(pi_distributed_time, april_ids, rvecs_eigen, |
| 157 | tvecs_eigen, timestamped_target_detections, |
| 158 | superstructure_status_fetcher, fixed_extrinsics, |
| 159 | turret_extrinsics); |
| 160 | } |
| 161 | })); |
| 162 | |
| 163 | std::string channel = |
| 164 | absl::StrCat("/pi", std::to_string(pi_number), "/camera"); |
| 165 | |
| 166 | image_callbacks->emplace_back(std::make_unique<ImageCallback>( |
| 167 | pi_event_loop, "/pi" + std::to_string(pi_number) + "/camera", |
| 168 | [&, charuco_extractor = |
| 169 | charuco_extractors->at(charuco_extractors->size() - 1).get()]( |
| 170 | cv::Mat rgb_image, const aos::monotonic_clock::time_point eof) { |
| 171 | charuco_extractor->HandleImage(rgb_image, eof); |
| 172 | })); |
| 173 | } |
| 174 | |
| 175 | void MappingMain(int argc, char *argv[]) { |
| 176 | std::vector<std::string> unsorted_logfiles = |
| 177 | aos::logger::FindLogs(argc, argv); |
| 178 | |
| 179 | std::vector<DataAdapter::TimestampedPose> timestamped_robot_poses; |
| 180 | std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections; |
| 181 | |
| 182 | // open logfiles |
| 183 | aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles)); |
| 184 | reader.Register(); |
| 185 | const aos::Node *imu_node = |
| 186 | aos::configuration::GetNode(reader.configuration(), "imu"); |
| 187 | |
| 188 | std::unique_ptr<aos::EventLoop> imu_event_loop = |
| 189 | reader.event_loop_factory()->MakeEventLoop("imu", imu_node); |
| 190 | |
| 191 | const aos::Node *roborio_node = |
| 192 | aos::configuration::GetNode(reader.configuration(), "roborio"); |
| 193 | |
| 194 | std::unique_ptr<aos::EventLoop> roborio_event_loop = |
| 195 | reader.event_loop_factory()->MakeEventLoop("roborio", roborio_node); |
| 196 | |
| 197 | imu_event_loop->MakeWatcher( |
| 198 | "/localizer", [&](const frc971::controls::LocalizerOutput &localizer) { |
| 199 | aos::monotonic_clock::time_point imu_monotonic_time = |
| 200 | aos::monotonic_clock::time_point(aos::monotonic_clock::duration( |
| 201 | localizer.monotonic_timestamp_ns())); |
| 202 | aos::distributed_clock::time_point imu_distributed_time = |
| 203 | reader.event_loop_factory() |
| 204 | ->GetNodeEventLoopFactory(imu_node) |
| 205 | ->ToDistributedClock(imu_monotonic_time); |
| 206 | |
| 207 | timestamped_robot_poses.emplace_back(DataAdapter::TimestampedPose{ |
| 208 | .time = imu_distributed_time, |
| 209 | .pose = ceres::examples::Pose2d{.x = localizer.x(), |
| 210 | .y = localizer.y(), |
| 211 | .yaw_radians = localizer.theta()}}); |
| 212 | }); |
| 213 | |
| 214 | // Override target_type to AprilTag, since that's what we're using here |
| 215 | FLAGS_target_type = "april_tag"; |
| 216 | |
| 217 | auto superstructure_status_fetcher = |
| 218 | roborio_event_loop->MakeFetcher<superstructure::Status>( |
| 219 | "/superstructure"); |
| 220 | |
| 221 | std::vector<std::unique_ptr<CharucoExtractor>> charuco_extractors; |
| 222 | std::vector<std::unique_ptr<ImageCallback>> image_callbacks; |
| 223 | |
| 224 | const aos::Node *pi1 = |
| 225 | aos::configuration::GetNode(reader.configuration(), "pi1"); |
| 226 | std::unique_ptr<aos::EventLoop> pi1_event_loop = |
| 227 | reader.event_loop_factory()->MakeEventLoop("pi1", pi1); |
| 228 | HandlePiCaptures( |
| 229 | 1, pi1_event_loop.get(), &reader, &superstructure_status_fetcher, |
| 230 | ×tamped_target_detections, &charuco_extractors, &image_callbacks); |
| 231 | |
| 232 | const aos::Node *pi2 = |
| 233 | aos::configuration::GetNode(reader.configuration(), "pi2"); |
| 234 | std::unique_ptr<aos::EventLoop> pi2_event_loop = |
| 235 | reader.event_loop_factory()->MakeEventLoop("pi2", pi2); |
| 236 | HandlePiCaptures( |
| 237 | 2, pi2_event_loop.get(), &reader, &superstructure_status_fetcher, |
| 238 | ×tamped_target_detections, &charuco_extractors, &image_callbacks); |
| 239 | |
| 240 | const aos::Node *pi3 = |
| 241 | aos::configuration::GetNode(reader.configuration(), "pi3"); |
| 242 | std::unique_ptr<aos::EventLoop> pi3_event_loop = |
| 243 | reader.event_loop_factory()->MakeEventLoop("pi3", pi3); |
| 244 | HandlePiCaptures( |
| 245 | 3, pi3_event_loop.get(), &reader, &superstructure_status_fetcher, |
| 246 | ×tamped_target_detections, &charuco_extractors, &image_callbacks); |
| 247 | |
| 248 | const aos::Node *pi4 = |
| 249 | aos::configuration::GetNode(reader.configuration(), "pi4"); |
| 250 | std::unique_ptr<aos::EventLoop> pi4_event_loop = |
| 251 | reader.event_loop_factory()->MakeEventLoop("pi4", pi4); |
| 252 | HandlePiCaptures( |
| 253 | 4, pi4_event_loop.get(), &reader, &superstructure_status_fetcher, |
| 254 | ×tamped_target_detections, &charuco_extractors, &image_callbacks); |
| 255 | |
| 256 | reader.event_loop_factory()->Run(); |
| 257 | |
| 258 | auto target_constraints = |
| 259 | DataAdapter::MatchTargetDetections(timestamped_robot_poses, |
| 260 | timestamped_target_detections) |
| 261 | .first; |
| 262 | |
| 263 | frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints); |
| 264 | mapper.Solve(); |
| 265 | |
| 266 | // Pointers need to be deleted to destruct all fetchers |
| 267 | for (auto &charuco_extractor_ptr : charuco_extractors) { |
| 268 | charuco_extractor_ptr.reset(); |
| 269 | } |
| 270 | |
| 271 | for (auto &image_callback_ptr : image_callbacks) { |
| 272 | image_callback_ptr.reset(); |
| 273 | } |
| 274 | } |
| 275 | |
| 276 | } // namespace vision |
| 277 | } // namespace y2022 |
| 278 | |
| 279 | int main(int argc, char **argv) { |
| 280 | aos::InitGoogle(&argc, &argv); |
| 281 | y2022::vision::MappingMain(argc, argv); |
| 282 | } |