Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 1 | #include "frc971/vision/extrinsics_calibration.h" |
| 2 | |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 3 | #include "Eigen/Dense" |
| 4 | #include "Eigen/Geometry" |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 5 | #include "absl/strings/str_format.h" |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame] | 6 | |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 7 | #include "aos/events/logging/log_reader.h" |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 8 | #include "aos/init.h" |
| 9 | #include "aos/network/team_number.h" |
| 10 | #include "aos/time/time.h" |
| 11 | #include "aos/util/file.h" |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 12 | #include "frc971/control_loops/quaternion_utils.h" |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 13 | #include "frc971/vision/charuco_lib.h" |
Jim Ostrowski | 977850f | 2022-01-22 21:04:22 -0800 | [diff] [blame] | 14 | #include "frc971/vision/vision_generated.h" |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 15 | #include "frc971/wpilib/imu_batch_generated.h" |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 16 | #include "y2020/control_loops/superstructure/superstructure_status_generated.h" |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 17 | |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 18 | DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate."); |
milind-u | 0084be6 | 2021-12-27 12:29:38 +0530 | [diff] [blame] | 19 | DEFINE_bool(plot, false, "Whether to plot the resulting data."); |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 20 | DEFINE_bool(turret, false, "If true, the camera is on the turret"); |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 21 | DEFINE_string(base_intrinsics, "", |
| 22 | "Intrinsics to use for extrinsics calibration."); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 23 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 24 | namespace frc971::vision { |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 25 | namespace chrono = std::chrono; |
| 26 | using aos::distributed_clock; |
| 27 | using aos::monotonic_clock; |
| 28 | |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 29 | void Main(int argc, char **argv) { |
| 30 | CalibrationData data; |
| 31 | |
| 32 | { |
| 33 | // Now, accumulate all the data into the data object. |
| 34 | aos::logger::LogReader reader( |
| 35 | aos::logger::SortParts(aos::logger::FindLogs(argc, argv))); |
| 36 | |
| 37 | aos::SimulatedEventLoopFactory factory(reader.configuration()); |
| 38 | reader.Register(&factory); |
| 39 | |
| 40 | CHECK(aos::configuration::MultiNode(reader.configuration())); |
| 41 | |
| 42 | // Find the nodes we care about. |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 43 | const aos::Node *const imu_node = |
| 44 | aos::configuration::GetNode(factory.configuration(), "imu"); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 45 | const aos::Node *const roborio_node = |
| 46 | aos::configuration::GetNode(factory.configuration(), "roborio"); |
| 47 | |
Jim Ostrowski | cb8b408 | 2024-01-21 02:23:46 -0800 | [diff] [blame^] | 48 | std::optional<uint16_t> pi_number = |
| 49 | aos::network::ParsePiOrOrinNumber(FLAGS_pi); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 50 | CHECK(pi_number); |
| 51 | LOG(INFO) << "Pi " << *pi_number; |
| 52 | const aos::Node *const pi_node = aos::configuration::GetNode( |
| 53 | factory.configuration(), absl::StrCat("pi", *pi_number)); |
| 54 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 55 | LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 56 | LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node); |
| 57 | LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node); |
| 58 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 59 | std::unique_ptr<aos::EventLoop> imu_event_loop = |
| 60 | factory.MakeEventLoop("calibration", imu_node); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 61 | std::unique_ptr<aos::EventLoop> roborio_event_loop = |
| 62 | factory.MakeEventLoop("calibration", roborio_node); |
| 63 | std::unique_ptr<aos::EventLoop> pi_event_loop = |
| 64 | factory.MakeEventLoop("calibration", pi_node); |
| 65 | |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 66 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics = |
| 67 | aos::JsonFileToFlatbuffer<calibration::CameraCalibration>( |
| 68 | FLAGS_base_intrinsics); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 69 | // Now, hook Calibration up to everything. |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 70 | Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(), |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 71 | FLAGS_pi, &intrinsics.message(), TargetType::kCharuco, |
| 72 | "/camera", &data); |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 73 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 74 | if (FLAGS_turret) { |
| 75 | aos::NodeEventLoopFactory *roborio_factory = |
| 76 | factory.GetNodeEventLoopFactory(roborio_node->name()->string_view()); |
| 77 | roborio_event_loop->MakeWatcher( |
| 78 | "/superstructure", |
| 79 | [roborio_factory, roborio_event_loop = roborio_event_loop.get(), |
| 80 | &data](const y2020::control_loops::superstructure::Status &status) { |
| 81 | data.AddTurret( |
| 82 | roborio_factory->ToDistributedClock( |
| 83 | roborio_event_loop->context().monotonic_event_time), |
| 84 | Eigen::Vector2d(status.turret()->position(), |
| 85 | status.turret()->velocity())); |
| 86 | }); |
| 87 | } |
| 88 | |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 89 | factory.Run(); |
| 90 | |
| 91 | reader.Deregister(); |
| 92 | } |
| 93 | |
| 94 | LOG(INFO) << "Done with event_loop running"; |
| 95 | // And now we have it, we can start processing it. |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 96 | |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 97 | const Eigen::Quaternion<double> nominal_initial_orientation( |
milind-u | e53bf55 | 2021-12-11 14:42:00 -0800 | [diff] [blame] | 98 | frc971::controls::ToQuaternionFromRotationVector( |
| 99 | Eigen::Vector3d(0.0, 0.0, M_PI))); |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 100 | const Eigen::Quaternion<double> nominal_pivot_to_camera( |
milind-u | e53bf55 | 2021-12-11 14:42:00 -0800 | [diff] [blame] | 101 | Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX())); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 102 | const Eigen::Quaternion<double> nominal_pivot_to_imu( |
| 103 | Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX())); |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 104 | const Eigen::Quaternion<double> nominal_board_to_world( |
| 105 | Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX())); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 106 | Eigen::Matrix<double, 6, 1> nominal_initial_state = |
| 107 | Eigen::Matrix<double, 6, 1>::Zero(); |
| 108 | // Set y value to -1 m (approx distance from imu to board/world |
| 109 | nominal_initial_state(1, 0) = -1.0; |
milind-u | e53bf55 | 2021-12-11 14:42:00 -0800 | [diff] [blame] | 110 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 111 | CalibrationParameters calibration_parameters; |
| 112 | calibration_parameters.initial_orientation = nominal_initial_orientation; |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 113 | calibration_parameters.pivot_to_camera = nominal_pivot_to_camera; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 114 | calibration_parameters.pivot_to_imu = nominal_pivot_to_imu; |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 115 | calibration_parameters.board_to_world = nominal_board_to_world; |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 116 | calibration_parameters.initial_state = nominal_initial_state; |
| 117 | if (data.turret_samples_size() > 0) { |
| 118 | LOG(INFO) << "Have turret, so using pivot setup"; |
| 119 | calibration_parameters.has_pivot = true; |
| 120 | } |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 121 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 122 | Solve(data, &calibration_parameters); |
| 123 | LOG(INFO) << "Nominal initial_orientation " |
| 124 | << nominal_initial_orientation.coeffs().transpose(); |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 125 | LOG(INFO) << "Nominal pivot_to_camera " |
| 126 | << nominal_pivot_to_camera.coeffs().transpose(); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 127 | LOG(INFO) << "Nominal pivot_to_camera (rot-xyz) " |
| 128 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 129 | nominal_pivot_to_camera) |
| 130 | .transpose(); |
| 131 | LOG(INFO) << "pivot_to_camera change " |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 132 | << frc971::controls::ToRotationVectorFromQuaternion( |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 133 | calibration_parameters.pivot_to_camera * |
| 134 | nominal_pivot_to_camera.inverse()) |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 135 | .transpose(); |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 136 | LOG(INFO) << "Nominal pivot_to_imu " |
| 137 | << nominal_pivot_to_imu.coeffs().transpose(); |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 138 | LOG(INFO) << "board_to_world delta " |
| 139 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 140 | calibration_parameters.board_to_world * |
| 141 | nominal_board_to_world.inverse()) |
| 142 | .transpose(); |
milind-u | e53bf55 | 2021-12-11 14:42:00 -0800 | [diff] [blame] | 143 | |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 144 | if (FLAGS_plot) { |
| 145 | Plot(data, calibration_parameters); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 146 | } |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 147 | } |
| 148 | |
Stephan Pleines | f63bde8 | 2024-01-13 15:59:33 -0800 | [diff] [blame] | 149 | } // namespace frc971::vision |
Austin Schuh | bb4aae7 | 2021-10-08 22:12:25 -0700 | [diff] [blame] | 150 | |
| 151 | int main(int argc, char **argv) { |
| 152 | aos::InitGoogle(&argc, &argv); |
| 153 | |
| 154 | frc971::vision::Main(argc, argv); |
| 155 | } |