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