blob: 7a5f7924ff9dd23bdcafd7003dfb7b27e8ab6068 [file] [log] [blame]
milind-ud4051fe2023-02-25 18:00:05 -08001#include "aos/init.h"
2#include "frc971/constants/constants_sender_lib.h"
3#include "frc971/control_loops/drivetrain/localization/localizer_output_generated.h"
4#include "frc971/vision/vision_generated.h"
5#include "glog/logging.h"
6#include "y2023/localizer/localizer.h"
7
8DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
9
10DEFINE_uint64(min_april_id, 1,
11 "Minimum april id to consider as part of the field and ignore");
12DEFINE_uint64(max_april_id, 8,
13 "Maximum april id to consider as part of the field and ignore");
14
15// This binary allows us to place extra april tags on the field and verify
16// that we can compute their field pose correctly
17
18namespace y2023::vision {
19
20using localizer::Localizer;
21
22Localizer::Transform LocalizerOutputToTransform(
23 const frc971::controls::LocalizerOutput &localizer) {
24 const auto T_field_robot =
25 Eigen::Translation3d(localizer.x(), localizer.y(), 0.0);
26
27 Eigen::AngleAxisd robot_yaw_angle(localizer.theta(),
28 Eigen::Vector3d::UnitZ());
29 const auto R_field_robot = Eigen::Quaterniond(robot_yaw_angle);
30 const Localizer::Transform H_field_robot =
31 (T_field_robot * R_field_robot).matrix();
32 return H_field_robot;
33}
34
35void HandleDetections(
36 const frc971::vision::TargetMap &detections,
37 const Localizer::Transform &H_robot_camera,
38 aos::Fetcher<frc971::controls::LocalizerOutput> *localizer_fetcher) {
39 localizer_fetcher->Fetch();
40 CHECK(localizer_fetcher->get());
41
42 for (const auto *target_pose : *detections.target_poses()) {
43 // Only look at april tags not part of the field
44 if (target_pose->id() >= FLAGS_min_april_id &&
45 target_pose->id() <= FLAGS_max_april_id) {
46 continue;
47 }
48
49 const Localizer::Transform H_camera_target =
50 localizer::PoseToTransform(target_pose);
51 const Localizer::Transform H_field_robot =
52 LocalizerOutputToTransform(*localizer_fetcher->get());
53
54 // Get the field-based target pose using the detection, extrinsics, and
55 // localizer output
56 const Localizer::Transform H_field_target =
57 H_field_robot * H_robot_camera * H_camera_target;
58
59 LOG(INFO) << "Field to target " << target_pose->id();
60 LOG(INFO) << "Transform: " << H_field_target;
61 LOG(INFO) << "Translation: "
62 << Eigen::Affine3d(H_field_target).translation();
63 LOG(INFO);
64 }
65}
66
67void LocalizationVerifierMain() {
68 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
69 aos::configuration::ReadConfig(FLAGS_config);
70
71 frc971::constants::WaitForConstants<Constants>(&config.message());
72
73 aos::ShmEventLoop event_loop(&config.message());
74
75 frc971::constants::ConstantsFetcher<Constants> constants_fetcher(&event_loop);
76
77 aos::Fetcher<frc971::controls::LocalizerOutput> localizer_fetcher =
78 event_loop.MakeFetcher<frc971::controls::LocalizerOutput>("/localizer");
79
80 for (const auto *camera : *constants_fetcher.constants().cameras()) {
81 CHECK(camera->has_calibration());
82 Localizer::Transform H_robot_camera =
83 frc971::control_loops::drivetrain::FlatbufferToTransformationMatrix(
84 *camera->calibration()->fixed_extrinsics());
85
86 const std::string_view pi_name =
87 camera->calibration()->node_name()->string_view();
88 event_loop.MakeWatcher(absl::StrCat("/", pi_name, "/camera"),
89 [&](const frc971::vision::TargetMap &target_map) {
90 HandleDetections(target_map, H_robot_camera,
91 &localizer_fetcher);
92 });
93
94 event_loop.Run();
95 }
96}
97
98} // namespace y2023::vision
99
100int main(int argc, char **argv) {
101 aos::InitGoogle(&argc, &argv);
102 y2023::vision::LocalizationVerifierMain();
103}