blob: c7269f97dbd317851cb320afe01353b411c1cd2a [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:
Austin Schuhac402e92023-01-08 13:56:20 -080052 enum class Format {
53 YUYV2 = 0,
54 BGR = 1,
55 GRAYSCALE = 2,
56 };
Jim Ostrowskib3cab972022-12-03 15:47:00 -080057 ImageCallback(aos::EventLoop *event_loop, std::string_view channel,
58 std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
59 &&handle_image_fn);
Austin Schuh25837f22021-06-27 15:49:14 -070060
Austin Schuhac402e92023-01-08 13:56:20 -080061 void set_format(Format format) {
62 format_ = format;
63 }
64
Austin Schuh25837f22021-06-27 15:49:14 -070065 private:
Austin Schuhc3419862023-01-08 13:54:36 -080066 void DisableTracing();
67
Austin Schuh25837f22021-06-27 15:49:14 -070068 aos::EventLoop *event_loop_;
Austin Schuhea7b0142021-10-08 22:04:53 -070069 aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_;
70 const aos::Node *source_node_;
71 std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_;
Austin Schuhc3419862023-01-08 13:54:36 -080072 aos::TimerHandler *timer_fn_;
73
74 bool disabling_ = false;
75
76 aos::Ftrace ftrace_;
Austin Schuhac402e92023-01-08 13:56:20 -080077
78 Format format_ = Format::BGR;
Austin Schuh25837f22021-06-27 15:49:14 -070079};
80
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080081// Types of targets that a CharucoExtractor can detect in images
82enum class TargetType : uint8_t {
83 kAprilTag = 0,
84 kAruco = 1,
85 kCharuco = 2,
86 kCharucoDiamond = 3
87};
88
Austin Schuh25837f22021-06-27 15:49:14 -070089// Class which calls a callback each time an image arrives with the information
90// extracted from it.
91class CharucoExtractor {
92 public:
93 // The callback takes the following arguments:
94 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070095 // monotonic_clock::time_point -> Time on this node when this image was
96 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080097 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
98 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
99 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -0700100 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800101 // std::vector<Eigen::Vector3d> -> rvec
102 // std::vector<Eigen::Vector3d> -> tvec
103 // NOTE: we return as a vector since all but charuco boards could have
104 // multiple targets in an image; for charuco boards, there should be just one
105 // element
Austin Schuhea7b0142021-10-08 22:04:53 -0700106 CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800107 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
108 std::string_view image_channel,
Austin Schuhea7b0142021-10-08 22:04:53 -0700109 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800110 std::vector<cv::Vec4i>,
111 std::vector<std::vector<cv::Point2f>>, bool,
112 std::vector<Eigen::Vector3d>,
113 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn);
114
115 // Handles the image by detecting the charuco board in it.
116 void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700117
118 // Returns the aruco dictionary in use.
119 cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; }
120 // Returns the aruco board in use.
121 cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; }
122
123 // Returns the camera matrix for this camera.
124 const cv::Mat camera_matrix() const { return camera_matrix_; }
125 // Returns the distortion coefficients for this camera.
126 const cv::Mat dist_coeffs() const { return dist_coeffs_; }
127
128 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800129 // Creates the dictionary, board, and other parameters for the appropriate
130 // (ch)aruco target
131 void SetupTargetData();
132
133 // Draw the axes from the pose(s) on the image
134 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
135 std::vector<cv::Vec3d> tvecs);
136
137 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
138 // into Eigen vectors and store in corresponding vectors
139 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
140 std::vector<cv::Vec3d> &tvecs,
141 std::vector<Eigen::Vector3d> *rvecs_eigen,
142 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700143
Austin Schuhea7b0142021-10-08 22:04:53 -0700144 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700145 CameraCalibration calibration_;
146
147 cv::Ptr<cv::aruco::Dictionary> dictionary_;
148 cv::Ptr<cv::aruco::CharucoBoard> board_;
149
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800150 // Type of targets to detect
151 TargetType target_type_;
152 // Channel to listen on for images
153 std::string_view image_channel_;
154
155 // Length of a side of the target marker
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800156 double marker_length_;
157 // Length of a side of the checkerboard squares (around the marker)
158 double square_length_;
159
160 // Intrinsic calibration matrix
Austin Schuh25837f22021-06-27 15:49:14 -0700161 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800162 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700163 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800164 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700165 const cv::Mat dist_coeffs_;
166
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800167 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700168 const std::optional<uint16_t> pi_number_;
169
Austin Schuh25837f22021-06-27 15:49:14 -0700170 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800171 std::function<void(
172 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
173 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
174 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700175 handle_charuco_;
176};
177
178} // namespace vision
179} // namespace frc971
180
181#endif // Y2020_VISION_CHARUCO_LIB_H_