blob: fd24ffee478dc04e9c6804ad9e7cfd92d7749621 [file] [log] [blame]
Austin Schuh99f7c6a2024-06-25 22:07:44 -07001#include "absl/flags/flag.h"
2#include "absl/log/check.h"
3#include "absl/log/log.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07004
milind-ud4051fe2023-02-25 18:00:05 -08005#include "aos/init.h"
6#include "frc971/constants/constants_sender_lib.h"
7#include "frc971/control_loops/drivetrain/localization/localizer_output_generated.h"
James Kuszmaul9c3db182024-02-09 22:02:18 -08008#include "frc971/vision/target_map_utils.h"
milind-ud4051fe2023-02-25 18:00:05 -08009#include "frc971/vision/vision_generated.h"
milind-ud4051fe2023-02-25 18:00:05 -080010#include "y2023/localizer/localizer.h"
milind-ud4051fe2023-02-25 18:00:05 -080011
Austin Schuh99f7c6a2024-06-25 22:07:44 -070012ABSL_FLAG(std::string, config, "aos_config.json",
13 "Path to the config file to use.");
milind-ud4051fe2023-02-25 18:00:05 -080014
Austin Schuh99f7c6a2024-06-25 22:07:44 -070015ABSL_FLAG(uint64_t, min_april_id, 1,
16 "Minimum april id to consider as part of the field and ignore");
17ABSL_FLAG(uint64_t, max_april_id, 8,
18 "Maximum april id to consider as part of the field and ignore");
milind-ud4051fe2023-02-25 18:00:05 -080019
20// This binary allows us to place extra april tags on the field and verify
21// that we can compute their field pose correctly
22
23namespace y2023::vision {
24
25using localizer::Localizer;
26
27Localizer::Transform LocalizerOutputToTransform(
28 const frc971::controls::LocalizerOutput &localizer) {
29 const auto T_field_robot =
30 Eigen::Translation3d(localizer.x(), localizer.y(), 0.0);
31
32 Eigen::AngleAxisd robot_yaw_angle(localizer.theta(),
33 Eigen::Vector3d::UnitZ());
34 const auto R_field_robot = Eigen::Quaterniond(robot_yaw_angle);
35 const Localizer::Transform H_field_robot =
36 (T_field_robot * R_field_robot).matrix();
37 return H_field_robot;
38}
39
40void HandleDetections(
41 const frc971::vision::TargetMap &detections,
42 const Localizer::Transform &H_robot_camera,
43 aos::Fetcher<frc971::controls::LocalizerOutput> *localizer_fetcher) {
44 localizer_fetcher->Fetch();
45 CHECK(localizer_fetcher->get());
46
47 for (const auto *target_pose : *detections.target_poses()) {
48 // Only look at april tags not part of the field
Austin Schuh99f7c6a2024-06-25 22:07:44 -070049 if (target_pose->id() >= absl::GetFlag(FLAGS_min_april_id) &&
50 target_pose->id() <= absl::GetFlag(FLAGS_max_april_id)) {
milind-ud4051fe2023-02-25 18:00:05 -080051 continue;
52 }
53
54 const Localizer::Transform H_camera_target =
James Kuszmaul9c3db182024-02-09 22:02:18 -080055 frc971::vision::PoseToTransform(target_pose);
milind-ud4051fe2023-02-25 18:00:05 -080056 const Localizer::Transform H_field_robot =
57 LocalizerOutputToTransform(*localizer_fetcher->get());
58
59 // Get the field-based target pose using the detection, extrinsics, and
60 // localizer output
61 const Localizer::Transform H_field_target =
62 H_field_robot * H_robot_camera * H_camera_target;
63
64 LOG(INFO) << "Field to target " << target_pose->id();
James Kuszmaul549bd362023-03-04 20:47:54 -080065 LOG(INFO) << "H_field_robot " << H_field_robot;
66 LOG(INFO) << "H_robot_camera " << H_robot_camera;
67 LOG(INFO) << "H_camera_target " << H_camera_target;
milind-ud4051fe2023-02-25 18:00:05 -080068 LOG(INFO) << "Transform: " << H_field_target;
69 LOG(INFO) << "Translation: "
70 << Eigen::Affine3d(H_field_target).translation();
71 LOG(INFO);
72 }
73}
74
75void LocalizationVerifierMain() {
76 aos::FlatbufferDetachedBuffer<aos::Configuration> config =
Austin Schuh99f7c6a2024-06-25 22:07:44 -070077 aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
milind-ud4051fe2023-02-25 18:00:05 -080078
79 frc971::constants::WaitForConstants<Constants>(&config.message());
80
81 aos::ShmEventLoop event_loop(&config.message());
82
83 frc971::constants::ConstantsFetcher<Constants> constants_fetcher(&event_loop);
84
85 aos::Fetcher<frc971::controls::LocalizerOutput> localizer_fetcher =
86 event_loop.MakeFetcher<frc971::controls::LocalizerOutput>("/localizer");
87
88 for (const auto *camera : *constants_fetcher.constants().cameras()) {
89 CHECK(camera->has_calibration());
90 Localizer::Transform H_robot_camera =
91 frc971::control_loops::drivetrain::FlatbufferToTransformationMatrix(
92 *camera->calibration()->fixed_extrinsics());
93
94 const std::string_view pi_name =
95 camera->calibration()->node_name()->string_view();
Philipp Schrader790cb542023-07-05 21:06:52 -070096 event_loop.MakeWatcher(
97 absl::StrCat("/", pi_name, "/camera"),
98 [H_robot_camera,
99 &localizer_fetcher](const frc971::vision::TargetMap &target_map) {
100 HandleDetections(target_map, H_robot_camera, &localizer_fetcher);
101 });
milind-ud4051fe2023-02-25 18:00:05 -0800102 }
James Kuszmauldc41ea12023-03-04 20:05:08 -0800103 event_loop.Run();
milind-ud4051fe2023-02-25 18:00:05 -0800104}
105
106} // namespace y2023::vision
107
108int main(int argc, char **argv) {
109 aos::InitGoogle(&argc, &argv);
110 y2023::vision::LocalizationVerifierMain();
111}