16 #ifndef TRACKERS__FIDUCIAL_TRACKER_HPP_
17 #define TRACKERS__FIDUCIAL_TRACKER_HPP_
24 #include <opencv2/aruco.hpp>
25 #include <opencv2/features2d.hpp>
26 #include <opencv2/opencv.hpp>
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"
37 enum class FiducialType
82 void Track(
double time,
int frame_id,
const cv::Mat & img_in, cv::Mat & img_out);
96 std::vector<std::vector<cv::Point2f>> & marker_corners,
97 std::vector<int> & marker_ids,
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
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
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,
152 Eigen::Vector3d m_pos_error;
153 Eigen::Vector3d m_ang_error;
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