blob: 8b1e31e40cc66463abd410a0cab81c8048f1b540 [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 {
milind-u16e3a082023-01-21 13:53:43 -080024using frc971::vision::CharucoExtractor;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080025using frc971::vision::DataAdapter;
milind-u16e3a082023-01-21 13:53:43 -080026using frc971::vision::ImageCallback;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080027using frc971::vision::PoseUtils;
milind-u09fb1252023-01-28 19:21:41 -080028using frc971::vision::TargetMap;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080029using frc971::vision::TargetMapper;
milind-u16e3a082023-01-21 13:53:43 -080030namespace calibration = frc971::vision::calibration;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080031
32// Change reference frame from camera to robot
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080033Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camrob_target,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080034 Eigen::Affine3d extrinsics) {
35 const Eigen::Affine3d H_robot_camrob = extrinsics;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080036 const Eigen::Affine3d H_robot_target = H_robot_camrob * H_camrob_target;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080037 return H_robot_target;
38}
39
40// Add detected apriltag poses relative to the robot to
41// timestamped_target_detections
milind-u09fb1252023-01-28 19:21:41 -080042void HandleAprilTag(const TargetMap &map,
43 aos::distributed_clock::time_point pi_distributed_time,
Milind Upadhyay915d6002022-12-26 20:37:43 -080044 std::vector<DataAdapter::TimestampedDetection>
45 *timestamped_target_detections,
Milind Upadhyayc5beba12022-12-17 17:41:20 -080046 Eigen::Affine3d extrinsics) {
milind-u3f5f83c2023-01-29 15:23:51 -080047 for (const auto *target_pose_fbs : *map.target_poses()) {
48 const TargetMapper::TargetPose target_pose =
49 PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080050
milind-u3f5f83c2023-01-29 15:23:51 -080051 Eigen::Affine3d H_camcv_target =
52 Eigen::Translation3d(target_pose.pose.p) * target_pose.pose.q;
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080053 // With X, Y, Z being robot axes and x, y, z being camera axes,
54 // x = -Y, y = -Z, z = X
55 static const Eigen::Affine3d H_camcv_camrob =
56 Eigen::Affine3d((Eigen::Matrix4d() << 0.0, -1.0, 0.0, 0.0, 0.0, 0.0,
57 -1.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)
58 .finished());
59 Eigen::Affine3d H_camrob_target = H_camcv_camrob.inverse() * H_camcv_target;
Milind Upadhyayc5beba12022-12-17 17:41:20 -080060 Eigen::Affine3d H_robot_target =
61 CameraToRobotDetection(H_camrob_target, extrinsics);
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080062
Milind Upadhyayc5beba12022-12-17 17:41:20 -080063 ceres::examples::Pose3d target_pose_camera =
64 PoseUtils::Affine3dToPose3d(H_camrob_target);
65 double distance_from_camera = target_pose_camera.p.norm();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080066
milind-u09fb1252023-01-28 19:21:41 -080067 CHECK(map.has_monotonic_timestamp_ns())
68 << "Need detection timestamps for mapping";
69
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080070 timestamped_target_detections->emplace_back(
Milind Upadhyayebf93ee2023-01-05 14:12:58 -080071 DataAdapter::TimestampedDetection{
72 .time = pi_distributed_time,
73 .H_robot_target = H_robot_target,
74 .distance_from_camera = distance_from_camera,
milind-u3f5f83c2023-01-29 15:23:51 -080075 .id = static_cast<TargetMapper::TargetId>(target_pose.id)});
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080076 }
77}
78
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080079// Get images from pi and pass apriltag positions to HandleAprilTag()
80void HandlePiCaptures(
milind-u09fb1252023-01-28 19:21:41 -080081 aos::EventLoop *pi_event_loop, aos::logger::LogReader *reader,
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080082 std::vector<DataAdapter::TimestampedDetection>
83 *timestamped_target_detections,
milind-u09fb1252023-01-28 19:21:41 -080084 std::vector<std::unique_ptr<AprilRoboticsDetector>> *detectors) {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080085 // TODO(milind): change to /camera once we log at full frequency
86 static constexpr std::string_view kImageChannel = "/camera/decimated";
milind-uf2a4e322023-02-01 19:33:10 -080087 auto detector_ptr =
88 std::make_unique<AprilRoboticsDetector>(pi_event_loop, kImageChannel);
89 // Get the camera extrinsics
90 cv::Mat extrinsics_cv = detector_ptr->extrinsics();
91 Eigen::Matrix4d extrinsics_matrix;
92 cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
93 const auto extrinsics = Eigen::Affine3d(extrinsics_matrix);
94
95 detectors->emplace_back(std::move(detector_ptr));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -080096
milind-u09fb1252023-01-28 19:21:41 -080097 pi_event_loop->MakeWatcher("/camera", [=](const TargetMap &map) {
98 aos::distributed_clock::time_point pi_distributed_time =
99 reader->event_loop_factory()
100 ->GetNodeEventLoopFactory(pi_event_loop->node())
101 ->ToDistributedClock(aos::monotonic_clock::time_point(
102 aos::monotonic_clock::duration(map.monotonic_timestamp_ns())));
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800103
milind-u09fb1252023-01-28 19:21:41 -0800104 HandleAprilTag(map, pi_distributed_time, timestamped_target_detections,
105 extrinsics);
106 });
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800107}
108
109void MappingMain(int argc, char *argv[]) {
110 std::vector<std::string> unsorted_logfiles =
111 aos::logger::FindLogs(argc, argv);
112
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800113 std::vector<DataAdapter::TimestampedDetection> timestamped_target_detections;
114
115 // open logfiles
116 aos::logger::LogReader reader(aos::logger::SortParts(unsorted_logfiles));
117 reader.Register();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800118
milind-u09fb1252023-01-28 19:21:41 -0800119 std::vector<std::unique_ptr<AprilRoboticsDetector>> detectors;
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800120
121 const aos::Node *pi1 =
122 aos::configuration::GetNode(reader.configuration(), "pi1");
123 std::unique_ptr<aos::EventLoop> pi1_event_loop =
124 reader.event_loop_factory()->MakeEventLoop("pi1", pi1);
milind-uf2a4e322023-02-01 19:33:10 -0800125 HandlePiCaptures(pi1_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800126 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800127
128 const aos::Node *pi2 =
129 aos::configuration::GetNode(reader.configuration(), "pi2");
130 std::unique_ptr<aos::EventLoop> pi2_event_loop =
131 reader.event_loop_factory()->MakeEventLoop("pi2", pi2);
milind-uf2a4e322023-02-01 19:33:10 -0800132 HandlePiCaptures(pi2_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800133 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800134
135 const aos::Node *pi3 =
136 aos::configuration::GetNode(reader.configuration(), "pi3");
137 std::unique_ptr<aos::EventLoop> pi3_event_loop =
138 reader.event_loop_factory()->MakeEventLoop("pi3", pi3);
milind-uf2a4e322023-02-01 19:33:10 -0800139 HandlePiCaptures(pi3_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800140 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800141
142 const aos::Node *pi4 =
143 aos::configuration::GetNode(reader.configuration(), "pi4");
144 std::unique_ptr<aos::EventLoop> pi4_event_loop =
145 reader.event_loop_factory()->MakeEventLoop("pi4", pi4);
milind-uf2a4e322023-02-01 19:33:10 -0800146 HandlePiCaptures(pi4_event_loop.get(), &reader,
milind-u09fb1252023-01-28 19:21:41 -0800147 &timestamped_target_detections, &detectors);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800148
149 reader.event_loop_factory()->Run();
150
151 auto target_constraints =
Milind Upadhyayc5beba12022-12-17 17:41:20 -0800152 DataAdapter::MatchTargetDetections(timestamped_target_detections);
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800153
154 frc971::vision::TargetMapper mapper(FLAGS_json_path, target_constraints);
milind-u09fb1252023-01-28 19:21:41 -0800155 mapper.Solve("charged_up");
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800156
milind-u09fb1252023-01-28 19:21:41 -0800157 // Clean up all the pointers
158 for (auto &detector_ptr : detectors) {
159 detector_ptr.reset();
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800160 }
161}
162
163} // namespace vision
milind-u16e3a082023-01-21 13:53:43 -0800164} // namespace y2023
Yash Chainanid5c7f0d2022-11-19 17:05:57 -0800165
166int main(int argc, char **argv) {
167 aos::InitGoogle(&argc, &argv);
milind-u16e3a082023-01-21 13:53:43 -0800168 y2023::vision::MappingMain(argc, argv);
Milind Upadhyay915d6002022-12-26 20:37:43 -0800169}