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