blob: 984cef6aae0f98b848eb85200fe522f08bfabd79 [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"
James Kuszmaul969e4ab2023-01-28 16:09:19 -080016#include "external/com_github_foxglove_schemas/ImageAnnotations_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070017
Jim Ostrowskib3cab972022-12-03 15:47:00 -080018DECLARE_bool(visualize);
Jim Ostrowskib3cab972022-12-03 15:47:00 -080019
Austin Schuh25837f22021-06-27 15:49:14 -070020namespace frc971 {
21namespace vision {
22
23// Class to find extrinsics for a specified pi's camera using the provided
24// training data.
25class CameraCalibration {
26 public:
27 CameraCalibration(const absl::Span<const uint8_t> training_data_bfbs,
28 std::string_view pi);
29
30 // Intrinsics for the located camera.
31 cv::Mat CameraIntrinsics() const;
32 Eigen::Matrix3d CameraIntrinsicsEigen() const;
33
34 // Distortion coefficients for the located camera.
35 cv::Mat CameraDistCoeffs() const;
36
37 private:
38 // Finds the camera specific calibration flatbuffer.
39 const sift::CameraCalibration *FindCameraCalibration(
40 const sift::TrainingData *const training_data, std::string_view pi) const;
41
42 // Pointer to this camera's calibration parameters.
43 const sift::CameraCalibration *camera_calibration_;
44};
45
Jim Ostrowskib3cab972022-12-03 15:47:00 -080046// Helper class to call a function with a cv::Mat and age when an image shows up
47// on the provided channel. This hides all the conversions and wrangling needed
48// to view the image.
49// Can connect this with HandleImage function from CharucoExtrator for
50// full-service callback functionality
Austin Schuh25837f22021-06-27 15:49:14 -070051class ImageCallback {
52 public:
Austin Schuhac402e92023-01-08 13:56:20 -080053 enum class Format {
54 YUYV2 = 0,
55 BGR = 1,
56 GRAYSCALE = 2,
57 };
milind-u0cb53112023-02-03 20:32:55 -080058
59 // `max_age` is the age to start dropping frames at
60 ImageCallback(
61 aos::EventLoop *event_loop, std::string_view channel,
62 std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
63 &&handle_image_fn,
64 aos::monotonic_clock::duration max_age = std::chrono::milliseconds(100));
Austin Schuh25837f22021-06-27 15:49:14 -070065
milind-u09fb1252023-01-28 19:21:41 -080066 void set_format(Format format) { format_ = format; }
Austin Schuhac402e92023-01-08 13:56:20 -080067
Austin Schuh25837f22021-06-27 15:49:14 -070068 private:
Austin Schuhc3419862023-01-08 13:54:36 -080069 void DisableTracing();
70
Austin Schuh25837f22021-06-27 15:49:14 -070071 aos::EventLoop *event_loop_;
Austin Schuhea7b0142021-10-08 22:04:53 -070072 aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_;
73 const aos::Node *source_node_;
74 std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_;
Austin Schuhc3419862023-01-08 13:54:36 -080075 aos::TimerHandler *timer_fn_;
76
77 bool disabling_ = false;
78
79 aos::Ftrace ftrace_;
Austin Schuhac402e92023-01-08 13:56:20 -080080
81 Format format_ = Format::BGR;
milind-u0cb53112023-02-03 20:32:55 -080082
83 aos::monotonic_clock::duration max_age_;
Austin Schuh25837f22021-06-27 15:49:14 -070084};
85
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080086// Types of targets that a CharucoExtractor can detect in images
87enum class TargetType : uint8_t {
milind-u09fb1252023-01-28 19:21:41 -080088 kAruco = 0,
89 kCharuco = 1,
90 kCharucoDiamond = 2
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080091};
92
Austin Schuh25837f22021-06-27 15:49:14 -070093// Class which calls a callback each time an image arrives with the information
94// extracted from it.
95class CharucoExtractor {
96 public:
97 // The callback takes the following arguments:
98 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070099 // monotonic_clock::time_point -> Time on this node when this image was
100 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800101 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
102 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
103 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -0700104 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800105 // std::vector<Eigen::Vector3d> -> rvec
106 // std::vector<Eigen::Vector3d> -> tvec
107 // NOTE: we return as a vector since all but charuco boards could have
108 // multiple targets in an image; for charuco boards, there should be just one
109 // element
Austin Schuhea7b0142021-10-08 22:04:53 -0700110 CharucoExtractor(
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800111 aos::EventLoop *event_loop, std::string_view pi, TargetType target_type,
112 std::string_view image_channel,
Austin Schuhea7b0142021-10-08 22:04:53 -0700113 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800114 std::vector<cv::Vec4i>,
115 std::vector<std::vector<cv::Point2f>>, bool,
116 std::vector<Eigen::Vector3d>,
117 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn);
118
119 // Handles the image by detecting the charuco board in it.
120 void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof);
Austin Schuh25837f22021-06-27 15:49:14 -0700121
122 // Returns the aruco dictionary in use.
123 cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; }
124 // Returns the aruco board in use.
125 cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; }
126
127 // Returns the camera matrix for this camera.
128 const cv::Mat camera_matrix() const { return camera_matrix_; }
129 // Returns the distortion coefficients for this camera.
130 const cv::Mat dist_coeffs() const { return dist_coeffs_; }
131
132 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800133 // Creates the dictionary, board, and other parameters for the appropriate
134 // (ch)aruco target
135 void SetupTargetData();
136
137 // Draw the axes from the pose(s) on the image
138 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
139 std::vector<cv::Vec3d> tvecs);
140
141 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
142 // into Eigen vectors and store in corresponding vectors
143 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
144 std::vector<cv::Vec3d> &tvecs,
145 std::vector<Eigen::Vector3d> *rvecs_eigen,
146 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700147
Austin Schuhea7b0142021-10-08 22:04:53 -0700148 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700149 CameraCalibration calibration_;
150
151 cv::Ptr<cv::aruco::Dictionary> dictionary_;
152 cv::Ptr<cv::aruco::CharucoBoard> board_;
153
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800154 // Type of targets to detect
155 TargetType target_type_;
156 // Channel to listen on for images
157 std::string_view image_channel_;
158
159 // Length of a side of the target marker
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800160 double marker_length_;
161 // Length of a side of the checkerboard squares (around the marker)
162 double square_length_;
163
164 // Intrinsic calibration matrix
Austin Schuh25837f22021-06-27 15:49:14 -0700165 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800166 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700167 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800168 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700169 const cv::Mat dist_coeffs_;
170
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800171 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700172 const std::optional<uint16_t> pi_number_;
173
Austin Schuh25837f22021-06-27 15:49:14 -0700174 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800175 std::function<void(
176 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
177 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
178 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700179 handle_charuco_;
180};
181
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800182// Puts the provided charuco corners into a foxglove ImageAnnotation type for
183// visualization purposes.
184flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations(
185 const aos::monotonic_clock::time_point monotonic_now,
186 const std::vector<std::vector<cv::Point2f>> &corners,
187 flatbuffers::FlatBufferBuilder *fbb);
188
Austin Schuh25837f22021-06-27 15:49:14 -0700189} // namespace vision
190} // namespace frc971
191
192#endif // Y2020_VISION_CHARUCO_LIB_H_