blob: deda8c3d3023dc89f1547264a594a30756187a06 [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 Schuhbb4aae72021-10-08 22:12:25 -07005#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07006
Austin Schuhbb4aae72021-10-08 22:12:25 -07007#include "aos/events/logging/log_reader.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -07008#include "aos/init.h"
9#include "aos/network/team_number.h"
10#include "aos/time/time.h"
11#include "aos/util/file.h"
milind-u8c72d532021-12-11 15:02:42 -080012#include "frc971/control_loops/quaternion_utils.h"
Jim Ostrowskib3cab972022-12-03 15:47:00 -080013#include "frc971/vision/charuco_lib.h"
Jim Ostrowski977850f2022-01-22 21:04:22 -080014#include "frc971/vision/vision_generated.h"
milind-u8c72d532021-12-11 15:02:42 -080015#include "frc971/wpilib/imu_batch_generated.h"
Austin Schuh2895f4c2022-02-26 16:38:46 -080016#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
Austin Schuhbb4aae72021-10-08 22:12:25 -070017
Austin Schuhbb4aae72021-10-08 22:12:25 -070018DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
milind-u0084be62021-12-27 12:29:38 +053019DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Austin Schuh2895f4c2022-02-26 16:38:46 -080020DEFINE_bool(turret, false, "If true, the camera is on the turret");
James Kuszmaul7e958812023-02-11 15:34:31 -080021DEFINE_string(base_intrinsics, "",
22 "Intrinsics to use for extrinsics calibration.");
Austin Schuhbb4aae72021-10-08 22:12:25 -070023
Stephan Pleinesf63bde82024-01-13 15:59:33 -080024namespace frc971::vision {
Austin Schuhbb4aae72021-10-08 22:12:25 -070025namespace chrono = std::chrono;
26using aos::distributed_clock;
27using aos::monotonic_clock;
28
Austin Schuhbb4aae72021-10-08 22:12:25 -070029void 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 Ostrowskiba2edd12022-12-03 15:44:37 -080043 const aos::Node *const imu_node =
44 aos::configuration::GetNode(factory.configuration(), "imu");
Austin Schuhbb4aae72021-10-08 22:12:25 -070045 const aos::Node *const roborio_node =
46 aos::configuration::GetNode(factory.configuration(), "roborio");
47
48 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
49 CHECK(pi_number);
50 LOG(INFO) << "Pi " << *pi_number;
51 const aos::Node *const pi_node = aos::configuration::GetNode(
52 factory.configuration(), absl::StrCat("pi", *pi_number));
53
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080054 LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node);
Austin Schuhbb4aae72021-10-08 22:12:25 -070055 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
56 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
57
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080058 std::unique_ptr<aos::EventLoop> imu_event_loop =
59 factory.MakeEventLoop("calibration", imu_node);
Austin Schuhbb4aae72021-10-08 22:12:25 -070060 std::unique_ptr<aos::EventLoop> roborio_event_loop =
61 factory.MakeEventLoop("calibration", roborio_node);
62 std::unique_ptr<aos::EventLoop> pi_event_loop =
63 factory.MakeEventLoop("calibration", pi_node);
64
James Kuszmaul7e958812023-02-11 15:34:31 -080065 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics =
66 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
67 FLAGS_base_intrinsics);
Austin Schuhbb4aae72021-10-08 22:12:25 -070068 // Now, hook Calibration up to everything.
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080069 Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
James Kuszmaul7e958812023-02-11 15:34:31 -080070 FLAGS_pi, &intrinsics.message(), TargetType::kCharuco,
71 "/camera", &data);
Austin Schuhbb4aae72021-10-08 22:12:25 -070072
Austin Schuh2895f4c2022-02-26 16:38:46 -080073 if (FLAGS_turret) {
74 aos::NodeEventLoopFactory *roborio_factory =
75 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
76 roborio_event_loop->MakeWatcher(
77 "/superstructure",
78 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
79 &data](const y2020::control_loops::superstructure::Status &status) {
80 data.AddTurret(
81 roborio_factory->ToDistributedClock(
82 roborio_event_loop->context().monotonic_event_time),
83 Eigen::Vector2d(status.turret()->position(),
84 status.turret()->velocity()));
85 });
86 }
87
Austin Schuhbb4aae72021-10-08 22:12:25 -070088 factory.Run();
89
90 reader.Deregister();
91 }
92
93 LOG(INFO) << "Done with event_loop running";
94 // And now we have it, we can start processing it.
milind-u8c72d532021-12-11 15:02:42 -080095
Austin Schuh5b379072021-12-26 16:01:04 -080096 const Eigen::Quaternion<double> nominal_initial_orientation(
milind-ue53bf552021-12-11 14:42:00 -080097 frc971::controls::ToQuaternionFromRotationVector(
98 Eigen::Vector3d(0.0, 0.0, M_PI)));
Austin Schuh2895f4c2022-02-26 16:38:46 -080099 const Eigen::Quaternion<double> nominal_pivot_to_camera(
milind-ue53bf552021-12-11 14:42:00 -0800100 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800101 const Eigen::Quaternion<double> nominal_pivot_to_imu(
102 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX()));
Austin Schuh5b379072021-12-26 16:01:04 -0800103 const Eigen::Quaternion<double> nominal_board_to_world(
104 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800105 Eigen::Matrix<double, 6, 1> nominal_initial_state =
106 Eigen::Matrix<double, 6, 1>::Zero();
107 // Set y value to -1 m (approx distance from imu to board/world
108 nominal_initial_state(1, 0) = -1.0;
milind-ue53bf552021-12-11 14:42:00 -0800109
Austin Schuhdcb6b362022-02-25 18:06:21 -0800110 CalibrationParameters calibration_parameters;
111 calibration_parameters.initial_orientation = nominal_initial_orientation;
Austin Schuh2895f4c2022-02-26 16:38:46 -0800112 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800113 calibration_parameters.pivot_to_imu = nominal_pivot_to_imu;
Austin Schuhdcb6b362022-02-25 18:06:21 -0800114 calibration_parameters.board_to_world = nominal_board_to_world;
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800115 calibration_parameters.initial_state = nominal_initial_state;
116 if (data.turret_samples_size() > 0) {
117 LOG(INFO) << "Have turret, so using pivot setup";
118 calibration_parameters.has_pivot = true;
119 }
Austin Schuh5b379072021-12-26 16:01:04 -0800120
Austin Schuhdcb6b362022-02-25 18:06:21 -0800121 Solve(data, &calibration_parameters);
122 LOG(INFO) << "Nominal initial_orientation "
123 << nominal_initial_orientation.coeffs().transpose();
Austin Schuh2895f4c2022-02-26 16:38:46 -0800124 LOG(INFO) << "Nominal pivot_to_camera "
125 << nominal_pivot_to_camera.coeffs().transpose();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800126 LOG(INFO) << "Nominal pivot_to_camera (rot-xyz) "
127 << frc971::controls::ToRotationVectorFromQuaternion(
128 nominal_pivot_to_camera)
129 .transpose();
130 LOG(INFO) << "pivot_to_camera change "
Austin Schuhdcb6b362022-02-25 18:06:21 -0800131 << frc971::controls::ToRotationVectorFromQuaternion(
Austin Schuh2895f4c2022-02-26 16:38:46 -0800132 calibration_parameters.pivot_to_camera *
133 nominal_pivot_to_camera.inverse())
Austin Schuhdcb6b362022-02-25 18:06:21 -0800134 .transpose();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800135 LOG(INFO) << "Nominal pivot_to_imu "
136 << nominal_pivot_to_imu.coeffs().transpose();
Austin Schuhdcb6b362022-02-25 18:06:21 -0800137 LOG(INFO) << "board_to_world delta "
138 << frc971::controls::ToRotationVectorFromQuaternion(
139 calibration_parameters.board_to_world *
140 nominal_board_to_world.inverse())
141 .transpose();
milind-ue53bf552021-12-11 14:42:00 -0800142
Austin Schuhdcb6b362022-02-25 18:06:21 -0800143 if (FLAGS_plot) {
144 Plot(data, calibration_parameters);
milind-u8c72d532021-12-11 15:02:42 -0800145 }
Austin Schuhbb4aae72021-10-08 22:12:25 -0700146}
147
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800148} // namespace frc971::vision
Austin Schuhbb4aae72021-10-08 22:12:25 -0700149
150int main(int argc, char **argv) {
151 aos::InitGoogle(&argc, &argv);
152
153 frc971::vision::Main(argc, argv);
154}