blob: fdf25e1d5862547803d553f23848fb780c8b93bf [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:
Jim Ostrowskib3cab972022-12-03 15:47:00 -080054 ImageCallback(aos::EventLoop *event_loop, std::string_view channel,
55 std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
56 &&handle_image_fn);
Austin Schuh25837f22021-06-27 15:49:14 -070057
58 private:
Austin Schuhc3419862023-01-08 13:54:36 -080059 void DisableTracing();
60
Austin Schuh25837f22021-06-27 15:49:14 -070061 aos::EventLoop *event_loop_;
Austin Schuhea7b0142021-10-08 22:04:53 -070062 aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_;
63 const aos::Node *source_node_;
64 std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_;
Austin Schuhc3419862023-01-08 13:54:36 -080065 aos::TimerHandler *timer_fn_;
66
67 bool disabling_ = false;
68
69 aos::Ftrace ftrace_;
Austin Schuh25837f22021-06-27 15:49:14 -070070};
71
72// Class which calls a callback each time an image arrives with the information
73// extracted from it.
74class CharucoExtractor {
75 public:
76 // The callback takes the following arguments:
77 // cv::Mat -> image with overlays drawn on it.
Austin Schuhea7b0142021-10-08 22:04:53 -070078 // monotonic_clock::time_point -> Time on this node when this image was
79 // captured.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080080 // std::vector<Vec4i> -> target ids (aruco/april in first slot of Vec4i)
81 // NOTE: We use Vec4i since that stores the ids for the charuco diamond target
82 // std::vector<std::vector<cv::Point2f>> -> charuco_corners
Austin Schuh25837f22021-06-27 15:49:14 -070083 // bool -> true if rvec/tvec is valid.
Jim Ostrowskib3cab972022-12-03 15:47:00 -080084 // std::vector<Eigen::Vector3d> -> rvec
85 // std::vector<Eigen::Vector3d> -> tvec
86 // NOTE: we return as a vector since all but charuco boards could have
87 // multiple targets in an image; for charuco boards, there should be just one
88 // element
Austin Schuhea7b0142021-10-08 22:04:53 -070089 CharucoExtractor(
90 aos::EventLoop *event_loop, std::string_view pi,
91 std::function<void(cv::Mat, aos::monotonic_clock::time_point,
Jim Ostrowskib3cab972022-12-03 15:47:00 -080092 std::vector<cv::Vec4i>,
93 std::vector<std::vector<cv::Point2f>>, bool,
94 std::vector<Eigen::Vector3d>,
95 std::vector<Eigen::Vector3d>)> &&handle_charuco_fn);
96
97 // Handles the image by detecting the charuco board in it.
98 void HandleImage(cv::Mat rgb_image, aos::monotonic_clock::time_point eof);
Austin Schuh25837f22021-06-27 15:49:14 -070099
100 // Returns the aruco dictionary in use.
101 cv::Ptr<cv::aruco::Dictionary> dictionary() const { return dictionary_; }
102 // Returns the aruco board in use.
103 cv::Ptr<cv::aruco::CharucoBoard> board() const { return board_; }
104
105 // Returns the camera matrix for this camera.
106 const cv::Mat camera_matrix() const { return camera_matrix_; }
107 // Returns the distortion coefficients for this camera.
108 const cv::Mat dist_coeffs() const { return dist_coeffs_; }
109
110 private:
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800111 // Creates the dictionary, board, and other parameters for the appropriate
112 // (ch)aruco target
113 void SetupTargetData();
114
115 // Draw the axes from the pose(s) on the image
116 void DrawTargetPoses(cv::Mat rgb_image, std::vector<cv::Vec3d> rvecs,
117 std::vector<cv::Vec3d> tvecs);
118
119 // Helper function to convert rotation (rvecs) and translation (tvecs) vectors
120 // into Eigen vectors and store in corresponding vectors
121 void PackPoseResults(std::vector<cv::Vec3d> &rvecs,
122 std::vector<cv::Vec3d> &tvecs,
123 std::vector<Eigen::Vector3d> *rvecs_eigen,
124 std::vector<Eigen::Vector3d> *tvecs_eigen);
Austin Schuh25837f22021-06-27 15:49:14 -0700125
Austin Schuhea7b0142021-10-08 22:04:53 -0700126 aos::EventLoop *event_loop_;
Austin Schuh25837f22021-06-27 15:49:14 -0700127 CameraCalibration calibration_;
128
129 cv::Ptr<cv::aruco::Dictionary> dictionary_;
130 cv::Ptr<cv::aruco::CharucoBoard> board_;
131
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800132 // Length of a side of the aruco marker
133 double marker_length_;
134 // Length of a side of the checkerboard squares (around the marker)
135 double square_length_;
136
137 // Intrinsic calibration matrix
Austin Schuh25837f22021-06-27 15:49:14 -0700138 const cv::Mat camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800139 // Intrinsic calibration matrix as Eigen::Matrix3d
Austin Schuh25837f22021-06-27 15:49:14 -0700140 const Eigen::Matrix3d eigen_camera_matrix_;
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800141 // Intrinsic distortion coefficients
Austin Schuh25837f22021-06-27 15:49:14 -0700142 const cv::Mat dist_coeffs_;
143
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800144 // Index number of the raspberry pi
Austin Schuh25837f22021-06-27 15:49:14 -0700145 const std::optional<uint16_t> pi_number_;
146
Austin Schuh25837f22021-06-27 15:49:14 -0700147 // Function to call.
Jim Ostrowskib3cab972022-12-03 15:47:00 -0800148 std::function<void(
149 cv::Mat, aos::monotonic_clock::time_point, std::vector<cv::Vec4i>,
150 std::vector<std::vector<cv::Point2f>>, bool, std::vector<Eigen::Vector3d>,
151 std::vector<Eigen::Vector3d>)>
Austin Schuh25837f22021-06-27 15:49:14 -0700152 handle_charuco_;
153};
154
155} // namespace vision
156} // namespace frc971
157
158#endif // Y2020_VISION_CHARUCO_LIB_H_