ekf_cal  0.4.0
A Kalman filter-based sensor calibration package
FiducialTracker Class Reference

FiducialTracker Class. More...

#include <fiducial_tracker.hpp>

Inheritance diagram for FiducialTracker:
[legend]
Collaboration diagram for FiducialTracker:
[legend]

Classes

struct  Parameters
 Feature Tracker Initialization parameters structure. More...
 

Public Types

typedef FiducialTracker::Parameters Parameters
 Feature Tracker Initialization parameters structure.
 
- Public Types inherited from Tracker
typedef struct Tracker::Parameters Parameters
 Tracker Initialization parameters structure.
 

Public Member Functions

 FiducialTracker (FiducialTracker::Parameters params)
 FeatureTracker sensor constructor. More...
 
void Track (double time, int frame_id, const cv::Mat &img_in, cv::Mat &img_out)
 Perform track on new image frame. More...
 
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. More...
 
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. More...
 
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. More...
 
- Public Member Functions inherited from Tracker
 Tracker (Parameters params)
 Tracker Initialization parameters structure. More...
 
unsigned int GetID ()
 Tracker ID getter method. More...
 

Public Attributes

cv::Ptr< cv::aruco::Dictionary > m_dict
 Fiducial board dictionary.
 
cv::Ptr< cv::aruco::Board > m_board
 Fiducial board.
 

Protected Attributes

FiducialUpdater m_fiducial_updater
 MSCKF updater object.
 
FiducialType m_detector_type
 Detector type.
 
- Protected Attributes inherited from Tracker
unsigned int m_id
 Tracker ID.
 
int m_camera_id
 Associated camera ID of tracker.
 
unsigned int m_min_track_length {2}
 Minimum track length to consider.
 
unsigned int m_max_track_length {20}
 Maximum track length before forced output.
 
std::shared_ptr< EKFm_ekf
 EKF.
 
std::shared_ptr< DebugLoggerm_logger
 Debug logger.
 

Detailed Description

Constructor & Destructor Documentation

◆ FiducialTracker()

FiducialTracker::FiducialTracker ( FiducialTracker::Parameters  params)
explicit

FeatureTracker sensor constructor.

Parameters
paramsParameter struct for feature tracker

Member Function Documentation

◆ DrawDetectedCorners()

void FiducialTracker::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.

Parameters
imageImage on which to draw corners
marker_cornersInput aruco corners
cornersInput charuco corners
idsDetected IDs
corner_colorColors for drawing

◆ EstimatePoseBoard()

bool FiducialTracker::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.

Parameters
marker_cornersInput aruco corners
cornersInput charuco corners
idsFiducial IDs
boardFiducial board
camera_matrixInput camera matrix
dist_coefficientsInput camera distortion coefficients
r_vecOutput rotation vector of board
t_vecOutput translation vector of board

◆ InterpolateCorners()

int FiducialTracker::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.

Parameters
marker_cornersInput marker corners
marker_idsInput marker IDs
imageImage on which to perform interpolation
boardFiducial board
cornersOutput corners
idsOutput ids
camera_matrixInput camera matrix
dist_coefficientsInput camera distortion coefficients

◆ Track()

void FiducialTracker::Track ( double  time,
int  frame_id,
const cv::Mat &  img_in,
cv::Mat &  img_out 
)

Perform track on new image frame.

Parameters
timeFrame time
frame_idFrame ID
img_inInput frame
img_outOutput frame with drawn track lines

The documentation for this class was generated from the following files: