blob: de6d4fb7e2e238f5a67682ebb76b4993fa3f4eb9 [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
milind-u09fb1252023-01-28 19:21:41 -080061 void set_format(Format format) { format_ = format; }
Austin Schuhac402e92023-01-08 13:56:20 -080062
Austin Schuh25837f22021-06-27 15:49:14 -070063 private:
Austin Schuhc3419862023-01-08 13:54:36 -080064 void DisableTracing();
65
Austin Schuh25837f22021-06-27 15:49:14 -070066 aos::EventLoop *event_loop_;
Austin Schuhea7b0142021-10-08 22:04:53 -070067 aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_;
68 const aos::Node *source_node_;
69 std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_;
Austin Schuhc3419862023-01-08 13:54:36 -080070 aos::TimerHandler *timer_fn_;
71
72 bool disabling_ = false;
73
74 aos::Ftrace ftrace_;
Austin Schuhac402e92023-01-08 13:56:20 -080075
76 Format format_ = Format::BGR;
Austin Schuh25837f22021-06-27 15:49:14 -070077};
78
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080079// Types of targets that a CharucoExtractor can detect in images
80enum class TargetType : uint8_t {
milind-u09fb1252023-01-28 19:21:41 -080081 kAruco = 0,
82 kCharuco = 1,
83 kCharucoDiamond = 2
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080084};
85
Austin Schuh25837f22021-06-27 15:49:14 -070086// Class which calls a callback each time an image arrives with the information
87// extracted from it.
88class CharucoExtractor {
89 public:
90 // The callback takes the following arguments:
91 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070092 // monotonic_clock::time_point -> Time on this node when this image was
93 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080094 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
95 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
96 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -070097 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080098 // std::vector<Eigen::Vector3d> -> rvec
99 // std::vector<Eigen::Vector3d> -> tvec
100 // NOTE: we return as a vector since all but charuco boards could have
101 // multiple targets in an image; for charuco boards, there should be just one
102 // element
Austin Schuhea7b0142021-10-08 22:04:53 -0700103 CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800104 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
105 std::string_view image_channel,
Austin Schuhea7b0142021-10-08 22:04:53 -0700106 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800107 std::vector<cv::Vec4i>,
108 std::vector<std::vector<cv::Point2f>>, bool,
109 std::vector<Eigen::Vector3d>,
110 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn);
111
112 // Handles the image by detecting the charuco board in it.
113 void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700114
115 // Returns the aruco dictionary in use.
116 cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; }
117 // Returns the aruco board in use.
118 cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; }
119
120 // Returns the camera matrix for this camera.
121 const cv::Mat camera_matrix() const { return camera_matrix_; }
122 // Returns the distortion coefficients for this camera.
123 const cv::Mat dist_coeffs() const { return dist_coeffs_; }
124
125 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800126 // Creates the dictionary, board, and other parameters for the appropriate
127 // (ch)aruco target
128 void SetupTargetData();
129
130 // Draw the axes from the pose(s) on the image
131 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
132 std::vector<cv::Vec3d> tvecs);
133
134 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
135 // into Eigen vectors and store in corresponding vectors
136 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
137 std::vector<cv::Vec3d> &tvecs,
138 std::vector<Eigen::Vector3d> *rvecs_eigen,
139 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700140
Austin Schuhea7b0142021-10-08 22:04:53 -0700141 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700142 CameraCalibration calibration_;
143
144 cv::Ptr<cv::aruco::Dictionary> dictionary_;
145 cv::Ptr<cv::aruco::CharucoBoard> board_;
146
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800147 // Type of targets to detect
148 TargetType target_type_;
149 // Channel to listen on for images
150 std::string_view image_channel_;
151
152 // Length of a side of the target marker
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800153 double marker_length_;
154 // Length of a side of the checkerboard squares (around the marker)
155 double square_length_;
156
157 // Intrinsic calibration matrix
Austin Schuh25837f22021-06-27 15:49:14 -0700158 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800159 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700160 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800161 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700162 const cv::Mat dist_coeffs_;
163
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800164 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700165 const std::optional<uint16_t> pi_number_;
166
Austin Schuh25837f22021-06-27 15:49:14 -0700167 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800168 std::function<void(
169 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
170 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
171 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700172 handle_charuco_;
173};
174
175} // namespace vision
176} // namespace frc971
177
178#endif // Y2020_VISION_CHARUCO_LIB_H_