James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 1 | #include "Eigen/Dense" |
| 2 | #include "Eigen/Geometry" |
| 3 | #include "absl/strings/str_format.h" |
| 4 | #include "aos/events/logging/log_reader.h" |
| 5 | #include "aos/events/logging/log_writer.h" |
| 6 | #include "aos/init.h" |
| 7 | #include "aos/network/team_number.h" |
| 8 | #include "aos/time/time.h" |
| 9 | #include "aos/util/file.h" |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 10 | #include "frc971/constants/constants_sender_lib.h" |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 11 | #include "frc971/control_loops/quaternion_utils.h" |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 12 | #include "frc971/vision/extrinsics_calibration.h" |
| 13 | #include "frc971/vision/vision_generated.h" |
| 14 | #include "frc971/wpilib/imu_batch_generated.h" |
| 15 | #include "y2023/constants/constants_generated.h" |
| 16 | #include "y2023/vision/vision_util.h" |
| 17 | |
| 18 | DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate."); |
| 19 | DEFINE_bool(plot, false, "Whether to plot the resulting data."); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 20 | DEFINE_string(target_type, "charuco_diamond", |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 21 | "Type of target: aruco|charuco|charuco_diamond"); |
| 22 | DEFINE_string(image_channel, "/camera", "Channel to listen for images on"); |
| 23 | DEFINE_string(output_logs, "/tmp/calibration/", |
| 24 | "Output folder for visualization logs."); |
| 25 | DEFINE_string(base_intrinsics, "", |
| 26 | "Intrinsics to use for extrinsics calibration."); |
| 27 | DEFINE_string(output_calibration, "", |
| 28 | "Output json file to use for the resulting extrinsics."); |
| 29 | |
| 30 | namespace frc971 { |
| 31 | namespace vision { |
| 32 | namespace chrono = std::chrono; |
| 33 | using aos::distributed_clock; |
| 34 | using aos::monotonic_clock; |
| 35 | |
| 36 | struct CalibrationAccumulatorState { |
| 37 | CalibrationAccumulatorState( |
| 38 | aos::SimulatedEventLoopFactory *factory, CalibrationData *data, |
| 39 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> *intrinsics) |
| 40 | : factory(factory), data(data), intrinsics(intrinsics) {} |
| 41 | aos::SimulatedEventLoopFactory *factory; |
| 42 | CalibrationData *data; |
| 43 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> *intrinsics; |
| 44 | std::unique_ptr<aos::EventLoop> imu_event_loop; |
| 45 | std::unique_ptr<aos::EventLoop> pi_event_loop; |
| 46 | std::unique_ptr<aos::EventLoop> logger_event_loop; |
| 47 | std::unique_ptr<aos::logger::Logger> logger; |
| 48 | std::unique_ptr<Calibration> extractor; |
| 49 | void MaybeMakeExtractor() { |
| 50 | if (imu_event_loop && pi_event_loop) { |
| 51 | TargetType target_type = TargetTypeFromString(FLAGS_target_type); |
| 52 | std::unique_ptr<aos::EventLoop> constants_event_loop = |
| 53 | factory->MakeEventLoop("constants_fetcher", pi_event_loop->node()); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 54 | if (FLAGS_base_intrinsics.empty()) { |
| 55 | frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher( |
| 56 | constants_event_loop.get()); |
| 57 | *intrinsics = |
| 58 | aos::RecursiveCopyFlatBuffer(y2023::vision::FindCameraCalibration( |
| 59 | constants_fetcher.constants(), |
| 60 | pi_event_loop->node()->name()->string_view())); |
| 61 | } else { |
| 62 | *intrinsics = aos::JsonFileToFlatbuffer<calibration::CameraCalibration>( |
| 63 | FLAGS_base_intrinsics); |
| 64 | } |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 65 | extractor = std::make_unique<Calibration>( |
| 66 | factory, pi_event_loop.get(), imu_event_loop.get(), FLAGS_pi, |
| 67 | &intrinsics->message(), target_type, FLAGS_image_channel, data); |
| 68 | } |
| 69 | } |
| 70 | }; |
| 71 | |
| 72 | void Main(int argc, char **argv) { |
| 73 | CalibrationData data; |
| 74 | std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi); |
| 75 | CHECK(pi_number); |
| 76 | const std::string pi_name = absl::StrCat("pi", *pi_number); |
| 77 | |
| 78 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics = |
| 79 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>::Empty(); |
| 80 | { |
| 81 | // Now, accumulate all the data into the data object. |
| 82 | aos::logger::LogReader reader( |
| 83 | aos::logger::SortParts(aos::logger::FindLogs(argc, argv))); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 84 | reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi1/camera"); |
| 85 | reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi2/camera"); |
| 86 | reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi3/camera"); |
| 87 | reader.RemapLoggedChannel<foxglove::CompressedImage>("/pi4/camera"); |
| 88 | reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi1/camera"); |
| 89 | reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi2/camera"); |
| 90 | reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi3/camera"); |
| 91 | reader.RemapLoggedChannel<foxglove::ImageAnnotations>("/pi4/camera"); |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 92 | |
| 93 | aos::SimulatedEventLoopFactory factory(reader.configuration()); |
| 94 | reader.RegisterWithoutStarting(&factory); |
| 95 | |
| 96 | CHECK(aos::configuration::MultiNode(reader.configuration())); |
| 97 | |
| 98 | // Find the nodes we care about. |
| 99 | const aos::Node *const imu_node = |
| 100 | aos::configuration::GetNode(factory.configuration(), "imu"); |
| 101 | |
| 102 | const aos::Node *const pi_node = |
| 103 | aos::configuration::GetNode(factory.configuration(), pi_name); |
| 104 | |
| 105 | CalibrationAccumulatorState accumulator_state(&factory, &data, &intrinsics); |
| 106 | |
| 107 | reader.OnStart(imu_node, [&accumulator_state, imu_node, &factory]() { |
| 108 | accumulator_state.imu_event_loop = |
| 109 | factory.MakeEventLoop("calibration", imu_node); |
| 110 | accumulator_state.MaybeMakeExtractor(); |
| 111 | }); |
| 112 | |
| 113 | reader.OnStart(imu_node, [&accumulator_state, pi_node, &factory]() { |
| 114 | accumulator_state.pi_event_loop = |
| 115 | factory.MakeEventLoop("logger", pi_node); |
| 116 | accumulator_state.logger_event_loop = |
| 117 | factory.MakeEventLoop("logger", pi_node); |
| 118 | accumulator_state.logger = std::make_unique<aos::logger::Logger>( |
| 119 | accumulator_state.logger_event_loop.get()); |
| 120 | accumulator_state.logger->StartLoggingOnRun(FLAGS_output_logs); |
| 121 | accumulator_state.MaybeMakeExtractor(); |
| 122 | }); |
| 123 | |
| 124 | factory.Run(); |
| 125 | |
| 126 | reader.Deregister(); |
| 127 | } |
| 128 | |
| 129 | LOG(INFO) << "Done with event_loop running"; |
| 130 | CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data"; |
| 131 | CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations"; |
| 132 | |
| 133 | // And now we have it, we can start processing it. |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 134 | // NOTE: For y2023, with no turret, pivot == imu |
| 135 | |
| 136 | // Define the mapping that takes imu frame (with z up) to camera frame (with z |
| 137 | // pointing out) |
| 138 | const Eigen::Quaterniond R_precam_cam( |
| 139 | Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()) * |
| 140 | Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitZ())); |
| 141 | // Set up initial conditions for the pis that are reasonable |
| 142 | Eigen::Quaternion<double> nominal_initial_orientation( |
| 143 | Eigen::AngleAxisd(0.0, Eigen::Vector3d::UnitZ())); |
| 144 | Eigen::Quaternion<double> nominal_pivot_to_camera( |
| 145 | Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()) * |
| 146 | Eigen::AngleAxisd(-0.75 * M_PI, Eigen::Vector3d::UnitY())); |
| 147 | Eigen::Vector3d nominal_pivot_to_camera_translation(8.0, 8.0, 0.0); |
| 148 | Eigen::Quaternion<double> nominal_board_to_world( |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 149 | Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX())); |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 150 | Eigen::Matrix<double, 6, 1> nominal_initial_state = |
| 151 | Eigen::Matrix<double, 6, 1>::Zero(); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 152 | // Set y value to -1 m (approx distance from imu to the board/world) |
| 153 | nominal_initial_state(1, 0) = 1.0; |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 154 | |
| 155 | CalibrationParameters calibration_parameters; |
| 156 | calibration_parameters.initial_orientation = nominal_initial_orientation; |
| 157 | calibration_parameters.pivot_to_camera = nominal_pivot_to_camera; |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 158 | calibration_parameters.pivot_to_camera_translation = |
| 159 | nominal_pivot_to_camera_translation; |
| 160 | // Board to world rotation |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 161 | calibration_parameters.board_to_world = nominal_board_to_world; |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 162 | // Initial imu location (and velocity) |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 163 | calibration_parameters.initial_state = nominal_initial_state; |
| 164 | calibration_parameters.has_pivot = false; |
| 165 | |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 166 | // Show the inverse of pivot_to_camera, since camera_to_pivot tells where |
| 167 | // the camera is with respect to the pivot frame |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 168 | const Eigen::Affine3d nominal_affine_pivot_to_camera = |
| 169 | Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) * |
| 170 | nominal_pivot_to_camera; |
| 171 | const Eigen::Quaterniond nominal_camera_to_pivot_rotation( |
| 172 | nominal_affine_pivot_to_camera.inverse().rotation()); |
| 173 | const Eigen::Vector3d nominal_camera_to_pivot_translation( |
| 174 | nominal_affine_pivot_to_camera.inverse().translation()); |
| 175 | |
| 176 | LOG(INFO) << "Initial Conditions for solver. Assumes:\n" |
| 177 | << "1) board origin is same as world, but rotated pi/2 about " |
| 178 | "x-axis, so z points out\n" |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 179 | << "2) pivot origin matches imu origin (since there's no turret)\n" |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 180 | << "3) camera is offset from pivot (depends on which camera)"; |
| 181 | |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 182 | LOG(INFO) << "Nominal initial_orientation of imu w.r.t. world " |
| 183 | "(angle-axis vector): " |
| 184 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 185 | nominal_initial_orientation) |
| 186 | .transpose(); |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 187 | LOG(INFO) << "Nominal initial_state: \n" |
| 188 | << "Position: " |
| 189 | << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n" |
| 190 | << "Velocity: " |
| 191 | << nominal_initial_state.block<3, 1>(3, 0).transpose(); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 192 | LOG(INFO) << "Nominal camera_to_pivot rotation (angle-axis vector): " |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 193 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 194 | nominal_camera_to_pivot_rotation) |
| 195 | .transpose(); |
| 196 | LOG(INFO) << "Nominal camera_to_pivot translation: " |
| 197 | << nominal_camera_to_pivot_translation.transpose(); |
| 198 | |
| 199 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 200 | solved_extrinsics = Solve(data, &calibration_parameters); |
| 201 | intrinsics.mutable_message()->clear_fixed_extrinsics(); |
| 202 | intrinsics.mutable_message()->clear_turret_extrinsics(); |
| 203 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 204 | merged_calibration = aos::MergeFlatBuffers(&intrinsics.message(), |
| 205 | &solved_extrinsics.message()); |
| 206 | |
| 207 | if (!FLAGS_output_calibration.empty()) { |
| 208 | aos::WriteFlatbufferToJson(FLAGS_output_calibration, merged_calibration); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 209 | } else { |
| 210 | LOG(WARNING) << "Calibration filename not provided, so not saving it"; |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 211 | } |
| 212 | |
| 213 | LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:"; |
| 214 | std::cout << aos::FlatbufferToJson(&merged_calibration.message()) |
| 215 | << std::endl; |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 216 | |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 217 | LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): " |
| 218 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 219 | calibration_parameters.initial_orientation) |
| 220 | .transpose(); |
| 221 | LOG(INFO) |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 222 | << "initial_state (imu): \n" |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 223 | << "Position: " |
| 224 | << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose() |
| 225 | << "\n" |
| 226 | << "Velocity: " |
| 227 | << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose(); |
| 228 | |
| 229 | const Eigen::Affine3d affine_pivot_to_camera = |
| 230 | Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) * |
| 231 | calibration_parameters.pivot_to_camera; |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 232 | const Eigen::Affine3d affine_camera_to_pivot = |
| 233 | affine_pivot_to_camera.inverse(); |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 234 | const Eigen::Quaterniond camera_to_pivot_rotation( |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 235 | affine_camera_to_pivot.rotation()); |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 236 | const Eigen::Vector3d camera_to_pivot_translation( |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 237 | affine_camera_to_pivot.translation()); |
| 238 | LOG(INFO) << "camera to pivot(imu) rotation (angle-axis vec): " |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 239 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 240 | camera_to_pivot_rotation) |
| 241 | .transpose(); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 242 | LOG(INFO) << "camera to pivot(imu) translation: " |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 243 | << camera_to_pivot_translation.transpose(); |
| 244 | LOG(INFO) << "board_to_world (rotation) " |
| 245 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 246 | calibration_parameters.board_to_world) |
| 247 | .transpose(); |
| 248 | LOG(INFO) << "accelerometer bias " |
| 249 | << calibration_parameters.accelerometer_bias.transpose(); |
| 250 | LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose(); |
| 251 | LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar; |
| 252 | |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 253 | LOG(INFO) << "Checking delta from nominal (initial condition) to solved " |
| 254 | "values:"; |
| 255 | LOG(INFO) << "nominal_pivot_to_camera rotation: " |
| 256 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 257 | R_precam_cam * nominal_pivot_to_camera) |
| 258 | .transpose(); |
| 259 | LOG(INFO) << "solved pivot_to_camera rotation: " |
| 260 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 261 | R_precam_cam * calibration_parameters.pivot_to_camera) |
| 262 | .transpose(); |
| 263 | |
| 264 | LOG(INFO) << "pivot_to_camera rotation delta (zero if the IC's match the " |
| 265 | "solved value) " |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 266 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 267 | calibration_parameters.pivot_to_camera * |
| 268 | nominal_pivot_to_camera.inverse()) |
| 269 | .transpose(); |
Jim Ostrowski | 8620368 | 2023-02-22 19:43:10 -0800 | [diff] [blame^] | 270 | LOG(INFO) << "board_to_world rotation change " |
James Kuszmaul | d6199be | 2023-02-11 19:56:28 -0800 | [diff] [blame] | 271 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 272 | calibration_parameters.board_to_world * |
| 273 | nominal_board_to_world.inverse()) |
| 274 | .transpose(); |
| 275 | |
| 276 | if (FLAGS_visualize) { |
| 277 | LOG(INFO) << "Showing visualization"; |
| 278 | Visualize(data, calibration_parameters); |
| 279 | } |
| 280 | |
| 281 | if (FLAGS_plot) { |
| 282 | Plot(data, calibration_parameters); |
| 283 | } |
| 284 | } // namespace vision |
| 285 | |
| 286 | } // namespace vision |
| 287 | } // namespace frc971 |
| 288 | |
| 289 | int main(int argc, char **argv) { |
| 290 | aos::InitGoogle(&argc, &argv); |
| 291 | |
| 292 | frc971::vision::Main(argc, argv); |
| 293 | } |