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