blob: 0a950ab4663c4145561af0bd4b83871d1d44f3a8 [file] [log] [blame]
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08001#include "Eigen/Dense"
2#include "Eigen/Geometry"
3#include "absl/strings/str_format.h"
Philipp Schrader790cb542023-07-05 21:06:52 -07004
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08005#include "aos/events/logging/log_reader.h"
James Kuszmaul969e4ab2023-01-28 16:09:19 -08006#include "aos/events/logging/log_writer.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -08007#include "aos/init.h"
8#include "aos/network/team_number.h"
9#include "aos/time/time.h"
10#include "aos/util/file.h"
11#include "frc971/control_loops/quaternion_utils.h"
12#include "frc971/vision/extrinsics_calibration.h"
13#include "frc971/vision/vision_generated.h"
14#include "frc971/wpilib/imu_batch_generated.h"
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080015#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
16
17DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
18DEFINE_bool(plot, false, "Whether to plot the resulting data.");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080019DEFINE_bool(turret, true, "If true, the camera is on the turret");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080020DEFINE_string(target_type, "charuco",
milind-u09fb1252023-01-28 19:21:41 -080021 "Type of target: aruco|charuco|charuco_diamond");
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080022DEFINE_string(image_channel, "/camera", "Channel to listen for images on");
James Kuszmaul969e4ab2023-01-28 16:09:19 -080023DEFINE_string(output_logs, "/tmp/calibration/",
24 "Output folder for visualization logs.");
James Kuszmaul7e958812023-02-11 15:34:31 -080025DEFINE_string(base_intrinsics, "",
26 "Intrinsics to use for extrinsics calibration.");
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080027
Stephan Pleinesf63bde82024-01-13 15:59:33 -080028namespace frc971::vision {
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080029namespace chrono = std::chrono;
30using aos::distributed_clock;
31using aos::monotonic_clock;
32
33// TODO(austin): Source of IMU data? Is it the same?
34// TODO(austin): Intrinsics data?
35
36void Main(int argc, char **argv) {
37 CalibrationData data;
James Kuszmaul969e4ab2023-01-28 16:09:19 -080038 std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
39 CHECK(pi_number);
40 const std::string pi_name = absl::StrCat("pi", *pi_number);
41 LOG(INFO) << "Pi " << *pi_number;
42 aos::FlatbufferDetachedBuffer<aos::Configuration> config = [argc, argv,
43 pi_name]() {
44 aos::logger::LogReader reader(
45 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
46 return CalibrationFoxgloveVisualizer::AddVisualizationChannels(
47 reader.logged_configuration(),
48 aos::configuration::GetNode(reader.logged_configuration(), pi_name));
49 }();
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080050
51 {
52 // Now, accumulate all the data into the data object.
53 aos::logger::LogReader reader(
James Kuszmaul969e4ab2023-01-28 16:09:19 -080054 aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
55 &config.message());
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080056
57 aos::SimulatedEventLoopFactory factory(reader.configuration());
58 reader.Register(&factory);
59
60 CHECK(aos::configuration::MultiNode(reader.configuration()));
61
62 // Find the nodes we care about.
63 const aos::Node *const imu_node =
64 aos::configuration::GetNode(factory.configuration(), "imu");
65 const aos::Node *const roborio_node =
66 aos::configuration::GetNode(factory.configuration(), "roborio");
67
James Kuszmaul969e4ab2023-01-28 16:09:19 -080068 const aos::Node *const pi_node =
69 aos::configuration::GetNode(factory.configuration(), pi_name);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -080070
71 LOG(INFO) << "imu " << aos::FlatbufferToJson(imu_node);
72 LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
73 LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
74
75 std::unique_ptr<aos::EventLoop> imu_event_loop =
76 factory.MakeEventLoop("calibration", imu_node);
77 std::unique_ptr<aos::EventLoop> roborio_event_loop =
78 factory.MakeEventLoop("calibration", roborio_node);
79 std::unique_ptr<aos::EventLoop> pi_event_loop =
80 factory.MakeEventLoop("calibration", pi_node);
81
James Kuszmaul969e4ab2023-01-28 16:09:19 -080082 std::unique_ptr<aos::EventLoop> logger_loop =
83 factory.MakeEventLoop("logger", pi_node);
84 aos::logger::Logger logger(logger_loop.get());
85 logger.StartLoggingOnRun(FLAGS_output_logs);
86
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080087 TargetType target_type = TargetType::kCharuco;
milind-u09fb1252023-01-28 19:21:41 -080088 if (FLAGS_target_type == "aruco") {
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080089 target_type = TargetType::kAruco;
90 } else if (FLAGS_target_type == "charuco") {
91 target_type = TargetType::kCharuco;
92 } else if (FLAGS_target_type == "charuco_diamond") {
93 target_type = TargetType::kCharucoDiamond;
94 } else {
95 LOG(FATAL) << "Unknown target type: " << FLAGS_target_type
milind-u09fb1252023-01-28 19:21:41 -080096 << ", expected: aruco|charuco|charuco_diamond";
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080097 }
98
James Kuszmaul7e958812023-02-11 15:34:31 -080099 aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics =
100 aos::JsonFileToFlatbuffer<calibration::CameraCalibration>(
101 FLAGS_base_intrinsics);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800102 // Now, hook Calibration up to everything.
103 Calibration extractor(&factory, pi_event_loop.get(), imu_event_loop.get(),
James Kuszmaul7e958812023-02-11 15:34:31 -0800104 FLAGS_pi, &intrinsics.message(), target_type,
105 FLAGS_image_channel, &data);
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800106
107 if (FLAGS_turret) {
108 aos::NodeEventLoopFactory *roborio_factory =
109 factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
110 roborio_event_loop->MakeWatcher(
111 "/superstructure",
112 [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
113 &data](const y2022::control_loops::superstructure::Status &status) {
114 data.AddTurret(
115 roborio_factory->ToDistributedClock(
116 roborio_event_loop->context().monotonic_event_time),
117 Eigen::Vector2d(status.turret()->position(),
118 status.turret()->velocity()));
119 });
120 }
121
122 factory.Run();
123
124 reader.Deregister();
125 }
126
127 LOG(INFO) << "Done with event_loop running";
128 CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data";
129 CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations";
130
131 // And now we have it, we can start processing it.
132 const Eigen::Quaternion<double> nominal_initial_orientation(
133 frc971::controls::ToQuaternionFromRotationVector(
134 Eigen::Vector3d(0.0, 0.0, M_PI)));
135 const Eigen::Quaternion<double> nominal_pivot_to_camera(
136 Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
137 const Eigen::Quaternion<double> nominal_pivot_to_imu(
138 Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitX()));
139 const Eigen::Quaternion<double> nominal_board_to_world(
140 Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
141 Eigen::Matrix<double, 6, 1> nominal_initial_state =
142 Eigen::Matrix<double, 6, 1>::Zero();
143 // Set x value to 0.5 m (center view on the board)
144 // nominal_initial_state(0, 0) = 0.5;
145 // Set y value to -1 m (approx distance from imu to board/world)
146 nominal_initial_state(1, 0) = -1.0;
147
148 CalibrationParameters calibration_parameters;
149 calibration_parameters.initial_orientation = nominal_initial_orientation;
150 calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
151 calibration_parameters.pivot_to_imu = nominal_pivot_to_imu;
152 calibration_parameters.board_to_world = nominal_board_to_world;
153 calibration_parameters.initial_state = nominal_initial_state;
154
155 // Show the inverse of pivot_to_camera, since camera_to_pivot tells where the
156 // camera is with respect to the pivot frame
157 const Eigen::Affine3d nominal_affine_pivot_to_camera =
158 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
159 nominal_pivot_to_camera;
160 const Eigen::Quaterniond nominal_camera_to_pivot_rotation(
161 nominal_affine_pivot_to_camera.inverse().rotation());
162 const Eigen::Vector3d nominal_camera_to_pivot_translation(
163 nominal_affine_pivot_to_camera.inverse().translation());
164
165 if (data.turret_samples_size() > 0) {
166 LOG(INFO) << "Have turret, so using pivot setup";
167 calibration_parameters.has_pivot = true;
168 }
169
170 LOG(INFO) << "Initial Conditions for solver. Assumes:\n"
171 << "1) board origin is same as world, but rotated pi/2 about "
172 "x-axis, so z points out\n"
173 << "2) pivot origin matches imu origin\n"
174 << "3) camera is offset from pivot (depends on which camera)";
175
176 LOG(INFO)
177 << "Nominal initial_orientation of imu w.r.t. world (angle-axis vector): "
178 << frc971::controls::ToRotationVectorFromQuaternion(
179 nominal_initial_orientation)
180 .transpose();
181 LOG(INFO) << "Nominal initial_state: \n"
182 << "Position: "
183 << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n"
184 << "Velocity: "
185 << nominal_initial_state.block<3, 1>(3, 0).transpose();
186 LOG(INFO) << "Nominal pivot_to_imu (angle-axis vector) "
187 << frc971::controls::ToRotationVectorFromQuaternion(
188 calibration_parameters.pivot_to_imu)
189 .transpose();
190 LOG(INFO) << "Nominal pivot_to_imu translation: "
191 << calibration_parameters.pivot_to_imu_translation.transpose();
192 // TODO<Jim>: Might be nice to take out the rotation component that maps into
193 // camera image coordinates (with x right, y down, z forward)
194 LOG(INFO) << "Nominal camera_to_pivot (angle-axis vector): "
195 << frc971::controls::ToRotationVectorFromQuaternion(
196 nominal_camera_to_pivot_rotation)
197 .transpose();
198 LOG(INFO) << "Nominal camera_to_pivot translation: "
199 << nominal_camera_to_pivot_translation.transpose();
200
201 Solve(data, &calibration_parameters);
202
203 LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:";
204 LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): "
205 << frc971::controls::ToRotationVectorFromQuaternion(
206 calibration_parameters.initial_orientation)
207 .transpose();
208 LOG(INFO)
209 << "initial_state: \n"
210 << "Position: "
211 << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose()
212 << "\n"
213 << "Velocity: "
214 << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose();
215
216 LOG(INFO) << "pivot_to_imu rotation (angle-axis vec) "
217 << frc971::controls::ToRotationVectorFromQuaternion(
218 calibration_parameters.pivot_to_imu)
219 .transpose();
220 LOG(INFO) << "pivot_to_imu_translation "
221 << calibration_parameters.pivot_to_imu_translation.transpose();
222 const Eigen::Affine3d affine_pivot_to_camera =
223 Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) *
224 calibration_parameters.pivot_to_camera;
225 const Eigen::Quaterniond camera_to_pivot_rotation(
226 affine_pivot_to_camera.inverse().rotation());
227 const Eigen::Vector3d camera_to_pivot_translation(
228 affine_pivot_to_camera.inverse().translation());
229 LOG(INFO) << "camera to pivot (angle-axis vec): "
230 << frc971::controls::ToRotationVectorFromQuaternion(
231 camera_to_pivot_rotation)
232 .transpose();
233 LOG(INFO) << "camera to pivot translation: "
234 << camera_to_pivot_translation.transpose();
235 LOG(INFO) << "board_to_world (rotation) "
236 << frc971::controls::ToRotationVectorFromQuaternion(
237 calibration_parameters.board_to_world)
238 .transpose();
239 LOG(INFO) << "accelerometer bias "
240 << calibration_parameters.accelerometer_bias.transpose();
241 LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose();
242 LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar;
243
244 LOG(INFO) << "pivot_to_camera change "
245 << frc971::controls::ToRotationVectorFromQuaternion(
246 calibration_parameters.pivot_to_camera *
247 nominal_pivot_to_camera.inverse())
248 .transpose();
249 LOG(INFO) << "board_to_world delta "
250 << frc971::controls::ToRotationVectorFromQuaternion(
251 calibration_parameters.board_to_world *
252 nominal_board_to_world.inverse())
253 .transpose();
254
255 if (FLAGS_visualize) {
256 LOG(INFO) << "Showing visualization";
257 Visualize(data, calibration_parameters);
258 }
259
260 if (FLAGS_plot) {
261 Plot(data, calibration_parameters);
262 }
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800263} // namespace vision
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800264
Stephan Pleinesf63bde82024-01-13 15:59:33 -0800265} // namespace frc971::vision
Jim Ostrowskiba2edd12022-12-03 15:44:37 -0800266
267int main(int argc, char **argv) {
268 aos::InitGoogle(&argc, &argv);
269
270 frc971::vision::Main(argc, argv);
271}