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