Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 1 | #ifndef FRC971_VISION_CALIBRATION_ACCUMULATOR_H_ |
| 2 | #define FRC971_VISION_CALIBRATION_ACCUMULATOR_H_ |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 3 | |
| 4 | #include <vector> |
| 5 | |
| 6 | #include "Eigen/Dense" |
Philipp Schrader | 790cb54 | 2023-07-05 21:06:52 -0700 | [diff] [blame^] | 7 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 8 | #include "aos/events/simulated_event_loop.h" |
| 9 | #include "aos/time/time.h" |
| 10 | #include "frc971/control_loops/quaternion_utils.h" |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 11 | #include "frc971/vision/charuco_lib.h" |
James Kuszmaul | 77d536c | 2023-02-11 17:30:59 -0800 | [diff] [blame] | 12 | #include "frc971/vision/foxglove_image_converter_lib.h" |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 13 | #include "frc971/wpilib/imu_batch_generated.h" |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 14 | |
| 15 | namespace frc971 { |
| 16 | namespace vision { |
| 17 | |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 18 | // This class provides an interface for an application to be notified of all |
| 19 | // camera and IMU samples in order with the correct timestamps. |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 20 | class CalibrationDataObserver { |
| 21 | public: |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 22 | // Observes a camera sample at the corresponding time t, and with the |
| 23 | // corresponding rotation and translation vectors rt. |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 24 | virtual void UpdateCamera(aos::distributed_clock::time_point t, |
| 25 | std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) = 0; |
| 26 | |
Austin Schuh | 5b37907 | 2021-12-26 16:01:04 -0800 | [diff] [blame] | 27 | // Observes an IMU sample at the corresponding time t, and with the |
| 28 | // corresponding angular velocity and linear acceleration vectors wa. |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 29 | virtual void UpdateIMU(aos::distributed_clock::time_point t, |
| 30 | std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) = 0; |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 31 | |
| 32 | // Observes a turret sample at the corresponding time t, and with the |
| 33 | // corresponding state. |
| 34 | virtual void UpdateTurret(aos::distributed_clock::time_point t, |
| 35 | Eigen::Vector2d state) = 0; |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 36 | }; |
| 37 | |
| 38 | // Class to both accumulate and replay camera and IMU data in time order. |
| 39 | class CalibrationData { |
| 40 | public: |
| 41 | // Adds a camera/charuco detection to the list at the provided time. |
| 42 | // This has only been tested with a charuco board. |
| 43 | void AddCameraPose(aos::distributed_clock::time_point distributed_now, |
| 44 | Eigen::Vector3d rvec, Eigen::Vector3d tvec); |
| 45 | |
| 46 | // Adds an IMU point to the list at the provided time. |
| 47 | void AddImu(aos::distributed_clock::time_point distributed_now, |
| 48 | Eigen::Vector3d gyro, Eigen::Vector3d accel); |
| 49 | |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 50 | // Adds a turret reading (position; velocity) to the list at the provided |
| 51 | // time. |
| 52 | void AddTurret(aos::distributed_clock::time_point distributed_now, |
| 53 | Eigen::Vector2d state); |
| 54 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 55 | // Processes the data points by calling UpdateCamera and UpdateIMU in time |
| 56 | // order. |
Austin Schuh | dcb6b36 | 2022-02-25 18:06:21 -0800 | [diff] [blame] | 57 | void ReviewData(CalibrationDataObserver *observer) const; |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 58 | |
| 59 | size_t camera_samples_size() const { return rot_trans_points_.size(); } |
| 60 | |
Jim Ostrowski | ba2edd1 | 2022-12-03 15:44:37 -0800 | [diff] [blame] | 61 | size_t imu_samples_size() const { return imu_points_.size(); } |
| 62 | |
| 63 | size_t turret_samples_size() const { return turret_points_.size(); } |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 64 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 65 | private: |
| 66 | std::vector<std::pair<aos::distributed_clock::time_point, |
| 67 | std::pair<Eigen::Vector3d, Eigen::Vector3d>>> |
| 68 | imu_points_; |
| 69 | |
| 70 | // Store pose samples as timestamp, along with |
| 71 | // pair of rotation, translation vectors |
| 72 | std::vector<std::pair<aos::distributed_clock::time_point, |
| 73 | std::pair<Eigen::Vector3d, Eigen::Vector3d>>> |
| 74 | rot_trans_points_; |
Austin Schuh | 2895f4c | 2022-02-26 16:38:46 -0800 | [diff] [blame] | 75 | |
| 76 | // Turret state as a timestamp and [x, v]. |
| 77 | std::vector<std::pair<aos::distributed_clock::time_point, Eigen::Vector2d>> |
| 78 | turret_points_; |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 79 | }; |
| 80 | |
James Kuszmaul | 969e4ab | 2023-01-28 16:09:19 -0800 | [diff] [blame] | 81 | class CalibrationFoxgloveVisualizer { |
| 82 | public: |
| 83 | CalibrationFoxgloveVisualizer(aos::EventLoop *event_loop); |
| 84 | |
| 85 | static aos::FlatbufferDetachedBuffer<aos::Configuration> |
| 86 | AddVisualizationChannels(const aos::Configuration *config, |
| 87 | const aos::Node *node); |
| 88 | |
| 89 | void HandleCharuco(const aos::monotonic_clock::time_point eof, |
| 90 | std::vector<std::vector<cv::Point2f>> charuco_corners) { |
| 91 | auto builder = annotations_sender_.MakeBuilder(); |
milind-u | 7aa29e2 | 2023-02-23 20:22:01 -0800 | [diff] [blame] | 92 | builder.CheckOk(builder.Send( |
Jim Ostrowski | 5e2c5e6 | 2023-02-26 12:52:56 -0800 | [diff] [blame] | 93 | BuildAnnotations(builder.fbb(), eof, charuco_corners, |
| 94 | std::vector<double>{0.0, 1.0, 0.0, 1.0}, 2.0))); |
James Kuszmaul | 969e4ab | 2023-01-28 16:09:19 -0800 | [diff] [blame] | 95 | } |
| 96 | |
| 97 | private: |
| 98 | aos::EventLoop *event_loop_; |
| 99 | FoxgloveImageConverter image_converter_; |
| 100 | |
| 101 | aos::Sender<foxglove::ImageAnnotations> annotations_sender_; |
| 102 | }; |
| 103 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 104 | // Class to register image and IMU callbacks in AOS and route them to the |
| 105 | // corresponding CalibrationData class. |
| 106 | class Calibration { |
| 107 | public: |
| 108 | Calibration(aos::SimulatedEventLoopFactory *event_loop_factory, |
| 109 | aos::EventLoop *image_event_loop, aos::EventLoop *imu_event_loop, |
James Kuszmaul | 7e95881 | 2023-02-11 15:34:31 -0800 | [diff] [blame] | 110 | std::string_view pi, |
| 111 | const calibration::CameraCalibration *intrinsics_calibration, |
| 112 | TargetType target_type, std::string_view image_channel, |
| 113 | CalibrationData *data); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 114 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 115 | // Processes a charuco detection that is returned from charuco_lib. |
| 116 | // For a valid detection(s), it stores camera observation |
| 117 | // Also optionally displays and saves annotated images based on visualize and |
| 118 | // save_path flags, respectively |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 119 | void HandleCharuco(cv::Mat rgb_image, |
| 120 | const aos::monotonic_clock::time_point eof, |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 121 | std::vector<cv::Vec4i> /*charuco_ids*/, |
| 122 | std::vector<std::vector<cv::Point2f>> /*charuco_corners*/, |
| 123 | bool valid, std::vector<Eigen::Vector3d> rvecs_eigen, |
| 124 | std::vector<Eigen::Vector3d> tvecs_eigen); |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 125 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 126 | // Processes an IMU reading by storing for later processing |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 127 | void HandleIMU(const frc971::IMUValues *imu); |
| 128 | |
| 129 | private: |
| 130 | aos::EventLoop *image_event_loop_; |
| 131 | aos::NodeEventLoopFactory *image_factory_; |
| 132 | aos::EventLoop *imu_event_loop_; |
| 133 | aos::NodeEventLoopFactory *imu_factory_; |
| 134 | |
| 135 | CharucoExtractor charuco_extractor_; |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 136 | ImageCallback image_callback_; |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 137 | |
| 138 | CalibrationData *data_; |
| 139 | |
James Kuszmaul | 969e4ab | 2023-01-28 16:09:19 -0800 | [diff] [blame] | 140 | std::unique_ptr<aos::EventLoop> visualizer_event_loop_; |
| 141 | CalibrationFoxgloveVisualizer visualizer_; |
| 142 | |
milind-u | 8c72d53 | 2021-12-11 15:02:42 -0800 | [diff] [blame] | 143 | frc971::IMUValuesT last_value_; |
| 144 | }; |
| 145 | |
| 146 | } // namespace vision |
| 147 | } // namespace frc971 |
| 148 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 149 | #endif // FRC971_VISION_CALIBRATION_ACCUMULATOR_H_ |