Public Member Functions | Private Attributes | List of all members
aruco::FractalPoseTracker Class Reference

#include <fractalposetracker.h>

Public Member Functions

void drawKeyPoints (const cv::Mat image, std::vector< cv::KeyPoint > kpoints, bool text=false, bool transf=false)
 image More...
 
cv::Mat fractal_solve_ransac (int ninners, std::vector< std::pair< uint, std::vector< uint >>> inner_kpnt, std::vector< cv::KeyPoint > kpnts, uint32_t maxIter=500, float _minInliers=0.2f, float _thresInliers=0.7f)
 fractal_solve_ransac More...
 
bool fractalInnerPose (const cv::Ptr< MarkerDetector > markerDetector, const std::vector< aruco::Marker > &markers, bool refinement=true)
 fractalInnerPose More...
 
 FractalPoseTracker ()
 
bool fractalRefinement (const cv::Ptr< MarkerDetector > markerDetector, int markerWarpPix=10)
 fractalRefinement More...
 
FractalMarkerSet getFractal ()
 
const std::vector< cv::Point3f > getInner3d ()
 
const cv::Mat getRvec () const
 
const cv::Mat getTvec () const
 
bool isPoseValid () const
 
bool ROI (const std::vector< cv::Mat > imagePyramid, cv::Mat &img, std::vector< cv::Point2f > &innerPoints2d, cv::Point2f &offset, float &ratio)
 ROI. More...
 
void setParams (const CameraParameters &cam_params, const FractalMarkerSet &msconf, const float markerSize=-1)
 setParams More...
 

Private Attributes

aruco::CameraParameters _cam_params
 
FractalMarkerSet _fractalMarker
 
std::map< int, float > _id_area
 
std::map< int, std::vector< cv::Point3f > > _id_innerp3d
 
std::map< int, double > _id_radius
 
std::vector< cv::KeyPoint > _innerkpoints
 
std::vector< cv::Point3f > _innerp3d
 
picoflann::KdTreeIndex< 2, PicoFlann_KeyPointAdapter_kdtree
 
float _preRadius = 0
 
cv::Mat _rvec
 
cv::Mat _tvec
 

Detailed Description

Definition at line 36 of file fractalposetracker.h.

Constructor & Destructor Documentation

◆ FractalPoseTracker()

aruco::FractalPoseTracker::FractalPoseTracker ( )

Definition at line 230 of file fractalposetracker.cpp.

Member Function Documentation

◆ drawKeyPoints()

void aruco::FractalPoseTracker::drawKeyPoints ( const cv::Mat  image,
std::vector< cv::KeyPoint >  kpoints,
bool  text = false,
bool  transf = false 
)

image

Draw keypoints

Parameters
kpoints
text
transf.Is it necessary to transform keypoints? (-MarkerSize/2 .. MarkerSize/2) to (0 .. ImageSize)

Definition at line 1047 of file fractalposetracker.cpp.

◆ fractal_solve_ransac()

cv::Mat aruco::FractalPoseTracker::fractal_solve_ransac ( int  ninners,
std::vector< std::pair< uint, std::vector< uint >>>  inner_kpnt,
std::vector< cv::KeyPoint >  kpnts,
uint32_t  maxIter = 500,
float  _minInliers = 0.2f,
float  _thresInliers = 0.7f 
)

fractal_solve_ransac

estimate the pose of the fractal marker. Method case 2, paper.

Parameters
ninners(number of total inners points used)
inner_kpntmatches (inner points - detected keypoints)
kpntskeypoints
maxItermaximum number of iterations
_minInliersbeta in paper
_thresInliersalpha in paper
Returns
Mat best model homography.

Definition at line 900 of file fractalposetracker.cpp.

◆ fractalInnerPose()

bool aruco::FractalPoseTracker::fractalInnerPose ( const cv::Ptr< MarkerDetector markerDetector,
const std::vector< aruco::Marker > &  markers,
bool  refinement = true 
)

fractalInnerPose

estimate the pose of the fractal marker.

Parameters
markerDetector
detectedmarkers
refinement,useor not pose refinement. True by default.
Returns
true if the pose is estimated and false otherwise. If not estimated, the parameters m.Rvec and m.Tvec and not set.

Definition at line 552 of file fractalposetracker.cpp.

◆ fractalRefinement()

