Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 1 | #ifndef Y2020_VISION_CHARUCO_LIB_H_ |
| 2 | #define Y2020_VISION_CHARUCO_LIB_H_ |
| 3 | |
| 4 | #include <functional> |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 5 | #include <opencv2/aruco/charuco.hpp> |
| 6 | #include <opencv2/calib3d.hpp> |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 7 | #include <string_view> |
| 8 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 9 | #include "Eigen/Dense" |
| 10 | #include "Eigen/Geometry" |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 11 | #include "absl/types/span.h" |
| 12 | #include "aos/events/event_loop.h" |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 13 | #include "aos/network/message_bridge_server_generated.h" |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 14 | #include "y2020/vision/sift/sift_generated.h" |
| 15 | #include "y2020/vision/sift/sift_training_generated.h" |
| 16 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 17 | DECLARE_bool(visualize); |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 18 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 19 | namespace frc971 { |
| 20 | namespace vision { |
| 21 | |
| 22 | // Class to find extrinsics for a specified pi's camera using the provided |
| 23 | // training data. |
| 24 | class CameraCalibration { |
| 25 | public: |
| 26 | CameraCalibration(const absl::Span<const uint8_t> training_data_bfbs, |
| 27 | std::string_view pi); |
| 28 | |
| 29 | // Intrinsics for the located camera. |
| 30 | cv::Mat CameraIntrinsics() const; |
| 31 | Eigen::Matrix3d CameraIntrinsicsEigen() const; |
| 32 | |
| 33 | // Distortion coefficients for the located camera. |
| 34 | cv::Mat CameraDistCoeffs() const; |
| 35 | |
| 36 | private: |
| 37 | // Finds the camera specific calibration flatbuffer. |
| 38 | const sift::CameraCalibration *FindCameraCalibration( |
| 39 | const sift::TrainingData *const training_data, std::string_view pi) const; |
| 40 | |
| 41 | // Pointer to this camera's calibration parameters. |
| 42 | const sift::CameraCalibration *camera_calibration_; |
| 43 | }; |
| 44 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 45 | // Helper class to call a function with a cv::Mat and age when an image shows up |
| 46 | // on the provided channel. This hides all the conversions and wrangling needed |
| 47 | // to view the image. |
| 48 | // Can connect this with HandleImage function from CharucoExtrator for |
| 49 | // full-service callback functionality |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 50 | class ImageCallback { |
| 51 | public: |
Austin Schuh | ac402e9 | 2023-01-08 13:56:20 -0800 | [diff] [blame] | 52 | enum class Format { |
| 53 | YUYV2 = 0, |
| 54 | BGR = 1, |
| 55 | GRAYSCALE = 2, |
| 56 | }; |
milind-u | 0cb5311 | 2023-02-03 20:32:55 -0800 | [diff] [blame^] | 57 | |
| 58 | // `max_age` is the age to start dropping frames at |
| 59 | ImageCallback( |
| 60 | aos::EventLoop *event_loop, std::string_view channel, |
| 61 | std::function<void(cv::Mat, aos::monotonic_clock::time_point)> |
| 62 | &&handle_image_fn, |
| 63 | aos::monotonic_clock::duration max_age = std::chrono::milliseconds(100)); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 64 | |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 65 | void set_format(Format format) { format_ = format; } |
Austin Schuh | ac402e9 | 2023-01-08 13:56:20 -0800 | [diff] [blame] | 66 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 67 | private: |
Austin Schuh | c341986 | 2023-01-08 13:54:36 -0800 | [diff] [blame] | 68 | void DisableTracing(); |
| 69 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 70 | aos::EventLoop *event_loop_; |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 71 | aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_; |
| 72 | const aos::Node *source_node_; |
| 73 | std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_; |
Austin Schuh | c341986 | 2023-01-08 13:54:36 -0800 | [diff] [blame] | 74 | aos::TimerHandler *timer_fn_; |
| 75 | |
| 76 | bool disabling_ = false; |
| 77 | |
| 78 | aos::Ftrace ftrace_; |
Austin Schuh | ac402e9 | 2023-01-08 13:56:20 -0800 | [diff] [blame] | 79 | |
| 80 | Format format_ = Format::BGR; |
milind-u | 0cb5311 | 2023-02-03 20:32:55 -0800 | [diff] [blame^] | 81 | |
| 82 | aos::monotonic_clock::duration max_age_; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 83 | }; |
| 84 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 85 | // Types of targets that a CharucoExtractor can detect in images |
| 86 | enum class TargetType : uint8_t { |
milind-u | 09fb125 | 2023-01-28 19:21:41 -0800 | [diff] [blame] | 87 | kAruco = 0, |
| 88 | kCharuco = 1, |
| 89 | kCharucoDiamond = 2 |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 90 | }; |
| 91 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 92 | // Class which calls a callback each time an image arrives with the information |
| 93 | // extracted from it. |
| 94 | class CharucoExtractor { |
| 95 | public: |
| 96 | // The callback takes the following arguments: |
| 97 | // cv::Mat -> image with overlays drawn on it. |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 98 | // monotonic_clock::time_point -> Time on this node when this image was |
| 99 | // captured. |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 100 | // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i) |
| 101 | // NOTE: We use Vec4i since that stores the ids for the charuco diamond target |
| 102 | // std::vector<std::vector<cv::Point2f>> -> charuco_corners |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 103 | // bool -> true if rvec/tvec is valid. |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 104 | // std::vector<Eigen::Vector3d> -> rvec |
| 105 | // std::vector<Eigen::Vector3d> -> tvec |
| 106 | // NOTE: we return as a vector since all but charuco boards could have |
| 107 | // multiple targets in an image; for charuco boards, there should be just one |
| 108 | // element |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 109 | CharucoExtractor( |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 110 | aos::EventLoop *event_loop, std::string_view pi, TargetType target_type, |
| 111 | std::string_view image_channel, |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 112 | std::function<void(cv::Mat, aos::monotonic_clock::time_point, |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 113 | std::vector<cv::Vec4i>, |
| 114 | std::vector<std::vector<cv::Point2f>>, bool, |
| 115 | std::vector<Eigen::Vector3d>, |
| 116 | std::vector<Eigen::Vector3d>)> &&handle_charuco_fn); |
| 117 | |
| 118 | // Handles the image by detecting the charuco board in it. |
| 119 | void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 120 | |
| 121 | // Returns the aruco dictionary in use. |
| 122 | cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; } |
| 123 | // Returns the aruco board in use. |
| 124 | cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; } |
| 125 | |
| 126 | // Returns the camera matrix for this camera. |
| 127 | const cv::Mat camera_matrix() const { return camera_matrix_; } |
| 128 | // Returns the distortion coefficients for this camera. |
| 129 | const cv::Mat dist_coeffs() const { return dist_coeffs_; } |
| 130 | |
| 131 | private: |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 132 | // Creates the dictionary, board, and other parameters for the appropriate |
| 133 | // (ch)aruco target |
| 134 | void SetupTargetData(); |
| 135 | |
| 136 | // Draw the axes from the pose(s) on the image |
| 137 | void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs, |
| 138 | std::vector<cv::Vec3d> tvecs); |
| 139 | |
| 140 | // Helper function to convert rotation (rvecs) and translation (tvecs) vectors |
| 141 | // into Eigen vectors and store in corresponding vectors |
| 142 | void PackPoseResults(std::vector<cv::Vec3d> &rvecs, |
| 143 | std::vector<cv::Vec3d> &tvecs, |
| 144 | std::vector<Eigen::Vector3d> *rvecs_eigen, |
| 145 | std::vector<Eigen::Vector3d> *tvecs_eigen); |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 146 | |
Austin Schuh | ea7b014 | 2021-10-08 22:04:53 -0700 | [diff] [blame] | 147 | aos::EventLoop *event_loop_; |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 148 | CameraCalibration calibration_; |
| 149 | |
| 150 | cv::Ptr<cv::aruco::Dictionary> dictionary_; |
| 151 | cv::Ptr<cv::aruco::CharucoBoard> board_; |
| 152 | |
Milind Upadhyay | c6e42ee | 2022-12-27 00:02:11 -0800 | [diff] [blame] | 153 | // Type of targets to detect |
| 154 | TargetType target_type_; |
| 155 | // Channel to listen on for images |
| 156 | std::string_view image_channel_; |
| 157 | |
| 158 | // Length of a side of the target marker |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 159 | double marker_length_; |
| 160 | // Length of a side of the checkerboard squares (around the marker) |
| 161 | double square_length_; |
| 162 | |
| 163 | // Intrinsic calibration matrix |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 164 | const cv::Mat camera_matrix_; |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 165 | // Intrinsic calibration matrix as Eigen::Matrix3d |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 166 | const Eigen::Matrix3d eigen_camera_matrix_; |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 167 | // Intrinsic distortion coefficients |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 168 | const cv::Mat dist_coeffs_; |
| 169 | |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 170 | // Index number of the raspberry pi |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 171 | const std::optional<uint16_t> pi_number_; |
| 172 | |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 173 | // Function to call. |
Jim Ostrowski | b3cab97 | 2022-12-03 15:47:00 -0800 | [diff] [blame] | 174 | std::function<void( |
| 175 | cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>, |
| 176 | std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>, |
| 177 | std::vector<Eigen::Vector3d>)> |
Austin Schuh | 25837f2 | 2021-06-27 15:49:14 -0700 | [diff] [blame] | 178 | handle_charuco_; |
| 179 | }; |
| 180 | |
| 181 | } // namespace vision |
| 182 | } // namespace frc971 |
| 183 | |
| 184 | #endif // Y2020_VISION_CHARUCO_LIB_H_ |