FiducialTracker Class.
More...
#include <fiducial_tracker.hpp>
|
| 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...
|
|
| Tracker (Parameters params) |
| Tracker Initialization parameters structure. More...
|
|
unsigned int | GetID () |
| Tracker ID getter method. More...
|
|
|
cv::Ptr< cv::aruco::Dictionary > | m_dict |
| Fiducial board dictionary.
|
|
cv::Ptr< cv::aruco::Board > | m_board |
| Fiducial board.
|
|
◆ FiducialTracker()
FeatureTracker sensor constructor.
- Parameters
-
params | Parameter struct for feature tracker |
◆ 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
-
image | Image on which to draw corners |
marker_corners | Input aruco corners |
corners | Input charuco corners |
ids | Detected IDs |
corner_color | Colors 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_corners | Input aruco corners |
corners | Input charuco corners |
ids | Fiducial IDs |
board | Fiducial board |
camera_matrix | Input camera matrix |
dist_coefficients | Input camera distortion coefficients |
r_vec | Output rotation vector of board |
t_vec | Output 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_corners | Input marker corners |
marker_ids | Input marker IDs |
image | Image on which to perform interpolation |
board | Fiducial board |
corners | Output corners |
ids | Output ids |
camera_matrix | Input camera matrix |
dist_coefficients | Input 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
-
time | Frame time |
frame_id | Frame ID |
img_in | Input frame |
img_out | Output frame with drawn track lines |
The documentation for this class was generated from the following files: