blob: 8c00d65c80291d5085a50f6760cd2a2a5a59538a [file] [log] [blame]
James Kuszmauld6199be2023-02-11 19:56:28 -08001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07004#include <opencv2/core/eigen.hpp>
5
James Kuszmauld6199be2023-02-11 19:56:28 -08006#include "aos/events/logging/log_reader.h"
7#include "aos/events/logging/log_writer.h"
8#include "aos/init.h"
9#include "aos/network/team_number.h"
10#include "aos/time/time.h"
11#include "aos/util/file.h"
James Kuszmauld6199be2023-02-11 19:56:28 -080012#include "frc971/constants/constants_sender_lib.h"
Jim Ostrowski86203682023-02-22 19:43:10 -080013#include "frc971/control_loops/quaternion_utils.h"
James Kuszmauld6199be2023-02-11 19:56:28 -080014#include "frc971/vision/extrinsics_calibration.h"
15#include "frc971/vision/vision_generated.h"
16#include "frc971/wpilib/imu_batch_generated.h"
17#include "y2023/constants/constants_generated.h"
18#include "y2023/vision/vision_util.h"
19
Austin Schuh99f7c6a2024-06-25 22:07:44 -070020ABSL_FLAG(std::string, pi, "pi-7971-2", "Pi name to calibrate.");
21ABSL_FLAG(bool, plot, false, "Whether to plot the resulting data.");
22ABSL_FLAG(std::string, target_type, "charuco_diamond",
23 "Type of target: aruco|charuco|charuco_diamond");
24ABSL_FLAG(std::string, image_channel, "/camera",
25 "Channel to listen for images on");
26ABSL_FLAG(std::string, output_logs, "/tmp/calibration/",
27 "Output folder for visualization logs.");
28ABSL_FLAG(std::string, base_calibration, "",
29 "Intrinsics (and optionally extrinsics) to use for extrinsics "
30 "calibration.");
31ABSL_FLAG(std::string, output_calibration, "",
32 "Output json file to use for the resulting calibration "
33 "(intrinsics and extrinsics).");
James Kuszmauld6199be2023-02-11 19:56:28 -080034
Stephan Pleinesf63bde82024-01-13 15:59:33 -080035namespace frc971::vision {
James Kuszmauld6199be2023-02-11 19:56:28 -080036namespace chrono = std::chrono;
37using aos::distributed_clock;
38using aos::monotonic_clock;
39
40struct CalibrationAccumulatorState {
41 CalibrationAccumulatorState(
42 aos::SimulatedEventLoopFactory *factory, CalibrationData *data,
43 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> *intrinsics)
44 : factory(factory), data(data), intrinsics(intrinsics) {}
45 aos::SimulatedEventLoopFactory *factory;
46 CalibrationData *data;
47 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> *intrinsics;
48 std::unique_ptr<aos::EventLoop> imu_event_loop;
49 std::unique_ptr<aos::EventLoop> pi_event_loop;
50 std::unique_ptr<aos::EventLoop> logger_event_loop;
51 std::unique_ptr<aos::logger::Logger> logger;
52 std::unique_ptr<Calibration> extractor;
53 void MaybeMakeExtractor() {
54 if (imu_event_loop && pi_event_loop) {
Austin Schuh99f7c6a2024-06-25 22:07:44 -070055 TargetType target_type =
56 TargetTypeFromString(absl::GetFlag(FLAGS_target_type));
James Kuszmauld6199be2023-02-11 19:56:28 -080057 std::unique_ptr<aos::EventLoop> constants_event_loop =
58 factory->MakeEventLoop("constants_fetcher", pi_event_loop->node());
Austin Schuh99f7c6a2024-06-25 22:07:44 -070059 if (absl::GetFlag(FLAGS_base_calibration).empty()) {
Jim Ostrowski86203682023-02-22 19:43:10 -080060 frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher(
61 constants_event_loop.get());
62 *intrinsics =
63 aos::RecursiveCopyFlatBuffer(y2023::vision::FindCameraCalibration(
64 constants_fetcher.constants(),
65 pi_event_loop->node()->name()->string_view()));
66 } else {
67 *intrinsics = aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
Austin Schuh99f7c6a2024-06-25 22:07:44 -070068 absl::GetFlag(FLAGS_base_calibration));
Jim Ostrowski86203682023-02-22 19:43:10 -080069 }
James Kuszmauld6199be2023-02-11 19:56:28 -080070 extractor = std::make_unique<Calibration>(
Austin Schuh99f7c6a2024-06-25 22:07:44 -070071 factory, pi_event_loop.get(), imu_event_loop.get(),
72 absl::GetFlag(FLAGS_pi), &intrinsics->message(), target_type,
73 absl::GetFlag(FLAGS_image_channel), data);
James Kuszmauld6199be2023-02-11 19:56:28 -080074 }
75 }
76};
77
78void Main(int argc, char **argv) {
79 CalibrationData data;
Jim Ostrowskicb8b4082024-01-21 02:23:46 -080080 std::optional<uint16_t> pi_number =
Austin Schuh99f7c6a2024-06-25 22:07:44 -070081 aos::network::ParsePiOrOrinNumber(absl::GetFlag(FLAGS_pi));
James Kuszmauld6199be2023-02-11 19:56:28 -080082 CHECK(pi_number);
83 const std::string pi_name = absl::StrCat("pi", *pi_number);
84
Jim Ostrowskie9085d42023-02-23 21:14:06 -080085 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> calibration =
James Kuszmauld6199be2023-02-11 19:56:28 -080086 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>::Empty();
87 {
88 // Now, accumulate all the data into the data object.
89 aos::logger::LogReader reader(
90 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
Jim Ostrowski86203682023-02-22 19:43:10 -080091 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi1/camera");
92 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi2/camera");
93 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi3/camera");
94 reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi4/camera");
95 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi1/camera");
96 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi2/camera");
97 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi3/camera");
98 reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi4/camera");
James Kuszmauld6199be2023-02-11 19:56:28 -080099
100 aos::SimulatedEventLoopFactory factory(reader.configuration());
101 reader.RegisterWithoutStarting(&factory);
102
103 CHECK(aos::configuration::MultiNode(reader.configuration()));
104
105 // Find the nodes we care about.
106 const aos::Node *const imu_node =
107 aos::configuration::GetNode(factory.configuration(), "imu");
108
109 const aos::Node *const pi_node =
110 aos::configuration::GetNode(factory.configuration(), pi_name);
111
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800112 CalibrationAccumulatorState accumulator_state(&factory, &data,
113 &calibration);
James Kuszmauld6199be2023-02-11 19:56:28 -0800114
115 reader.OnStart(imu_node, [&accumulator_state, imu_node, &factory]() {
116 accumulator_state.imu_event_loop =
117 factory.MakeEventLoop("calibration", imu_node);
118 accumulator_state.MaybeMakeExtractor();
119 });
120
121 reader.OnStart(imu_node, [&accumulator_state, pi_node, &factory]() {
122 accumulator_state.pi_event_loop =
123 factory.MakeEventLoop("logger", pi_node);
124 accumulator_state.logger_event_loop =
125 factory.MakeEventLoop("logger", pi_node);
126 accumulator_state.logger = std::make_unique<aos::logger::Logger>(
127 accumulator_state.logger_event_loop.get());
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700128 accumulator_state.logger->StartLoggingOnRun(
129 absl::GetFlag(FLAGS_output_logs));
James Kuszmauld6199be2023-02-11 19:56:28 -0800130 accumulator_state.MaybeMakeExtractor();
131 });
132
133 factory.Run();
134
135 reader.Deregister();
136 }
137
138 LOG(INFO) << "Done with event_loop running";
139 CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data";
140 CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations";
141
142 // And now we have it, we can start processing it.
Jim Ostrowski86203682023-02-22 19:43:10 -0800143 // NOTE: For y2023, with no turret, pivot == imu
144
145 // Define the mapping that takes imu frame (with z up) to camera frame (with z
146 // pointing out)
147 const Eigen::Quaterniond R_precam_cam(
148 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()) *
149 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitZ()));
150 // Set up initial conditions for the pis that are reasonable
151 Eigen::Quaternion<double> nominal_initial_orientation(
152 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitZ()));
153 Eigen::Quaternion<double> nominal_pivot_to_camera(
154 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()) *
155 Eigen::AngleAxisd(-0.75 * M_PI, Eigen::Vector3d::UnitY()));
156 Eigen::Vector3d nominal_pivot_to_camera_translation(8.0, 8.0, 0.0);
157 Eigen::Quaternion<double> nominal_board_to_world(
James Kuszmauld6199be2023-02-11 19:56:28 -0800158 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
James Kuszmauld6199be2023-02-11 19:56:28 -0800159 Eigen::Matrix<double, 6, 1> nominal_initial_state =
160 Eigen::Matrix<double, 6, 1>::Zero();
Jim Ostrowski86203682023-02-22 19:43:10 -0800161 // Set y value to -1 m (approx distance from imu to the board/world)
162 nominal_initial_state(1, 0) = 1.0;
James Kuszmauld6199be2023-02-11 19:56:28 -0800163
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800164 // If available, pull extrinsics from the calibration file
165 const calibration::CameraCalibration *calib_msg = &calibration.message();
166 if (calib_msg->has_fixed_extrinsics()) {
167 LOG(INFO) << "Using extrinsiscs from calibration file as initial condition";
168 const cv::Mat extrinsics_cv(
169 4, 4, CV_32F,
170 const_cast<void *>(static_cast<const void *>(
171 calib_msg->fixed_extrinsics()->data()->data())));
172 CHECK_EQ(extrinsics_cv.total(),
173 calib_msg->fixed_extrinsics()->data()->size());
174 Eigen::Matrix4d ext_mat;
175 cv::cv2eigen(extrinsics_cv, ext_mat);
176 Eigen::Affine3d extrinsics(ext_mat);
177 Eigen::Affine3d H_camera_imu = extrinsics.inverse();
178 nominal_pivot_to_camera = H_camera_imu.rotation();
179 nominal_pivot_to_camera_translation = H_camera_imu.translation();
180 }
181
James Kuszmauld6199be2023-02-11 19:56:28 -0800182 CalibrationParameters calibration_parameters;
183 calibration_parameters.initial_orientation = nominal_initial_orientation;
184 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
Jim Ostrowski86203682023-02-22 19:43:10 -0800185 calibration_parameters.pivot_to_camera_translation =
186 nominal_pivot_to_camera_translation;
187 // Board to world rotation
James Kuszmauld6199be2023-02-11 19:56:28 -0800188 calibration_parameters.board_to_world = nominal_board_to_world;
Jim Ostrowski86203682023-02-22 19:43:10 -0800189 // Initial imu location (and velocity)
James Kuszmauld6199be2023-02-11 19:56:28 -0800190 calibration_parameters.initial_state = nominal_initial_state;
191 calibration_parameters.has_pivot = false;
192
Jim Ostrowski86203682023-02-22 19:43:10 -0800193 // Show the inverse of pivot_to_camera, since camera_to_pivot tells where
194 // the camera is with respect to the pivot frame
James Kuszmauld6199be2023-02-11 19:56:28 -0800195 const Eigen::Affine3d nominal_affine_pivot_to_camera =
196 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
197 nominal_pivot_to_camera;
198 const Eigen::Quaterniond nominal_camera_to_pivot_rotation(
199 nominal_affine_pivot_to_camera.inverse().rotation());
200 const Eigen::Vector3d nominal_camera_to_pivot_translation(
201 nominal_affine_pivot_to_camera.inverse().translation());
202
203 LOG(INFO) << "Initial Conditions for solver. Assumes:\n"
204 << "1) board origin is same as world, but rotated pi/2 about "
205 "x-axis, so z points out\n"
Jim Ostrowski86203682023-02-22 19:43:10 -0800206 << "2) pivot origin matches imu origin (since there's no turret)\n"
James Kuszmauld6199be2023-02-11 19:56:28 -0800207 << "3) camera is offset from pivot (depends on which camera)";
208
Jim Ostrowski86203682023-02-22 19:43:10 -0800209 LOG(INFO) << "Nominal initial_orientation of imu w.r.t. world "
210 "(angle-axis vector): "
211 << frc971::controls::ToRotationVectorFromQuaternion(
212 nominal_initial_orientation)
213 .transpose();
James Kuszmauld6199be2023-02-11 19:56:28 -0800214 LOG(INFO) << "Nominal initial_state: \n"
215 << "Position: "
216 << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n"
217 << "Velocity: "
218 << nominal_initial_state.block<3, 1>(3, 0).transpose();
Jim Ostrowski86203682023-02-22 19:43:10 -0800219 LOG(INFO) << "Nominal camera_to_pivot rotation (angle-axis vector): "
James Kuszmauld6199be2023-02-11 19:56:28 -0800220 << frc971::controls::ToRotationVectorFromQuaternion(
221 nominal_camera_to_pivot_rotation)
222 .transpose();
223 LOG(INFO) << "Nominal camera_to_pivot translation: "
224 << nominal_camera_to_pivot_translation.transpose();
225
226 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
227 solved_extrinsics = Solve(data, &calibration_parameters);
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800228 calibration.mutable_message()->clear_fixed_extrinsics();
229 calibration.mutable_message()->clear_turret_extrinsics();
James Kuszmauld6199be2023-02-11 19:56:28 -0800230 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
Jim Ostrowskie9085d42023-02-23 21:14:06 -0800231 merged_calibration = aos::MergeFlatBuffers(&calibration.message(),
James Kuszmauld6199be2023-02-11 19:56:28 -0800232 &solved_extrinsics.message());
233
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700234 if (!absl::GetFlag(FLAGS_output_calibration).empty()) {
235 aos::WriteFlatbufferToJson(absl::GetFlag(FLAGS_output_calibration),
236 merged_calibration);
Jim Ostrowski86203682023-02-22 19:43:10 -0800237 } else {
238 LOG(WARNING) << "Calibration filename not provided, so not saving it";
James Kuszmauld6199be2023-02-11 19:56:28 -0800239 }
240
241 LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:";
242 std::cout << aos::FlatbufferToJson(&merged_calibration.message())
243 << std::endl;
Jim Ostrowski86203682023-02-22 19:43:10 -0800244
James Kuszmauld6199be2023-02-11 19:56:28 -0800245 LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): "
246 << frc971::controls::ToRotationVectorFromQuaternion(
247 calibration_parameters.initial_orientation)
248 .transpose();
249 LOG(INFO)
Jim Ostrowski86203682023-02-22 19:43:10 -0800250 << "initial_state (imu): \n"
James Kuszmauld6199be2023-02-11 19:56:28 -0800251 << "Position: "
252 << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose()
253 << "\n"
254 << "Velocity: "
255 << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose();
256
257 const Eigen::Affine3d affine_pivot_to_camera =
258 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
259 calibration_parameters.pivot_to_camera;
Jim Ostrowski86203682023-02-22 19:43:10 -0800260 const Eigen::Affine3d affine_camera_to_pivot =
261 affine_pivot_to_camera.inverse();
James Kuszmauld6199be2023-02-11 19:56:28 -0800262 const Eigen::Quaterniond camera_to_pivot_rotation(
Jim Ostrowski86203682023-02-22 19:43:10 -0800263 affine_camera_to_pivot.rotation());
James Kuszmauld6199be2023-02-11 19:56:28 -0800264 const Eigen::Vector3d camera_to_pivot_translation(
Jim Ostrowski86203682023-02-22 19:43:10 -0800265 affine_camera_to_pivot.translation());
266 LOG(INFO) << "camera to pivot(imu) rotation (angle-axis vec): "
James Kuszmauld6199be2023-02-11 19:56:28 -0800267 << frc971::controls::ToRotationVectorFromQuaternion(
268 camera_to_pivot_rotation)
269 .transpose();
Jim Ostrowski86203682023-02-22 19:43:10 -0800270 LOG(INFO) << "camera to pivot(imu) translation: "
James Kuszmauld6199be2023-02-11 19:56:28 -0800271 << camera_to_pivot_translation.transpose();
272 LOG(INFO) << "board_to_world (rotation) "
273 << frc971::controls::ToRotationVectorFromQuaternion(
274 calibration_parameters.board_to_world)
275 .transpose();
276 LOG(INFO) << "accelerometer bias "
277 << calibration_parameters.accelerometer_bias.transpose();
278 LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose();
279 LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar;
280
Jim Ostrowski86203682023-02-22 19:43:10 -0800281 LOG(INFO) << "Checking delta from nominal (initial condition) to solved "
282 "values:";
283 LOG(INFO) << "nominal_pivot_to_camera rotation: "
284 << frc971::controls::ToRotationVectorFromQuaternion(
285 R_precam_cam * nominal_pivot_to_camera)
286 .transpose();
287 LOG(INFO) << "solved pivot_to_camera rotation: "
288 << frc971::controls::ToRotationVectorFromQuaternion(
289 R_precam_cam * calibration_parameters.pivot_to_camera)
290 .transpose();
291
292 LOG(INFO) << "pivot_to_camera rotation delta (zero if the IC's match the "
293 "solved value) "
James Kuszmauld6199be2023-02-11 19:56:28 -0800294 << frc971::controls::ToRotationVectorFromQuaternion(
295 calibration_parameters.pivot_to_camera *
296 nominal_pivot_to_camera.inverse())
297 .transpose();
Jim Ostrowski86203682023-02-22 19:43:10 -0800298 LOG(INFO) << "board_to_world rotation change "
James Kuszmauld6199be2023-02-11 19:56:28 -0800299 << frc971::controls::ToRotationVectorFromQuaternion(
300 calibration_parameters.board_to_world *
301 nominal_board_to_world.inverse())
302 .transpose();
303
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700304 if (absl::GetFlag(FLAGS_visualize)) {
James Kuszmauld6199be2023-02-11 19:56:28 -0800305 LOG(INFO) << "Showing visualization";
306 Visualize(data, calibration_parameters);
307 }
308
Austin Schuh99f7c6a2024-06-25 22:07:44 -0700309 if (absl::GetFlag(FLAGS_plot)) {
James Kuszmauld6199be2023-02-11 19:56:28 -0800310 Plot(data, calibration_parameters);
311 }
312} // namespace vision
313
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800314} // namespace frc971::vision
James Kuszmauld6199be2023-02-11 19:56:28 -0800315
316int main(int argc, char **argv) {
317 aos::InitGoogle(&argc, &argv);
318
319 frc971::vision::Main(argc, argv);
320}