blob: f8a8e3890a400145702e0159eb35006bee5848ad [file] [log] [blame]
Maxwell Hendersonfebee252023-01-28 16:53:52 -08001#include "y2023/vision/aprilrobotics.h"
2
3DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
4
5DEFINE_bool(
6 debug, false,
7 "If true, dump a ton of debug and crash on the first valid detection.");
8
9DEFINE_int32(team_number, 971,
10 "Use the calibration for a node with this team number");
11namespace y2023 {
12namespace vision {
13
14AprilRoboticsDetector::AprilRoboticsDetector(aos::EventLoop *event_loop,
15 std::string_view channel_name)
16 : calibration_data_(CalibrationData()),
17 ftrace_(),
18 image_callback_(event_loop, channel_name,
19 [&](cv::Mat image_color_mat,
20 const aos::monotonic_clock::time_point /*eof*/) {
21 HandleImage(image_color_mat);
22 }),
23 target_map_sender_(
24 event_loop->MakeSender<frc971::vision::TargetMap>("/camera")) {
25 tag_family_ = tag16h5_create();
26 tag_detector_ = apriltag_detector_create();
27
28 apriltag_detector_add_family_bits(tag_detector_, tag_family_, 1);
29 tag_detector_->nthreads = 6;
30 tag_detector_->wp = workerpool_create(tag_detector_->nthreads);
31 tag_detector_->qtp.min_white_black_diff = 5;
32 tag_detector_->debug = FLAGS_debug;
33
34 std::string hostname = aos::network::GetHostname();
35
36 // Check team string is valid
37 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(hostname);
38 std::optional<uint16_t> team_number =
39 aos::network::team_number_internal::ParsePiTeamNumber(hostname);
40 CHECK(pi_number) << "Unable to parse pi number from '" << hostname << "'";
41 CHECK(team_number);
42
43 calibration_ = FindCameraCalibration(&calibration_data_.message(),
44 "pi" + std::to_string(*pi_number));
45 intrinsics_ = CameraIntrinsics(calibration_);
46 camera_distortion_coeffs_ = CameraDistCoeffs(calibration_);
47
48 image_callback_.set_format(frc971::vision::ImageCallback::Format::GRAYSCALE);
49}
50
51AprilRoboticsDetector::~AprilRoboticsDetector() {
52 apriltag_detector_destroy(tag_detector_);
53 free(tag_family_);
54}
55
56void AprilRoboticsDetector::SetWorkerpoolAffinities() {
57 for (int i = 0; i < tag_detector_->wp->nthreads; i++) {
58 cpu_set_t affinity;
59 CPU_ZERO(&affinity);
60 CPU_SET(i, &affinity);
61 pthread_setaffinity_np(tag_detector_->wp->threads[i], sizeof(affinity),
62 &affinity);
63 struct sched_param param;
64 param.sched_priority = 20;
65 int res = pthread_setschedparam(tag_detector_->wp->threads[i], SCHED_FIFO,
66 &param);
67 PCHECK(res == 0) << "Failed to set priority of threadpool threads";
68 }
69}
70
71void AprilRoboticsDetector::HandleImage(cv::Mat image_color_mat) {
72 std::vector<std::pair<apriltag_detection_t, apriltag_pose_t>> detections =
73 DetectTags(image_color_mat);
74
75 auto builder = target_map_sender_.MakeBuilder();
76 std::vector<flatbuffers::Offset<frc971::vision::TargetPoseFbs>> target_poses;
77 for (const auto &[detection, pose] : detections) {
78 target_poses.emplace_back(
79 BuildTargetPose(pose, detection.id, builder.fbb()));
80 }
81 const auto target_poses_offset = builder.fbb()->CreateVector(target_poses);
82 auto target_map_builder = builder.MakeBuilder<frc971::vision::TargetMap>();
83
84 target_map_builder.add_target_poses(target_poses_offset);
85 builder.CheckOk(builder.Send(target_map_builder.Finish()));
86}
87
88flatbuffers::Offset<frc971::vision::TargetPoseFbs>
89AprilRoboticsDetector::BuildTargetPose(
90 const apriltag_pose_t &pose,
91 frc971::vision::TargetMapper::TargetId target_id,
92 flatbuffers::FlatBufferBuilder *fbb) {
93 const auto T =
94 Eigen::Translation3d(pose.t->data[0], pose.t->data[1], pose.t->data[2]);
95 const auto rpy = frc971::vision::PoseUtils::RotationMatrixToEulerAngles(
96 Eigen::Matrix3d(pose.R->data));
97 return frc971::vision::CreateTargetPoseFbs(*fbb, target_id, T.x(), T.y(),
98 T.z(), rpy(0), rpy(1), rpy(2));
99}
100
101std::vector<std::pair<apriltag_detection_t, apriltag_pose_t>>
102AprilRoboticsDetector::DetectTags(cv::Mat image) {
103 const aos::monotonic_clock::time_point start_time =
104 aos::monotonic_clock::now();
105
106 image_u8_t im = {
107 .width = image.cols,
108 .height = image.rows,
109 .stride = image.cols,
110 .buf = image.data,
111 };
112
113 ftrace_.FormatMessage("Starting detect\n");
114 zarray_t *detections = apriltag_detector_detect(tag_detector_, &im);
115 ftrace_.FormatMessage("Done detecting\n");
116
117 std::vector<std::pair<apriltag_detection_t, apriltag_pose_t>> results;
118
119 for (int i = 0; i < zarray_size(detections); i++) {
120 apriltag_detection_t *det;
121 zarray_get(detections, i, &det);
122
123 if (det->decision_margin > 30) {
124 VLOG(1) << "Found tag number " << det->id << " hamming: " << det->hamming
125 << " margin: " << det->decision_margin;
126
127 const aos::monotonic_clock::time_point before_pose_estimation =
128 aos::monotonic_clock::now();
129 // First create an apriltag_detection_info_t struct using your known
130 // parameters.
131 apriltag_detection_info_t info;
132 info.det = det;
133 info.tagsize = 0.1524;
134 info.fx = intrinsics_.at<double>(0, 0);
135 info.fy = intrinsics_.at<double>(1, 1);
136 info.cx = intrinsics_.at<double>(0, 2);
137 info.cy = intrinsics_.at<double>(1, 2);
138
139 apriltag_pose_t pose;
140 double err = estimate_tag_pose(&info, &pose);
141
142 VLOG(1) << "err: " << err;
143
144 results.emplace_back(*det, pose);
145
146 const aos::monotonic_clock::time_point after_pose_estimation =
147 aos::monotonic_clock::now();
148
149 VLOG(1) << "Took "
150 << std::chrono::duration<double>(after_pose_estimation -
151 before_pose_estimation)
152 .count()
153 << " seconds for pose estimation";
154 }
155 }
156
157 apriltag_detections_destroy(detections);
158
159 const aos::monotonic_clock::time_point end_time = aos::monotonic_clock::now();
160
161 timeprofile_display(tag_detector_->tp);
162
163 VLOG(1) << "Took "
164 << std::chrono::duration<double>(end_time - start_time).count()
165 << " seconds to detect overall";
166
167 return results;
168}
169
170void AprilViewerMain() {
171 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
172 aos::configuration::ReadConfig(FLAGS_config);
173
174 aos::ShmEventLoop event_loop(&config.message());
175
176 AprilRoboticsDetector detector(&event_loop, "/camera");
177
178 detector.SetWorkerpoolAffinities();
179
180 event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({5}));
181
182 struct sched_param param;
183 param.sched_priority = 21;
184 PCHECK(sched_setscheduler(0, SCHED_FIFO, &param) == 0);
185
186 event_loop.Run();
187}
188
189} // namespace vision
190} // namespace y2023
191
192int main(int argc, char **argv) {
193 aos::InitGoogle(&argc, &argv);
194 y2023::vision::AprilViewerMain();
195
196 return 0;
197}