blob: b2ca7ee05088c81ba98524606411d241c5010960 [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"
James Kuszmaul7e958812023-02-11 15:34:31 -080014#include "frc971/vision/calibration_generated.h"
James Kuszmaul969e4ab2023-01-28 16:09:19 -080015#include "external/com_github_foxglove_schemas/ImageAnnotations_generated.h"
Austin Schuh25837f22021-06-27 15:49:14 -070016
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:
James Kuszmaul7e958812023-02-11 15:34:31 -080026 CameraCalibration(const calibration::CameraCalibration *calibration);
Austin Schuh25837f22021-06-27 15:49:14 -070027
28 // Intrinsics for the located camera.
James Kuszmaul7e958812023-02-11 15:34:31 -080029 cv::Mat CameraIntrinsics() const { return intrinsics_; }
30 Eigen::Matrix3d CameraIntrinsicsEigen() const { return intrinsics_eigen_; }
Austin Schuh25837f22021-06-27 15:49:14 -070031
32 // Distortion coefficients for the located camera.
James Kuszmaul7e958812023-02-11 15:34:31 -080033 cv::Mat CameraDistCoeffs() const { return dist_coeffs_; }
Austin Schuh25837f22021-06-27 15:49:14 -070034
35 private:
James Kuszmaul7e958812023-02-11 15:34:31 -080036 const cv::Mat intrinsics_;
37 const Eigen::Matrix3d intrinsics_eigen_;
38 const cv::Mat dist_coeffs_;
Austin Schuh25837f22021-06-27 15:49:14 -070039};
40
Jim Ostrowskib3cab972022-12-03 15:47:00 -080041// Helper class to call a function with a cv::Mat and age when an image shows up
42// on the provided channel. This hides all the conversions and wrangling needed
43// to view the image.
44// Can connect this with HandleImage function from CharucoExtrator for
45// full-service callback functionality
Austin Schuh25837f22021-06-27 15:49:14 -070046class ImageCallback {
47 public:
Austin Schuhac402e92023-01-08 13:56:20 -080048 enum class Format {
49 YUYV2 = 0,
50 BGR = 1,
51 GRAYSCALE = 2,
52 };
milind-u0cb53112023-02-03 20:32:55 -080053
54 // `max_age` is the age to start dropping frames at
55 ImageCallback(
56 aos::EventLoop *event_loop, std::string_view channel,
57 std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
58 &&handle_image_fn,
59 aos::monotonic_clock::duration max_age = std::chrono::milliseconds(100));
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;
milind-u0cb53112023-02-03 20:32:55 -080077
78 aos::monotonic_clock::duration max_age_;
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 {
milind-u09fb1252023-01-28 19:21:41 -080083 kAruco = 0,
84 kCharuco = 1,
85 kCharucoDiamond = 2
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -080086};
87
Austin Schuh25837f22021-06-27 15:49:14 -070088// Class which calls a callback each time an image arrives with the information
89// extracted from it.
90class CharucoExtractor {
91 public:
92 // The callback takes the following arguments:
93 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070094 // monotonic_clock::time_point -> Time on this node when this image was
95 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080096 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
97 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
98 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -070099 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800100 // std::vector<Eigen::Vector3d> -> rvec
101 // std::vector<Eigen::Vector3d> -> tvec
102 // NOTE: we return as a vector since all but charuco boards could have
103 // multiple targets in an image; for charuco boards, there should be just one
104 // element
Austin Schuhea7b0142021-10-08 22:04:53 -0700105 CharucoExtractor(
James Kuszmaul7e958812023-02-11 15:34:31 -0800106 aos::EventLoop *event_loop,
107 const calibration::CameraCalibration *calibration, TargetType target_type,
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800108 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.
James Kuszmaul7e958812023-02-11 15:34:31 -0800124 const cv::Mat camera_matrix() const {
125 return calibration_.CameraIntrinsics();
126 }
Austin Schuh25837f22021-06-27 15:49:14 -0700127 // Returns the distortion coefficients for this camera.
James Kuszmaul7e958812023-02-11 15:34:31 -0800128 const cv::Mat dist_coeffs() const { return calibration_.CameraDistCoeffs(); }
Austin Schuh25837f22021-06-27 15:49:14 -0700129
130 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800131 // Creates the dictionary, board, and other parameters for the appropriate
132 // (ch)aruco target
133 void SetupTargetData();
134
135 // Draw the axes from the pose(s) on the image
136 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
137 std::vector<cv::Vec3d> tvecs);
138
139 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
140 // into Eigen vectors and store in corresponding vectors
141 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
142 std::vector<cv::Vec3d> &tvecs,
143 std::vector<Eigen::Vector3d> *rvecs_eigen,
144 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700145
Austin Schuhea7b0142021-10-08 22:04:53 -0700146 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700147
148 cv::Ptr<cv::aruco::Dictionary> dictionary_;
149 cv::Ptr<cv::aruco::CharucoBoard> board_;
150
Milind Upadhyayc6e42ee2022-12-27 00:02:11 -0800151 // Type of targets to detect
152 TargetType target_type_;
153 // Channel to listen on for images
154 std::string_view image_channel_;
155
156 // Length of a side of the target marker
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800157 double marker_length_;
158 // Length of a side of the checkerboard squares (around the marker)
159 double square_length_;
160
James Kuszmaul7e958812023-02-11 15:34:31 -0800161 CameraCalibration calibration_;
Austin Schuh25837f22021-06-27 15:49:14 -0700162
Austin Schuh25837f22021-06-27 15:49:14 -0700163 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800164 std::function<void(
165 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
166 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
167 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700168 handle_charuco_;
169};
170
James Kuszmaul969e4ab2023-01-28 16:09:19 -0800171// Puts the provided charuco corners into a foxglove ImageAnnotation type for
172// visualization purposes.
173flatbuffers::Offset<foxglove::ImageAnnotations> BuildAnnotations(
174 const aos::monotonic_clock::time_point monotonic_now,
175 const std::vector<std::vector<cv::Point2f>> &corners,
176 flatbuffers::FlatBufferBuilder *fbb);
177
Austin Schuh25837f22021-06-27 15:49:14 -0700178} // namespace vision
179} // namespace frc971
180
181#endif // Y2020_VISION_CHARUCO_LIB_H_