blob: 02bad18ff0cf7af0ed920d7fcc695d00c4f4142d [file] [log] [blame]
Austin Schuh25837f22021-06-27 15:49:14 -07001#ifndef Y2020_VISION_CHARUCO_LIB_H_
2#define Y2020_VISION_CHARUCO_LIB_H_
3
4#include <functional>
Austin Schuh25837f22021-06-27 15:49:14 -07005#include <opencv2/aruco/charuco.hpp>
6#include <opencv2/calib3d.hpp>
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -08007#include <string_view>
8
Austin Schuh25837f22021-06-27 15:49:14 -07009#include "Eigen/Dense"
10#include "Eigen/Geometry"
Austin Schuh25837f22021-06-27 15:49:14 -070011#include "absl/types/span.h"
12#include "aos/events/event_loop.h"
Austin Schuhea7b0142021-10-08 22:04:53 -070013#include "aos/network/message_bridge_server_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070014#include "y2020/vision/sift/sift_generated.h"
15#include "y2020/vision/sift/sift_training_generated.h"
16
Jim Ostrowskib3cab972022-12-03 15:47:00 -080017DECLARE_bool(visualize);
Jim Ostrowskib3cab972022-12-03 15:47:00 -080018
Austin Schuh25837f22021-06-27 15:49:14 -070019namespace frc971 {
20namespace vision {
21
22// Class to find extrinsics for a specified pi's camera using the provided
23// training data.
24class 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 Ostrowskib3cab972022-12-03 15:47:00 -080045// 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 Schuh25837f22021-06-27 15:49:14 -070050class ImageCallback {
51 public:
Jim Ostrowskib3cab972022-12-03 15:47:00 -080052 ImageCallback(aos::EventLoop *event_loop, std::string_view channel,
53 std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
54 &&handle_image_fn);
Austin Schuh25837f22021-06-27 15:49:14 -070055
56 private:
57 aos::EventLoop *event_loop_;
Austin Schuhea7b0142021-10-08 22:04:53 -070058 aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_;
59 const aos::Node *source_node_;
60 std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_;
Austin Schuh25837f22021-06-27 15:49:14 -070061};
62
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080063// Types of targets that a CharucoExtractor can detect in images
64enum class TargetType : uint8_t {
65 kAprilTag = 0,
66 kAruco = 1,
67 kCharuco = 2,
68 kCharucoDiamond = 3
69};
70
Austin Schuh25837f22021-06-27 15:49:14 -070071// Class which calls a callback each time an image arrives with the information
72// extracted from it.
73class CharucoExtractor {
74 public:
75 // The callback takes the following arguments:
76 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070077 // monotonic_clock::time_point -> Time on this node when this image was
78 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080079 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
80 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
81 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -070082 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080083 // std::vector<Eigen::Vector3d> -> rvec
84 // std::vector<Eigen::Vector3d> -> tvec
85 // NOTE: we return as a vector since all but charuco boards could have
86 // multiple targets in an image; for charuco boards, there should be just one
87 // element
Austin Schuhea7b0142021-10-08 22:04:53 -070088 CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080089 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
90 std::string_view image_channel,
Austin Schuhea7b0142021-10-08 22:04:53 -070091 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080092 std::vector<cv::Vec4i>,
93 std::vector<std::vector<cv::Point2f>>, bool,
94 std::vector<Eigen::Vector3d>,
95 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn);
96
97 // Handles the image by detecting the charuco board in it.
98 void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof);
Austin Schuh25837f22021-06-27 15:49:14 -070099
100 // Returns the aruco dictionary in use.
101 cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; }
102 // Returns the aruco board in use.
103 cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; }
104
105 // Returns the camera matrix for this camera.
106 const cv::Mat camera_matrix() const { return camera_matrix_; }
107 // Returns the distortion coefficients for this camera.
108 const cv::Mat dist_coeffs() const { return dist_coeffs_; }
109
110 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800111 // Creates the dictionary, board, and other parameters for the appropriate
112 // (ch)aruco target
113 void SetupTargetData();
114
115 // Draw the axes from the pose(s) on the image
116 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
117 std::vector<cv::Vec3d> tvecs);
118
119 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
120 // into Eigen vectors and store in corresponding vectors
121 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
122 std::vector<cv::Vec3d> &tvecs,
123 std::vector<Eigen::Vector3d> *rvecs_eigen,
124 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700125
Austin Schuhea7b0142021-10-08 22:04:53 -0700126 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700127 CameraCalibration calibration_;
128
129 cv::Ptr<cv::aruco::Dictionary> dictionary_;
130 cv::Ptr<cv::aruco::CharucoBoard> board_;
131
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800132 // Type of targets to detect
133 TargetType target_type_;
134 // Channel to listen on for images
135 std::string_view image_channel_;
136
137 // Length of a side of the target marker
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800138 double marker_length_;
139 // Length of a side of the checkerboard squares (around the marker)
140 double square_length_;
141
142 // Intrinsic calibration matrix
Austin Schuh25837f22021-06-27 15:49:14 -0700143 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800144 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700145 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800146 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700147 const cv::Mat dist_coeffs_;
148
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800149 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700150 const std::optional<uint16_t> pi_number_;
151
Austin Schuh25837f22021-06-27 15:49:14 -0700152 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800153 std::function<void(
154 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
155 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
156 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700157 handle_charuco_;
158};
159
160} // namespace vision
161} // namespace frc971
162
163#endif // Y2020_VISION_CHARUCO_LIB_H_