ekf_cal  0.4.0
A Kalman filter-based sensor calibration package
fiducial_tracker.hpp
1 // Copyright 2023 Jacob Hartzer
2 //
3 // This program is free software: you can redistribute it and/or modify
4 // it under the terms of the GNU General Public License as published by
5 // the Free Software Foundation, either version 3 of the License, or
6 // (at your option) any later version.
7 //
8 // This program is distributed in the hope that it will be useful,
9 // but WITHOUT ANY WARRANTY; without even the implied warranty of
10 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11 // GNU General Public License for more details.
12 //
13 // You should have received a copy of the GNU General Public License
14 // along with this program. If not, see <https://www.gnu.org/licenses/>.
15 
16 #ifndef TRACKERS__FIDUCIAL_TRACKER_HPP_
17 #define TRACKERS__FIDUCIAL_TRACKER_HPP_
18 
19 #include <map>
20 #include <memory>
21 #include <string>
22 #include <vector>
23 
24 #include <opencv2/aruco.hpp>
25 #include <opencv2/features2d.hpp>
26 #include <opencv2/opencv.hpp>
27 
28 #include "ekf/ekf.hpp"
29 #include "ekf/types.hpp"
30 #include "ekf/update/fiducial_updater.hpp"
31 #include "infrastructure/debug_logger.hpp"
32 #include "trackers/tracker.hpp"
33 
37 enum class FiducialType
38 {
39  ARUCO_BOARD,
40  CHARUCO_BOARD
41 };
42 
47 class FiducialTracker : public Tracker
48 {
49 public:
53  typedef struct Parameters : public Tracker::Parameters
54  {
55  FiducialType detector_type;
56  unsigned int predefined_dict{0};
57  unsigned int squares_x {1};
58  unsigned int squares_y {1};
59  double square_length {1.0};
60  double marker_length {1.0};
61  unsigned int id{0};
62  Eigen::Vector3d pos_f_in_l;
63  Eigen::Quaterniond ang_f_to_l;
64  bool is_extrinsic{false};
65  Eigen::VectorXd variance {{1, 1, 1, 1, 1, 1}};
66  bool is_cam_extrinsic{false};
68 
74 
82  void Track(double time, int frame_id, const cv::Mat & img_in, cv::Mat & img_out);
83 
96  std::vector<std::vector<cv::Point2f>> & marker_corners,
97  std::vector<int> & marker_ids,
98  cv::Mat image,
99  cv::Ptr<cv::aruco::Board> & board,
100  std::vector<cv::Point2f> & corners,
101  std::vector<int> & ids,
102  cv::Mat camera_matrix,
103  cv::Mat dist_coefficients
104  );
105 
114  void DrawDetectedCorners(
115  cv::Mat image,
116  std::vector<std::vector<cv::Point2f>> & marker_corners,
117  std::vector<cv::Point2f> & corners,
118  std::vector<int> & ids,
119  cv::Scalar corner_color
120  );
121 
133  bool EstimatePoseBoard(
134  std::vector<std::vector<cv::Point2f>> & marker_corners,
135  cv::InputArray & corners,
136  cv::InputArray & ids,
137  cv::Ptr<cv::aruco::Board> board,
138  cv::InputArray & camera_matrix,
139  cv::InputArray & dist_coefficients,
140  cv::Vec3d & r_vec,
141  cv::Vec3d & t_vec
142  );
143 
144  cv::Ptr<cv::aruco::Dictionary> m_dict;
145  cv::Ptr<cv::aruco::Board> m_board;
146 
147 protected:
149  FiducialType m_detector_type;
150 
151 private:
152  Eigen::Vector3d m_pos_error;
153  Eigen::Vector3d m_ang_error;
154 };
155 
156 #endif // TRACKERS__FIDUCIAL_TRACKER_HPP_
FiducialTracker Class.
Definition: fiducial_tracker.hpp:48
FiducialType m_detector_type
Detector type.
Definition: fiducial_tracker.hpp:149
FiducialTracker::Parameters Parameters
Feature Tracker Initialization parameters structure.
void Track(double time, int frame_id, const cv::Mat &img_in, cv::Mat &img_out)
Perform track on new image frame.
Definition: fiducial_tracker.cpp:131
void DrawDetectedCorners(cv::Mat image, std::vector< std::vector< cv::Point2f >> &marker_corners, std::vector< cv::Point2f > &corners, std::vector< int > &ids, cv::Scalar corner_color)
DrawDetectedCorners.
Definition: fiducial_tracker.cpp:93
cv::Ptr< cv::aruco::Board > m_board
Fiducial board.
Definition: fiducial_tracker.hpp:145
FiducialTracker(FiducialTracker::Parameters params)
FeatureTracker sensor constructor.
Definition: fiducial_tracker.cpp:26
cv::Ptr< cv::aruco::Dictionary > m_dict
Fiducial board dictionary.
Definition: fiducial_tracker.hpp:144
int InterpolateCorners(std::vector< std::vector< cv::Point2f >> &marker_corners, std::vector< int > &marker_ids, cv::Mat image, cv::Ptr< cv::aruco::Board > &board, std::vector< cv::Point2f > &corners, std::vector< int > &ids, cv::Mat camera_matrix, cv::Mat dist_coefficients)
Function to interpolate corners of charuco boards.
Definition: fiducial_tracker.cpp:69
bool EstimatePoseBoard(std::vector< std::vector< cv::Point2f >> &marker_corners, cv::InputArray &corners, cv::InputArray &ids, cv::Ptr< cv::aruco::Board > board, cv::InputArray &camera_matrix, cv::InputArray &dist_coefficients, cv::Vec3d &r_vec, cv::Vec3d &t_vec)
Estimate pose of board.
Definition: fiducial_tracker.cpp:108
FiducialUpdater m_fiducial_updater
MSCKF updater object.
Definition: fiducial_tracker.hpp:148
EKF Updater Class for Fiducial Camera Measurements.
Definition: fiducial_updater.hpp:34
Tracker Class.
Definition: tracker.hpp:31
Feature Tracker Initialization parameters structure.
Definition: fiducial_tracker.hpp:54
bool is_extrinsic
Perform extrinsic calibration.
Definition: fiducial_tracker.hpp:64
FiducialType detector_type
Detector type.
Definition: fiducial_tracker.hpp:55
bool is_cam_extrinsic
Flag for extrinsic camera calibration.
Definition: fiducial_tracker.hpp:66
unsigned int squares_y
Number of squares in the y direction.
Definition: fiducial_tracker.hpp:58
Eigen::VectorXd variance
Fiducial marker variance.
Definition: fiducial_tracker.hpp:65
unsigned int predefined_dict
Predefined dictionary.
Definition: fiducial_tracker.hpp:56
Eigen::Quaterniond ang_f_to_l
Fiducial orientation.
Definition: fiducial_tracker.hpp:63
Eigen::Vector3d pos_f_in_l
Fiducial position.
Definition: fiducial_tracker.hpp:62
double marker_length
Marker length.
Definition: fiducial_tracker.hpp:60
double square_length
Checkerboard square length.
Definition: fiducial_tracker.hpp:59
unsigned int squares_x
Number of squares in the x direction.
Definition: fiducial_tracker.hpp:57
Tracker Initialization parameters structure.
Definition: tracker.hpp:37