blob: f4f123331ae2a4ae52042083e0065ed7eb0a8990 [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>
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 Schuhea7b0142021-10-08 22:04:53 -070014#include "aos/network/message_bridge_server_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070015#include "y2020/vision/sift/sift_generated.h"
16#include "y2020/vision/sift/sift_training_generated.h"
17
Jim Ostrowskib3cab972022-12-03 15:47:00 -080018DECLARE_bool(visualize);
19DECLARE_string(target_type);
20
Austin Schuh25837f22021-06-27 15:49:14 -070021namespace frc971 {
22namespace vision {
23
24// Class to find extrinsics for a specified pi's camera using the provided
25// training data.
26class 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 Ostrowskib3cab972022-12-03 15:47:00 -080047// 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 Schuh25837f22021-06-27 15:49:14 -070052class ImageCallback {
53 public:
Austin Schuhac402e92023-01-08 13:56:20 -080054 enum class Format {
55 YUYV2 = 0,
56 BGR = 1,
57 GRAYSCALE = 2,
58 };
Jim Ostrowskib3cab972022-12-03 15:47:00 -080059 ImageCallback(aos::EventLoop *event_loop, std::string_view channel,
60 std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
61 &&handle_image_fn);
Austin Schuh25837f22021-06-27 15:49:14 -070062
Austin Schuhac402e92023-01-08 13:56:20 -080063 void set_format(Format format) {
64 format_ = format;
65 }
66
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;
Austin Schuh25837f22021-06-27 15:49:14 -070081};
82
83// Class which calls a callback each time an image arrives with the information
84// extracted from it.
85class CharucoExtractor {
86 public:
87 // The callback takes the following arguments:
88 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070089 // monotonic_clock::time_point -> Time on this node when this image was
90 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080091 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
92 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
93 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -070094 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080095 // std::vector<Eigen::Vector3d> -> rvec
96 // std::vector<Eigen::Vector3d> -> tvec
97 // NOTE: we return as a vector since all but charuco boards could have
98 // multiple targets in an image; for charuco boards, there should be just one
99 // element
Austin Schuhea7b0142021-10-08 22:04:53 -0700100 CharucoExtractor(
101 aos::EventLoop *event_loop, std::string_view pi,
102 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800103 std::vector<cv::Vec4i>,
104 std::vector<std::vector<cv::Point2f>>, bool,
105 std::vector<Eigen::Vector3d>,
106 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn);
107
108 // Handles the image by detecting the charuco board in it.
109 void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700110
111 // Returns the aruco dictionary in use.
112 cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; }
113 // Returns the aruco board in use.
114 cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; }
115
116 // Returns the camera matrix for this camera.
117 const cv::Mat camera_matrix() const { return camera_matrix_; }
118 // Returns the distortion coefficients for this camera.
119 const cv::Mat dist_coeffs() const { return dist_coeffs_; }
120
121 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800122 // Creates the dictionary, board, and other parameters for the appropriate
123 // (ch)aruco target
124 void SetupTargetData();
125
126 // Draw the axes from the pose(s) on the image
127 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
128 std::vector<cv::Vec3d> tvecs);
129
130 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
131 // into Eigen vectors and store in corresponding vectors
132 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
133 std::vector<cv::Vec3d> &tvecs,
134 std::vector<Eigen::Vector3d> *rvecs_eigen,
135 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700136
Austin Schuhea7b0142021-10-08 22:04:53 -0700137 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700138 CameraCalibration calibration_;
139
140 cv::Ptr<cv::aruco::Dictionary> dictionary_;
141 cv::Ptr<cv::aruco::CharucoBoard> board_;
142
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800143 // Length of a side of the aruco marker
144 double marker_length_;
145 // Length of a side of the checkerboard squares (around the marker)
146 double square_length_;
147
148 // Intrinsic calibration matrix
Austin Schuh25837f22021-06-27 15:49:14 -0700149 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800150 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700151 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800152 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700153 const cv::Mat dist_coeffs_;
154
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800155 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700156 const std::optional<uint16_t> pi_number_;
157
Austin Schuh25837f22021-06-27 15:49:14 -0700158 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800159 std::function<void(
160 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
161 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
162 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700163 handle_charuco_;
164};
165
166} // namespace vision
167} // namespace frc971
168
169#endif // Y2020_VISION_CHARUCO_LIB_H_