blob: 4f10499206dd0522d40c34ff24796ce2daa20739 [file] [log] [blame]
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08001#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"
milind-u16e3a082023-01-21 13:53:43 -08005#include "frc971/vision/calibration_generated.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -08006#include "frc971/vision/charuco_lib.h"
7#include "frc971/vision/target_mapper.h"
8#include "opencv2/aruco.hpp"
9#include "opencv2/calib3d.hpp"
10#include "opencv2/core/eigen.hpp"
11#include "opencv2/features2d.hpp"
12#include "opencv2/highgui.hpp"
13#include "opencv2/highgui/highgui.hpp"
14#include "opencv2/imgproc.hpp"
milind-u09fb1252023-01-28 19:21:41 -080015#include "y2023/vision/aprilrobotics.h"
James Kuszmauld67f6d22023-02-05 17:37:25 -080016#include "y2023/vision/vision_util.h"
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080017
18DEFINE_string(json_path, "target_map.json",
19 "Specify path for json with initial pose guesses.");
milind-u09fb1252023-01-28 19:21:41 -080020DECLARE_int32(team_number);
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080021
milind-u16e3a082023-01-21 13:53:43 -080022namespace y2023 {
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080023namespace vision {
24using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080025using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080026using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080027using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080028using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080029namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080030
31// Change reference frame from camera to robot
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080032Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080033 Eigen::Affine3d extrinsics) {
34 const Eigen::Affine3d H_robot_camrob = extrinsics;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080035 const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080036 return H_robot_target;
37}
38
39// Add detected apriltag poses relative to the robot to
40// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080041void HandleAprilTag(const TargetMap &map,
42 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080043 std::vector<DataAdapter::TimestampedDetection>
44 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080045 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080046 for (const auto *target_pose_fbs : *map.target_poses()) {
47 const TargetMapper::TargetPose target_pose =
48 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080049
milind-u3f5f83c2023-01-29 15:23:51 -080050 Eigen::Affine3d H_camcv_target =
51 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080052 // With X, Y, Z being robot axes and x, y, z being camera axes,
53 // x = -Y, y = -Z, z = X
54 static const Eigen::Affine3d H_camcv_camrob =
55 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0,
56 -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
57 .finished());
58 Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080059 Eigen::Affine3d H_robot_target =
60 CameraToRobotDetection(H_camrob_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080061
Milind Upadhyayc5beba12022-12-17 17:41:20 -080062 ceres::examples::Pose3d target_pose_camera =
63 PoseUtils::Affine3dToPose3d(H_camrob_target);
64 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080065
milind-u09fb1252023-01-28 19:21:41 -080066 CHECK(map.has_monotonic_timestamp_ns())
67 << "Need detection timestamps for mapping";
68
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080069 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080070 DataAdapter::TimestampedDetection{
71 .time = pi_distributed_time,
72 .H_robot_target = H_robot_target,
73 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080074 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080075 }
76}
77
Milind Upadhyayc5beba12022-12-17 17:41:20 -080078Eigen::Affine3d CameraExtrinsics(
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080079 const calibration::CameraCalibration *camera_calibration) {
milind-u16e3a082023-01-21 13:53:43 -080080 const frc971::vision::calibration::TransformationMatrix *transform =
81 camera_calibration->has_turret_extrinsics()
82 ? camera_calibration->turret_extrinsics()
83 : camera_calibration->fixed_extrinsics();
84
85 cv::Mat result(
86 4, 4, CV_32F,
87 const_cast<void *>(static_cast<const void *>(transform->data()->data())));
88 result.convertTo(result, CV_64F);
89 CHECK_EQ(result.total(), transform->data()->size());
90
91 Eigen::Matrix4d result_eigen;
92 cv::cv2eigen(result, result_eigen);
93 return Eigen::Affine3d(result_eigen);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080094}
95
96// Get images from pi and pass apriltag positions to HandleAprilTag()
97void HandlePiCaptures(
James Kuszmauld67f6d22023-02-05 17:37:25 -080098 const frc971::constants::ConstantsFetcher<Constants> &constants,
milind-u09fb1252023-01-28 19:21:41 -080099 aos::EventLoop *pi_event_loop, aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800100 std::vector<DataAdapter::TimestampedDetection>
101 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -0800102 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
milind-u09fb1252023-01-28 19:21:41 -0800103
104 const auto node_name = pi_event_loop->node()->name()->string_view();
105 const calibration::CameraCalibration *calibration =
James Kuszmauld67f6d22023-02-05 17:37:25 -0800106 FindCameraCalibration(constants.constants(), node_name);
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800107 const auto extrinsics = CameraExtrinsics(calibration);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800108
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800109 // TODO(milind): change to /camera once we log at full frequency
110 static constexpr std::string_view kImageChannel = "/camera/decimated";
milind-u09fb1252023-01-28 19:21:41 -0800111 detectors->emplace_back(
112 std::make_unique<AprilRoboticsDetector>(pi_event_loop, kImageChannel));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800113
milind-u09fb1252023-01-28 19:21:41 -0800114 pi_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
115 aos::distributed_clock::time_point pi_distributed_time =
116 reader->event_loop_factory()
117 ->GetNodeEventLoopFactory(pi_event_loop->node())
118 ->ToDistributedClock(aos::monotonic_clock::time_point(
119 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120
milind-u09fb1252023-01-28 19:21:41 -0800121 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
122 extrinsics);
123 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800124}
125
126void MappingMain(int argc, char *argv[]) {
127 std::vector<std::string> unsorted_logfiles =
128 aos::logger::FindLogs(argc, argv);
129
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800130 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
131
132 // open logfiles
133 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
134 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800135
milind-u09fb1252023-01-28 19:21:41 -0800136 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800137
138 const aos::Node *pi1 =
139 aos::configuration::GetNode(reader.configuration(), "pi1");
140 std::unique_ptr<aos::EventLoop> pi1_event_loop =
141 reader.event_loop_factory()->MakeEventLoop("pi1", pi1);
James Kuszmauld67f6d22023-02-05 17:37:25 -0800142 frc971::constants::ConstantsFetcher<Constants> pi1_constants(
143 pi1_event_loop.get());
144 HandlePiCaptures(pi1_constants, pi1_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800145 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800146
147 const aos::Node *pi2 =
148 aos::configuration::GetNode(reader.configuration(), "pi2");
149 std::unique_ptr<aos::EventLoop> pi2_event_loop =
150 reader.event_loop_factory()->MakeEventLoop("pi2", pi2);
James Kuszmauld67f6d22023-02-05 17:37:25 -0800151 frc971::constants::ConstantsFetcher<Constants> pi2_constants(
152 pi2_event_loop.get());
153 HandlePiCaptures(pi2_constants, pi2_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800154 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800155
156 const aos::Node *pi3 =
157 aos::configuration::GetNode(reader.configuration(), "pi3");
158 std::unique_ptr<aos::EventLoop> pi3_event_loop =
159 reader.event_loop_factory()->MakeEventLoop("pi3", pi3);
James Kuszmauld67f6d22023-02-05 17:37:25 -0800160 frc971::constants::ConstantsFetcher<Constants> pi3_constants(
161 pi3_event_loop.get());
162 HandlePiCaptures(pi3_constants, pi3_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800163 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800164
165 const aos::Node *pi4 =
166 aos::configuration::GetNode(reader.configuration(), "pi4");
167 std::unique_ptr<aos::EventLoop> pi4_event_loop =
168 reader.event_loop_factory()->MakeEventLoop("pi4", pi4);
James Kuszmauld67f6d22023-02-05 17:37:25 -0800169 frc971::constants::ConstantsFetcher<Constants> pi4_constants(
170 pi4_event_loop.get());
171 HandlePiCaptures(pi4_constants, pi4_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800172 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800173
174 reader.event_loop_factory()->Run();
175
176 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800177 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800178
179 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-u09fb1252023-01-28 19:21:41 -0800180 mapper.Solve("charged_up");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800181
milind-u09fb1252023-01-28 19:21:41 -0800182 // Clean up all the pointers
183 for (auto &detector_ptr : detectors) {
184 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800185 }
186}
187
188} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800189} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800190
191int main(int argc, char **argv) {
192 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800193 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800194}