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