blob: 9f503733900958b20aff050921985e4664f4798e [file] [log] [blame]
Austin Schuh2895f4c2022-02-26 16:38:46 -08001#include "frc971/vision/extrinsics_calibration.h"
2
Austin Schuhbb4aae72021-10-08 22:12:25 -07003#include "Eigen/Dense"
4#include "Eigen/Geometry"
Austin Schuh99f7c6a2024-06-25 22:07:44 -07005#include "absl/flags/flag.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07006#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07007
Austin Schuhbb4aae72021-10-08 22:12:25 -07008#include "aos/events/logging/log_reader.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07009#include "aos/init.h"
10#include "aos/network/team_number.h"
11#include "aos/time/time.h"
12#include "aos/util/file.h"
milind-u8c72d532021-12-11 15:02:42 -080013#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowskib3cab972022-12-03 15:47:00 -080014#include "frc971/vision/charuco_lib.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080015#include "frc971/vision/vision_generated.h"
milind-u8c72d532021-12-11 15:02:42 -080016#include "frc971/wpilib/imu_batch_generated.h"
Austin Schuh2895f4c2022-02-26 16:38:46 -080017#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070018
Austin Schuh99f7c6a2024-06-25 22:07:44 -070019ABSL_FLAG(std::string, pi, "pi-7971-2", "Pi name to calibrate.");
20ABSL_FLAG(bool, plot, false, "Whether to plot the resulting data.");
21ABSL_FLAG(bool, turret, false, "If true, the camera is on the turret");
22ABSL_FLAG(std::string, base_intrinsics, "",
23 "Intrinsics to use for extrinsics calibration.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070024
Stephan Pleinesf63bde82024-01-13 15:59:33 -080025namespace frc971::vision {
Austin Schuhbb4aae72021-10-08 22:12:25 -070026namespace chrono = std::chrono;
27using aos::distributed_clock;
28using aos::monotonic_clock;
29
Austin Schuhbb4aae72021-10-08 22:12:25 -070030void Main(int argc, char **argv) {
31 CalibrationData data;
32
33 {
34 // Now, accumulate all the data into the data object.
35 aos::logger::LogReader reader(
36 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
37
38 aos::SimulatedEventLoopFactory factory(reader.configuration());
39 reader.Register(&factory);
40
41 CHECK(aos::configuration::MultiNode(reader.configuration()));
42
43 // Find the nodes we care about.
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080044 const aos::Node *const imu_node =
45 aos::configuration::GetNode(factory.configuration(), "imu");
Austin Schuhbb4aae72021-10-08 22:12:25 -070046 const aos::Node *const roborio_node =
47 aos::configuration::GetNode(factory.configuration(), "roborio");
48
Jim Ostrowskicb8b4082024-01-21 02:23:46 -080049 std::optional<uint16_t> pi_number =
Austin Schuh99f7c6a2024-06-25 22:07:44 -070050 aos::network::ParsePiOrOrinNumber(absl::GetFlag(FLAGS_pi));
Austin Schuhbb4aae72021-10-08 22:12:25 -070051 CHECK(pi_number);
52 LOG(INFO) << "Pi " << *pi_number;
53 const aos::Node *const pi_node = aos::configuration::GetNode(
54 factory.configuration(), absl::StrCat("pi", *pi_number));
55
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080056 LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node);
Austin Schuhbb4aae72021-10-08 22:12:25 -070057 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
58 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
59
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080060 std::unique_ptr<aos::EventLoop> imu_event_loop =
61 factory.MakeEventLoop("calibration", imu_node);
Austin Schuhbb4aae72021-10-08 22:12:25 -070062 std::unique_ptr<aos::EventLoop> roborio_event_loop =
63 factory.MakeEventLoop("calibration", roborio_node);
64 std::unique_ptr<aos::EventLoop> pi_event_loop =
65 factory.MakeEventLoop("calibration", pi_node);
66
James Kuszmaul7e958812023-02-11 15:34:31 -080067 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics =
68 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
Austin Schuh99f7c6a2024-06-25 22:07:44 -070069 absl::GetFlag(FLAGS_base_intrinsics));
Austin Schuhbb4aae72021-10-08 22:12:25 -070070 // Now, hook Calibration up to everything.
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080071 Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
Austin Schuh99f7c6a2024-06-25 22:07:44 -070072 absl::GetFlag(FLAGS_pi), &intrinsics.message(),
73 TargetType::kCharuco, "/camera", &data);
Austin Schuhbb4aae72021-10-08 22:12:25 -070074
Austin Schuh99f7c6a2024-06-25 22:07:44 -070075 if (absl::GetFlag(FLAGS_turret)) {
Austin Schuh2895f4c2022-02-26 16:38:46 -080076 aos::NodeEventLoopFactory *roborio_factory =
77 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
78 roborio_event_loop->MakeWatcher(
79 "/superstructure",
80 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
81 &data](const y2020::control_loops::superstructure::Status &status) {
82 data.AddTurret(
83 roborio_factory->ToDistributedClock(
84 roborio_event_loop->context().monotonic_event_time),
85 Eigen::Vector2d(status.turret()->position(),
86 status.turret()->velocity()));
87 });
88 }
89
Austin Schuhbb4aae72021-10-08 22:12:25 -070090 factory.Run();
91
92 reader.Deregister();
93 }
94
95 LOG(INFO) << "Done with event_loop running";
96 // And now we have it, we can start processing it.
milind-u8c72d532021-12-11 15:02:42 -080097
Austin Schuh5b379072021-12-26 16:01:04 -080098 const Eigen::Quaternion<double> nominal_initial_orientation(
milind-ue53bf552021-12-11 14:42:00 -080099 frc971::controls::ToQuaternionFromRotationVector(
100 Eigen::Vector3d(0.0, 0.0, M_PI)));
Austin Schuh2895f4c2022-02-26 16:38:46 -0800101 const Eigen::Quaternion<double> nominal_pivot_to_camera(
milind-ue53bf552021-12-11 14:42:00 -0800102 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800103 const Eigen::Quaternion<double> nominal_pivot_to_imu(
104 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX()));
Austin Schuh5b379072021-12-26 16:01:04 -0800105 const Eigen::Quaternion<double> nominal_board_to_world(
106 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800107 Eigen::Matrix<double, 6, 1> nominal_initial_state =
108 Eigen::Matrix<double, 6, 1>::Zero();
109 // Set y value to -1 m (approx distance from imu to board/world
110 nominal_initial_state(1, 0) = -1.0;
milind-ue53bf552021-12-11 14:42:00 -0800111
Austin Schuhdcb6b362022-02-25 18:06:21 -0800112 CalibrationParameters calibration_parameters;
113 calibration_parameters.initial_orientation = nominal_initial_orientation;
Austin Schuh2895f4c2022-02-26 16:38:46 -0800114 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800115 calibration_parameters.pivot_to_imu = nominal_pivot_to_imu;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800116 calibration_parameters.board_to_world = nominal_board_to_world;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800117 calibration_parameters.initial_state = nominal_initial_state;
118 if (data.turret_samples_size() > 0) {
119 LOG(INFO) << "Have turret, so using pivot setup";
120 calibration_parameters.has_pivot = true;
121 }
Austin Schuh5b379072021-12-26 16:01:04 -0800122
Austin Schuhdcb6b362022-02-25 18:06:21 -0800123 Solve(data, &calibration_parameters);
124 LOG(INFO) << "Nominal initial_orientation "
125 << nominal_initial_orientation.coeffs().transpose();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800126 LOG(INFO) << "Nominal pivot_to_camera "
127 << nominal_pivot_to_camera.coeffs().transpose();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800128 LOG(INFO) << "Nominal pivot_to_camera (rot-xyz) "
129 << frc971::controls::ToRotationVectorFromQuaternion(
130 nominal_pivot_to_camera)
131 .transpose();
132 LOG(INFO) << "pivot_to_camera change "
Austin Schuhdcb6b362022-02-25 18:06:21 -0800133 << frc971::controls::ToRotationVectorFromQuaternion(
Austin Schuh2895f4c2022-02-26 16:38:46 -0800134 calibration_parameters.pivot_to_camera *
135 nominal_pivot_to_camera.inverse())
Austin Schuhdcb6b362022-02-25 18:06:21 -0800136 .transpose();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800137 LOG(INFO) << "Nominal pivot_to_imu "
138 << nominal_pivot_to_imu.coeffs().transpose();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800139 LOG(INFO) << "board_to_world delta "
140 << frc971::controls::ToRotationVectorFromQuaternion(
141 calibration_parameters.board_to_world *
142 nominal_board_to_world.inverse())
143 .transpose();
milind-ue53bf552021-12-11 14:42:00 -0800144
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700145 if (absl::GetFlag(FLAGS_plot)) {
Austin Schuhdcb6b362022-02-25 18:06:21 -0800146 Plot(data, calibration_parameters);
milind-u8c72d532021-12-11 15:02:42 -0800147 }
Austin Schuhbb4aae72021-10-08 22:12:25 -0700148}
149
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800150} // namespace frc971::vision
Austin Schuhbb4aae72021-10-08 22:12:25 -0700151
152int main(int argc, char **argv) {
153 aos::InitGoogle(&argc, &argv);
154
155 frc971::vision::Main(argc, argv);
156}