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