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" |
| 10 | #include "frc971/control_loops/quaternion_utils.h" |
| 11 | #include "frc971/constants/constants_sender_lib.h" |
| 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."); |
| 20 | DEFINE_string(target_type, "charuco", |
| 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()); |
| 54 | frc971::constants::ConstantsFetcher<y2023::Constants> constants_fetcher( |
| 55 | constants_event_loop.get()); |
| 56 | *intrinsics = |
| 57 | FLAGS_base_intrinsics.empty() |
| 58 | ? aos::RecursiveCopyFlatBuffer( |
| 59 | y2023::vision::FindCameraCalibration( |
| 60 | constants_fetcher.constants(), |
| 61 | pi_event_loop->node()->name()->string_view())) |
| 62 | : aos::JsonFileToFlatbuffer<calibration::CameraCalibration>( |
| 63 | FLAGS_base_intrinsics); |
| 64 | extractor = std::make_unique<Calibration>( |
| 65 | factory, pi_event_loop.get(), imu_event_loop.get(), FLAGS_pi, |
| 66 | &intrinsics->message(), target_type, FLAGS_image_channel, data); |
| 67 | } |
| 68 | } |
| 69 | }; |
| 70 | |
| 71 | void Main(int argc, char **argv) { |
| 72 | CalibrationData data; |
| 73 | std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi); |
| 74 | CHECK(pi_number); |
| 75 | const std::string pi_name = absl::StrCat("pi", *pi_number); |
| 76 | |
| 77 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> intrinsics = |
| 78 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>::Empty(); |
| 79 | { |
| 80 | // Now, accumulate all the data into the data object. |
| 81 | aos::logger::LogReader reader( |
| 82 | aos::logger::SortParts(aos::logger::FindLogs(argc, argv))); |
| 83 | |
| 84 | aos::SimulatedEventLoopFactory factory(reader.configuration()); |
| 85 | reader.RegisterWithoutStarting(&factory); |
| 86 | |
| 87 | CHECK(aos::configuration::MultiNode(reader.configuration())); |
| 88 | |
| 89 | // Find the nodes we care about. |
| 90 | const aos::Node *const imu_node = |
| 91 | aos::configuration::GetNode(factory.configuration(), "imu"); |
| 92 | |
| 93 | const aos::Node *const pi_node = |
| 94 | aos::configuration::GetNode(factory.configuration(), pi_name); |
| 95 | |
| 96 | CalibrationAccumulatorState accumulator_state(&factory, &data, &intrinsics); |
| 97 | |
| 98 | reader.OnStart(imu_node, [&accumulator_state, imu_node, &factory]() { |
| 99 | accumulator_state.imu_event_loop = |
| 100 | factory.MakeEventLoop("calibration", imu_node); |
| 101 | accumulator_state.MaybeMakeExtractor(); |
| 102 | }); |
| 103 | |
| 104 | reader.OnStart(imu_node, [&accumulator_state, pi_node, &factory]() { |
| 105 | accumulator_state.pi_event_loop = |
| 106 | factory.MakeEventLoop("logger", pi_node); |
| 107 | accumulator_state.logger_event_loop = |
| 108 | factory.MakeEventLoop("logger", pi_node); |
| 109 | accumulator_state.logger = std::make_unique<aos::logger::Logger>( |
| 110 | accumulator_state.logger_event_loop.get()); |
| 111 | accumulator_state.logger->StartLoggingOnRun(FLAGS_output_logs); |
| 112 | accumulator_state.MaybeMakeExtractor(); |
| 113 | }); |
| 114 | |
| 115 | factory.Run(); |
| 116 | |
| 117 | reader.Deregister(); |
| 118 | } |
| 119 | |
| 120 | LOG(INFO) << "Done with event_loop running"; |
| 121 | CHECK(data.imu_samples_size() > 0) << "Didn't get any IMU data"; |
| 122 | CHECK(data.camera_samples_size() > 0) << "Didn't get any camera observations"; |
| 123 | |
| 124 | // And now we have it, we can start processing it. |
| 125 | const Eigen::Quaternion<double> nominal_initial_orientation( |
| 126 | frc971::controls::ToQuaternionFromRotationVector( |
| 127 | Eigen::Vector3d(0.0, 0.0, M_PI))); |
| 128 | const Eigen::Quaternion<double> nominal_pivot_to_camera( |
| 129 | Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX())); |
| 130 | const Eigen::Quaternion<double> nominal_board_to_world( |
| 131 | Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX())); |
| 132 | Eigen::Matrix<double, 6, 1> nominal_initial_state = |
| 133 | Eigen::Matrix<double, 6, 1>::Zero(); |
| 134 | // Set x value to 0.5 m (center view on the board) |
| 135 | // nominal_initial_state(0, 0) = 0.5; |
| 136 | // Set y value to -1 m (approx distance from imu to board/world) |
| 137 | nominal_initial_state(1, 0) = -1.0; |
| 138 | |
| 139 | CalibrationParameters calibration_parameters; |
| 140 | calibration_parameters.initial_orientation = nominal_initial_orientation; |
| 141 | calibration_parameters.pivot_to_camera = nominal_pivot_to_camera; |
| 142 | calibration_parameters.board_to_world = nominal_board_to_world; |
| 143 | calibration_parameters.initial_state = nominal_initial_state; |
| 144 | calibration_parameters.has_pivot = false; |
| 145 | |
| 146 | // Show the inverse of pivot_to_camera, since camera_to_pivot tells where the |
| 147 | // camera is with respect to the pivot frame |
| 148 | const Eigen::Affine3d nominal_affine_pivot_to_camera = |
| 149 | Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) * |
| 150 | nominal_pivot_to_camera; |
| 151 | const Eigen::Quaterniond nominal_camera_to_pivot_rotation( |
| 152 | nominal_affine_pivot_to_camera.inverse().rotation()); |
| 153 | const Eigen::Vector3d nominal_camera_to_pivot_translation( |
| 154 | nominal_affine_pivot_to_camera.inverse().translation()); |
| 155 | |
| 156 | LOG(INFO) << "Initial Conditions for solver. Assumes:\n" |
| 157 | << "1) board origin is same as world, but rotated pi/2 about " |
| 158 | "x-axis, so z points out\n" |
| 159 | << "2) pivot origin matches imu origin\n" |
| 160 | << "3) camera is offset from pivot (depends on which camera)"; |
| 161 | |
| 162 | LOG(INFO) |
| 163 | << "Nominal initial_orientation of imu w.r.t. world (angle-axis vector): " |
| 164 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 165 | nominal_initial_orientation) |
| 166 | .transpose(); |
| 167 | LOG(INFO) << "Nominal initial_state: \n" |
| 168 | << "Position: " |
| 169 | << nominal_initial_state.block<3, 1>(0, 0).transpose() << "\n" |
| 170 | << "Velocity: " |
| 171 | << nominal_initial_state.block<3, 1>(3, 0).transpose(); |
| 172 | // TODO<Jim>: Might be nice to take out the rotation component that maps into |
| 173 | // camera image coordinates (with x right, y down, z forward) |
| 174 | LOG(INFO) << "Nominal camera_to_pivot (angle-axis vector): " |
| 175 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 176 | nominal_camera_to_pivot_rotation) |
| 177 | .transpose(); |
| 178 | LOG(INFO) << "Nominal camera_to_pivot translation: " |
| 179 | << nominal_camera_to_pivot_translation.transpose(); |
| 180 | |
| 181 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 182 | solved_extrinsics = Solve(data, &calibration_parameters); |
| 183 | intrinsics.mutable_message()->clear_fixed_extrinsics(); |
| 184 | intrinsics.mutable_message()->clear_turret_extrinsics(); |
| 185 | aos::FlatbufferDetachedBuffer<calibration::CameraCalibration> |
| 186 | merged_calibration = aos::MergeFlatBuffers(&intrinsics.message(), |
| 187 | &solved_extrinsics.message()); |
| 188 | |
| 189 | if (!FLAGS_output_calibration.empty()) { |
| 190 | aos::WriteFlatbufferToJson(FLAGS_output_calibration, merged_calibration); |
| 191 | } |
| 192 | |
| 193 | LOG(INFO) << "RESULTS OF CALIBRATION SOLVER:"; |
| 194 | std::cout << aos::FlatbufferToJson(&merged_calibration.message()) |
| 195 | << std::endl; |
| 196 | LOG(INFO) << "initial_orientation of imu w.r.t. world (angle-axis vector): " |
| 197 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 198 | calibration_parameters.initial_orientation) |
| 199 | .transpose(); |
| 200 | LOG(INFO) |
| 201 | << "initial_state: \n" |
| 202 | << "Position: " |
| 203 | << calibration_parameters.initial_state.block<3, 1>(0, 0).transpose() |
| 204 | << "\n" |
| 205 | << "Velocity: " |
| 206 | << calibration_parameters.initial_state.block<3, 1>(3, 0).transpose(); |
| 207 | |
| 208 | const Eigen::Affine3d affine_pivot_to_camera = |
| 209 | Eigen::Translation3d(calibration_parameters.pivot_to_camera_translation) * |
| 210 | calibration_parameters.pivot_to_camera; |
| 211 | const Eigen::Quaterniond camera_to_pivot_rotation( |
| 212 | affine_pivot_to_camera.inverse().rotation()); |
| 213 | const Eigen::Vector3d camera_to_pivot_translation( |
| 214 | affine_pivot_to_camera.inverse().translation()); |
| 215 | LOG(INFO) << "camera to pivot (angle-axis vec): " |
| 216 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 217 | camera_to_pivot_rotation) |
| 218 | .transpose(); |
| 219 | LOG(INFO) << "camera to pivot translation: " |
| 220 | << camera_to_pivot_translation.transpose(); |
| 221 | LOG(INFO) << "board_to_world (rotation) " |
| 222 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 223 | calibration_parameters.board_to_world) |
| 224 | .transpose(); |
| 225 | LOG(INFO) << "accelerometer bias " |
| 226 | << calibration_parameters.accelerometer_bias.transpose(); |
| 227 | LOG(INFO) << "gyro_bias " << calibration_parameters.gyro_bias.transpose(); |
| 228 | LOG(INFO) << "gravity " << 9.81 * calibration_parameters.gravity_scalar; |
| 229 | |
| 230 | LOG(INFO) << "pivot_to_camera change " |
| 231 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 232 | calibration_parameters.pivot_to_camera * |
| 233 | nominal_pivot_to_camera.inverse()) |
| 234 | .transpose(); |
| 235 | LOG(INFO) << "board_to_world delta " |
| 236 | << frc971::controls::ToRotationVectorFromQuaternion( |
| 237 | calibration_parameters.board_to_world * |
| 238 | nominal_board_to_world.inverse()) |
| 239 | .transpose(); |
| 240 | |
| 241 | if (FLAGS_visualize) { |
| 242 | LOG(INFO) << "Showing visualization"; |
| 243 | Visualize(data, calibration_parameters); |
| 244 | } |
| 245 | |
| 246 | if (FLAGS_plot) { |
| 247 | Plot(data, calibration_parameters); |
| 248 | } |
| 249 | } // namespace vision |
| 250 | |
| 251 | } // namespace vision |
| 252 | } // namespace frc971 |
| 253 | |
| 254 | int main(int argc, char **argv) { |
| 255 | aos::InitGoogle(&argc, &argv); |
| 256 | |
| 257 | frc971::vision::Main(argc, argv); |
| 258 | } |