bool aruco::FractalPoseTracker::fractalRefinement ( const cv::Ptr< MarkerDetector markerDetector,
int  markerWarpPix = 10 
)

fractalRefinement

Refinement of the internal points of the marker and pose estimation with these.

Parameters
markerDetector
markerWarpPix.Optimal markerwarpPix used to select the image of the pyramid. Default value 10.
Returns
true if the pose is estimated and false otherwise. If not estimated, the parameters m.Rvec and m.Tvec and not set.

Definition at line 288 of file fractalposetracker.cpp.

◆ getFractal()

FractalMarkerSet aruco::FractalPoseTracker::getFractal ( )
inline

Definition at line 130 of file fractalposetracker.h.

◆ getInner3d()

const std::vector<cv::Point3f> aruco::FractalPoseTracker::getInner3d ( )
inline

Definition at line 119 of file fractalposetracker.h.

◆ getRvec()

const cv::Mat aruco::FractalPoseTracker::getRvec ( ) const
inline

Definition at line 107 of file fractalposetracker.h.

◆ getTvec()

const cv::Mat aruco::FractalPoseTracker::getTvec ( ) const
inline

Definition at line 113 of file fractalposetracker.h.

◆ isPoseValid()

bool aruco::FractalPoseTracker::isPoseValid ( ) const
inline

Definition at line 125 of file fractalposetracker.h.

◆ ROI()

bool aruco::FractalPoseTracker::ROI ( const std::vector< cv::Mat >  imagePyramid,
cv::Mat &  img,
std::vector< cv::Point2f > &  innerPoints2d,
cv::Point2f &  offset,
float &  ratio 
)

ROI.

extraction of the region of the image where the marker is estimated to be based on the previous pose

Parameters
imagePyramidset images
imgoriginal image. The image is scaled according to the selected pyramid image.
innerPoints2dcollection fractal inner points. The points are scaled according to the selected pyramid image.
offset.Position of the upper inner corner of the marker. The offset is scaled according to the selected pyramid image.
ratioselected scaling factor

Definition at line 794 of file fractalposetracker.cpp.

◆ setParams()

void aruco::FractalPoseTracker::setParams ( const CameraParameters cam_params,
const FractalMarkerSet msconf,
const float  markerSize = -1 
)

setParams

init fractlPoseTracker parameters

Parameters
cam_paramscamera paremeters
msconfFractalMarkerSet configuration
markerSizeFractalMarker size

Definition at line 234 of file fractalposetracker.cpp.

Member Data Documentation

◆ _cam_params

aruco::CameraParameters aruco::FractalPoseTracker::_cam_params
private

Definition at line 137 of file fractalposetracker.h.

◆ _fractalMarker

FractalMarkerSet aruco::FractalPoseTracker::_fractalMarker
private

Definition at line 136 of file fractalposetracker.h.

◆ _id_area

std::map<int, float> aruco::FractalPoseTracker::_id_area
private

Definition at line 144 of file fractalposetracker.h.

◆ _id_innerp3d

std::map<int, std::vector<cv::Point3f> > aruco::FractalPoseTracker::_id_innerp3d
private

Definition at line 139 of file fractalposetracker.h.

◆ _id_radius

std::map<int, double> aruco::FractalPoseTracker::_id_radius
private

Definition at line 143 of file fractalposetracker.h.

◆ _innerkpoints

std::vector<cv::KeyPoint> aruco::FractalPoseTracker::_innerkpoints
private

Definition at line 141 of file fractalposetracker.h.

◆ _innerp3d

std::vector<cv::Point3f> aruco::FractalPoseTracker::_innerp3d
private

Definition at line 140 of file fractalposetracker.h.

◆ _kdtree

picoflann::KdTreeIndex<2, PicoFlann_KeyPointAdapter> aruco::FractalPoseTracker::_kdtree
private

Definition at line 142 of file fractalposetracker.h.

◆ _preRadius

float aruco::FractalPoseTracker::_preRadius = 0
private

Definition at line 145 of file fractalposetracker.h.

◆ _rvec

cv::Mat aruco::FractalPoseTracker::_rvec
private

Definition at line 138 of file fractalposetracker.h.

◆ _tvec

cv::Mat aruco::FractalPoseTracker::_tvec
private

Definition at line 138 of file fractalposetracker.h.


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


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:45