blob: 7759482fa6e3dcb06bcdca926a10282af86f6443 [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 };
milind-u0cb53112023-02-03 20:32:55 -080057
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 Schuh25837f22021-06-27 15:49:14 -070064
milind-u09fb1252023-01-28 19:21:41 -080065 void set_format(Format format) { format_ = format; }
Austin Schuhac402e92023-01-08 13:56:20 -080066
Austin Schuh25837f22021-06-27 15:49:14 -070067 private:
Austin Schuhc3419862023-01-08 13:54:36 -080068 void DisableTracing();
69
Austin Schuh25837f22021-06-27 15:49:14 -070070 aos::EventLoop *event_loop_;
Austin Schuhea7b0142021-10-08 22:04:53 -070071 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 Schuhc3419862023-01-08 13:54:36 -080074 aos::TimerHandler *timer_fn_;
75
76 bool disabling_ = false;
77
78 aos::Ftrace ftrace_;
Austin Schuhac402e92023-01-08 13:56:20 -080079
80 Format format_ = Format::BGR;
milind-u0cb53112023-02-03 20:32:55 -080081
82 aos::monotonic_clock::duration max_age_;
Austin Schuh25837f22021-06-27 15:49:14 -070083};
84
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080085// Types of targets that a CharucoExtractor can detect in images
86enum class TargetType : uint8_t {
milind-u09fb1252023-01-28 19:21:41 -080087 kAruco = 0,
88 kCharuco = 1,
89 kCharucoDiamond = 2
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080090};
91
Austin Schuh25837f22021-06-27 15:49:14 -070092// Class which calls a callback each time an image arrives with the information
93// extracted from it.
94class CharucoExtractor {
95 public:
96 // The callback takes the following arguments:
97 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070098 // monotonic_clock::time_point -> Time on this node when this image was
99 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800100 // 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 Schuh25837f22021-06-27 15:49:14 -0700103 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800104 // 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 Schuhea7b0142021-10-08 22:04:53 -0700109 CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800110 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
111 std::string_view image_channel,
Austin Schuhea7b0142021-10-08 22:04:53 -0700112 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800113 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 Schuh25837f22021-06-27 15:49:14 -0700120
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 Ostrowskib3cab972022-12-03 15:47:00 -0800132 // 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 Schuh25837f22021-06-27 15:49:14 -0700146
Austin Schuhea7b0142021-10-08 22:04:53 -0700147 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700148 CameraCalibration calibration_;
149
150 cv::Ptr<cv::aruco::Dictionary> dictionary_;
151 cv::Ptr<cv::aruco::CharucoBoard> board_;
152
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800153 // 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 Ostrowskib3cab972022-12-03 15:47:00 -0800159 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 Schuh25837f22021-06-27 15:49:14 -0700164 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800165 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700166 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800167 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700168 const cv::Mat dist_coeffs_;
169
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800170 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700171 const std::optional<uint16_t> pi_number_;
172
Austin Schuh25837f22021-06-27 15:49:14 -0700173 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800174 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 Schuh25837f22021-06-27 15:49:14 -0700178 handle_charuco_;
179};
180
181} // namespace vision
182} // namespace frc971
183
184#endif // Y2020_VISION_CHARUCO_LIB_H_