Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
aruco::MarkerDetector Class Reference

Main class for marker detection. More...

#include <markerdetector.h>

Classes

class  MarkerCandidate
 
struct  Params
 

Public Types

enum  CornerRefinementMethod { NONE, SUBPIX, LINES }
 
enum  ThresholdMethods { FIXED_THRES, ADPT_THRES, CANNY }
 

Public Member Functions

void adpt_threshold_multi (const cv::Mat &grey, std::vector< cv::Mat > &out, double param1, double param1_range, double param2, double param2_range=0)
 
std::vector< aruco::Markerdetect (const cv::Mat &input) throw (cv::Exception)
 
std::vector< aruco::Markerdetect (const cv::Mat &input, const CameraParameters &camParams, float markerSizeMeters, bool setYPerperdicular=false) throw (cv::Exception)
 
void detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, CameraParameters camParams, float markerSizeMeters=-1, bool setYPerperdicular=false) throw (cv::Exception)
 
void detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), float markerSizeMeters=-1, bool setYPerperdicular=false) throw (cv::Exception)
 
void detectRectangles (const cv::Mat &thresImg, vector< std::vector< cv::Point2f > > &candidates)
 
const vector< std::vector< cv::Point2f > > & getCandidates ()
 
CornerRefinementMethod getCornerRefinementMethod () const
 
int getDesiredSpeed () const
 
cv::Ptr< MarkerLabelergetMarkerLabeler () throw (cv::Exception)
 
void getMinMaxSize (float &min, float &max)
 
Params getParams () const
 
const cv::Mat & getThresholdedImage ()
 
ThresholdMethods getThresholdMethod () const
 
void getThresholdParams (double &param1, double &param2) const
 
int getWarpSize () const
 
 MarkerDetector ()
 
void refineCandidateLines (MarkerCandidate &candidate, const cv::Mat &camMatrix, const cv::Mat &distCoeff)
 
void setCornerRefinementMethod (CornerRefinementMethod method, int val=-1)
 
void setDesiredSpeed (int val)
 
void setDictionary (std::string dict_type, float error_correction_rate=0) throw (cv::Exception)
 
void setDictionary (Dictionary::DICT_TYPES dict_type, float error_correction_rate=0) throw (cv::Exception)
 setDictionary Specifies the dictionary you want to use for marker decoding More...
 
void setMarkerLabeler (cv::Ptr< MarkerLabeler > detector) throw (cv::Exception)
 setMakerLabeler sets the labeler employed to analyze the squares and extract the inner binary code More...
 
void setMinMaxSize (float min=0.03, float max=0.5) throw (cv::Exception)
 
void setParams (Params p)
 
void setThresholdMethod (ThresholdMethods m)
 
void setThresholdParamRange (size_t r1=0, size_t r2=0)
 
void setThresholdParams (double param1, double param2)
 
void setWarpSize (int val) throw (cv::Exception)
 
void thresHold (int method, const cv::Mat &grey, cv::Mat &thresImg, double param1=-1, double param2=-1) throw (cv::Exception)
 
bool warp (cv::Mat &in, cv::Mat &out, cv::Size size, std::vector< cv::Point2f > points) throw (cv::Exception)
 
 ~MarkerDetector ()
 

Private Member Functions

void detectRectangles (vector< cv::Mat > &vimages, vector< MarkerCandidate > &candidates)
 
void distortPoints (vector< cv::Point2f > in, vector< cv::Point2f > &out, const cv::Mat &camMatrix, const cv::Mat &distCoeff)
 
void draw (cv::Mat out, const std::vector< Marker > &markers)
 
void drawAllContours (cv::Mat input, std::vector< std::vector< cv::Point > > &contours)
 
void drawApproxCurve (cv::Mat &in, std::vector< cv::Point > &approxCurve, cv::Scalar color)
 
void drawContour (cv::Mat &in, std::vector< cv::Point > &contour, cv::Scalar)
 
void findCornerMaxima (vector< cv::Point2f > &Corners, const cv::Mat &grey, int wsize)
 
cv::Point2f getCrossPoint (const cv::Point3f &line1, const cv::Point3f &line2)
 
void interpolate2Dline (const vector< cv::Point2f > &inPoints, cv::Point3f &outLine)
 
bool isInto (cv::Mat &contour, std::vector< cv::Point2f > &b)
 
template<typename T >
void joinVectors (vector< vector< T > > &vv, vector< T > &v, bool clearv=false)
 
int perimeter (std::vector< cv::Point2f > &a)
 
template<typename T >
void removeElements (vector< T > &vinout, const vector< bool > &toRemove)
 
bool warp_cylinder (cv::Mat &in, cv::Mat &out, cv::Size size, MarkerCandidate &mc) throw (cv::Exception)
 

Private Attributes

vector< std::vector< cv::Point2f > > _candidates
 
Params _params
 
cv::Mat grey
 
vector< cv::Mat > imagePyramid
 
cv::Ptr< MarkerLabelermarkerIdDetector
 
cv::Mat thres
 

Detailed Description

Main class for marker detection.

Definition at line 44 of file markerdetector.h.

Member Enumeration Documentation

Methods for corner refinement

Enumerator
NONE 
SUBPIX 
LINES 

Definition at line 50 of file markerdetector.h.

This set the type of thresholding methods available

Enumerator
FIXED_THRES 
ADPT_THRES 
CANNY 

Definition at line 55 of file markerdetector.h.

Constructor & Destructor Documentation

aruco::MarkerDetector::MarkerDetector ( )

See

Definition at line 50 of file markerdetector.cpp.

aruco::MarkerDetector::~MarkerDetector ( )

Definition at line 66 of file markerdetector.cpp.

Member Function Documentation

void aruco::MarkerDetector::adpt_threshold_multi ( const cv::Mat &  grey,
std::vector< cv::Mat > &  out,
double  param1,
double  param1_range,
double  param2,
double  param2_range = 0 
)

A

Definition at line 477 of file markerdetector.cpp.

std::vector< aruco::Marker > aruco::MarkerDetector::detect ( const cv::Mat &  input)
throw (cv::Exception
)

Detects the markers in the image passed

If you provide information about the camera parameters and the size of the marker, then, the extrinsics of the markers are detected

Parameters
inputinput color image
camMatrixintrinsic camera information.
distCoeffcamera distorsion coefficient. If set Mat() if is assumed no camera distorion
markerSizeMeterssize of the marker sides expressed in meters. If not specified this value, the extrinsics of the markers are not detected.
setYPerperdicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
Returns
vector with the detected markers

Definition at line 77 of file markerdetector.cpp.

std::vector< aruco::Marker > aruco::MarkerDetector::detect ( const cv::Mat &  input,
const CameraParameters camParams,
float  markerSizeMeters,
bool  setYPerperdicular = false 
)
throw (cv::Exception
)

Definition at line 83 of file markerdetector.cpp.

void aruco::MarkerDetector::detect ( const cv::Mat &  input,
std::vector< Marker > &  detectedMarkers,
CameraParameters  camParams,
float  markerSizeMeters = -1,
bool  setYPerperdicular = false 
)
throw (cv::Exception
)

Detects the markers in the image passed

If you provide information about the camera parameters and the size of the marker, then, the extrinsics of the markers are detected

Parameters
inputinput color image
detectedMarkersoutput vector with the markers detected
camParamsCamera parameters
markerSizeMeterssize of the marker sides expressed in meters
setYPerperdicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis

Definition at line 96 of file markerdetector.cpp.

void aruco::MarkerDetector::detect ( const cv::Mat &  input,
std::vector< Marker > &  detectedMarkers,
cv::Mat  camMatrix = cv::Mat(),
cv::Mat  distCoeff = cv::Mat(),
float  markerSizeMeters = -1,
bool  setYPerperdicular = false 
)
throw (cv::Exception
)

Detects the markers in the image passed

If you provide information about the camera parameters and the size of the marker, then, the extrinsics of the markers are detected

NOTE: be sure that the camera matrix is for this image size. If you do not know what I am talking about, use functions above and not this one

Parameters
inputinput color image
detectedMarkersoutput vector with the markers detected
camMatrixintrinsic camera information.
distCoeffcamera distorsion coefficient. If set Mat() if is assumed no camera distorion
markerSizeMeterssize of the marker sides expressed in meters
setYPerperdicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
void aruco::MarkerDetector::detectRectangles ( const cv::Mat &  thresImg,
vector< std::vector< cv::Point2f > > &  candidates 
)

Detection of candidates to be markers, i.e., rectangles. This function returns in candidates all the rectangles found in a thresolded image

Definition at line 317 of file markerdetector.cpp.

void aruco::MarkerDetector::detectRectangles ( vector< cv::Mat > &  vimages,
vector< MarkerCandidate > &  candidates 
)
private

Detection of candidates to be markers, i.e., rectangles. This function returns in candidates all the rectangles found in a thresolded image

for each contour, analyze if it is a paralelepiped likely to be the marker

sort the points in anti-clockwise order

remove these elements which corners are too close to each other

Definition at line 328 of file markerdetector.cpp.

void aruco::MarkerDetector::distortPoints ( vector< cv::Point2f >  in,
vector< cv::Point2f > &  out,
const cv::Mat &  camMatrix,
const cv::Mat &  distCoeff 
)
private

Definition at line 1017 of file markerdetector.cpp.

void aruco::MarkerDetector::draw ( cv::Mat  out,
const std::vector< Marker > &  markers 
)
private

Definition at line 1064 of file markerdetector.cpp.

void aruco::MarkerDetector::drawAllContours ( cv::Mat  input,
std::vector< std::vector< cv::Point > > &  contours 
)
private

Definition at line 1038 of file markerdetector.cpp.

void aruco::MarkerDetector::drawApproxCurve ( cv::Mat &  in,
std::vector< cv::Point > &  approxCurve,
cv::Scalar  color 
)
private

Definition at line 1052 of file markerdetector.cpp.

void aruco::MarkerDetector::drawContour ( cv::Mat &  in,
std::vector< cv::Point > &  contour,
cv::Scalar   
)
private

Definition at line 1046 of file markerdetector.cpp.

void aruco::MarkerDetector::findCornerMaxima ( vector< cv::Point2f > &  Corners,
const cv::Mat &  grey,
int  wsize 
)
private

Definition at line 1099 of file markerdetector.cpp.

const vector< std::vector< cv::Point2f > >& aruco::MarkerDetector::getCandidates ( )
inline

Returns a list candidates to be markers (rectangles), for which no valid id was found after calling detectRectangles

Definition at line 337 of file markerdetector.h.

CornerRefinementMethod aruco::MarkerDetector::getCornerRefinementMethod ( ) const
inline
Deprecated:

Definition at line 234 of file markerdetector.h.

Point2f aruco::MarkerDetector::getCrossPoint ( const cv::Point3f &  line1,
const cv::Point3f &  line2 
)
private

Definition at line 994 of file markerdetector.cpp.

int aruco::MarkerDetector::getDesiredSpeed ( ) const
inline
Deprecated:

Definition at line 270 of file markerdetector.h.

cv::Ptr<MarkerLabeler> aruco::MarkerDetector::getMarkerLabeler ( )
throw (cv::Exception
)
inline

Definition at line 301 of file markerdetector.h.

void aruco::MarkerDetector::getMinMaxSize ( float &  min,
float &  max 
)
inline
Deprecated:
use setParams() and getParams() reads the min and max sizes employed
Parameters
minoutput size of the contour to consider a possible marker as valid (0,1]
maxoutput size of the contour to consider a possible marker as valid [0,1)

Definition at line 258 of file markerdetector.h.

Params aruco::MarkerDetector::getParams ( ) const
inline

Returns operating params

Definition at line 155 of file markerdetector.h.

const cv::Mat& aruco::MarkerDetector::getThresholdedImage ( )
inline

Returns a reference to the internal image thresholded. It is for visualization purposes and to adjust manually the parameters

Definition at line 182 of file markerdetector.h.

ThresholdMethods aruco::MarkerDetector::getThresholdMethod ( ) const
inline

Returns the current threshold method

Definition at line 193 of file markerdetector.h.

void aruco::MarkerDetector::getThresholdParams ( double &  param1,
double &  param2 
) const
inline
Deprecated:
use setParams() and getParams() Set the parameters of the threshold method We are currently using the Adptive threshold ee opencv doc of adaptiveThreshold for more info param1: blockSize of the pixel neighborhood that is used to calculate a threshold value for the pixel param2: The constant subtracted from the mean or weighted mean

Definition at line 220 of file markerdetector.h.

int aruco::MarkerDetector::getWarpSize ( ) const
inline
Deprecated:
use setParams() and getParams()

Definition at line 283 of file markerdetector.h.

void aruco::MarkerDetector::interpolate2Dline ( const vector< cv::Point2f > &  inPoints,
cv::Point3f &  outLine 
)
private

Definition at line 940 of file markerdetector.cpp.

bool aruco::MarkerDetector::isInto ( cv::Mat &  contour,
std::vector< cv::Point2f > &  b 
)
private

Definition at line 831 of file markerdetector.cpp.

template<typename T >
void aruco::MarkerDetector::joinVectors ( vector< vector< T > > &  vv,
vector< T > &  v,
bool  clearv = false 
)
inlineprivate

Definition at line 417 of file markerdetector.h.

int aruco::MarkerDetector::perimeter ( std::vector< cv::Point2f > &  a)
private

Definition at line 844 of file markerdetector.cpp.

void aruco::MarkerDetector::refineCandidateLines ( MarkerDetector::MarkerCandidate candidate,
const cv::Mat &  camMatrix,
const cv::Mat &  distCoeff 
)

Refine MarkerCandidate Corner using LINES method

Parameters
candidatecandidate to refine corners

Definition at line 861 of file markerdetector.cpp.

template<typename T >
void aruco::MarkerDetector::removeElements ( vector< T > &  vinout,
const vector< bool > &  toRemove 
)
inlineprivate

Given a vector vinout with elements and a boolean vector indicating the lements from it to remove, this function remove the elements

Parameters
vinout
toRemove

Definition at line 393 of file markerdetector.h.

void aruco::MarkerDetector::setCornerRefinementMethod ( CornerRefinementMethod  method,
int  val = -1 
)
inline
Deprecated:
use setParams() and getParams() Sets the method for corner refinement When using SUBPIX, the second value indicates the window size in which search is done. Default value is 5

Definition at line 231 of file markerdetector.h.

void aruco::MarkerDetector::setDesiredSpeed ( int  val)
inline
Deprecated:
Is now null

Definition at line 267 of file markerdetector.h.

void aruco::MarkerDetector::setDictionary ( std::string  dict_type,
float  error_correction_rate = 0 
)
throw (cv::Exception
)

Sets the dictionary to be employed. You can choose:ARUCO,//original aruco dictionary. By default ARUCO_MIP_25h7, ARUCO_MIP_16h3, ARUCO_MIP_36h12, **** recommended ARTAG,// ARTOOLKITPLUS, ARTOOLKITPLUSBCH,// TAG16h5,TAG25h7,TAG25h9,TAG36h11,TAG36h10//APRIL TAGS DICIONARIES

void aruco::MarkerDetector::setDictionary ( Dictionary::DICT_TYPES  dict_type,
float  error_correction_rate = 0 
)
throw (cv::Exception
)

setDictionary Specifies the dictionary you want to use for marker decoding

Parameters
dict_typedictionary employed for decoding markers
See also
Dictionary
Parameters
error_correction_ratevalue indicating the correction error allowed. Is in range [0,1]. 0 means no correction at all. So an erroneous bit will result in discarding the marker. 1, mean full correction. The maximum number of bits that can be corrected depends on each ditionary. We recommend using values from 0 to 0.5. (in general, this will allow up to 3 bits or correction).

Definition at line 1151 of file markerdetector.cpp.

void aruco::MarkerDetector::setMarkerLabeler ( cv::Ptr< MarkerLabeler detector)
throw (cv::Exception
)

setMakerLabeler sets the labeler employed to analyze the squares and extract the inner binary code


Methods you may not need

Thesde methods do the hard work. They have been set public in case you want to do customizations

Parameters
detector

Definition at line 1145 of file markerdetector.cpp.

void aruco::MarkerDetector::setMinMaxSize ( float  min = 0.03,
float  max = 0.5 
)
throw (cv::Exception
)
inline
Deprecated:
use setParams() and getParams() Specifies the min and max sizes of the markers as a fraction of the image size. By size we mean the maximum of cols and rows.
Parameters
minsize of the contour to consider a possible marker as valid (0,1]
maxsize of the contour to consider a possible marker as valid [0,1)

Definition at line 243 of file markerdetector.h.

void aruco::MarkerDetector::setParams ( Params  p)
inline

Sets operating params

Definition at line 152 of file markerdetector.h.

void aruco::MarkerDetector::setThresholdMethod ( ThresholdMethods  m)
inline
Deprecated:
use setParams() and getParams() Sets the threshold method

Definition at line 190 of file markerdetector.h.

void aruco::MarkerDetector::setThresholdParamRange ( size_t  r1 = 0,
size_t  r2 = 0 
)
inline
Deprecated:
use setParams() and getParams() Allows for a parallel search of several values of the param1 simultaneously (in different threads) The param r1 the indicates how many values around the current value of param1 are evaluated. In other words if r1>0, param1 is searched in range [param1- r1 ,param1+ r1 ]

r2 unused yet. Added in case of future need.

Definition at line 212 of file markerdetector.h.

void aruco::MarkerDetector::setThresholdParams ( double  param1,
double  param2 
)
inline
Deprecated:
use setParams() and getParams() Set the parameters of the threshold method We are currently using the Adptive threshold ee opencv doc of adaptiveThreshold for more info
Parameters
param1blockSize of the pixel neighborhood that is used to calculate a threshold value for the pixel
param2The constant subtracted from the mean or weighted mean

Definition at line 200 of file markerdetector.h.

void aruco::MarkerDetector::setWarpSize ( int  val)
throw (cv::Exception
)
inline
Deprecated:
use setParams() and getParams() Specifies the size for the canonical marker image. A big value makes the detection slower than a small value. Minimun value is 10. Default value is 56.

Definition at line 276 of file markerdetector.h.

void aruco::MarkerDetector::thresHold ( int  method,
const cv::Mat &  grey,
cv::Mat &  thresImg,
double  param1 = -1,
double  param2 = -1 
)
throw (cv::Exception
)

Thesholds the passed image with the specified method.

Definition at line 526 of file markerdetector.cpp.

bool aruco::MarkerDetector::warp ( cv::Mat &  in,
cv::Mat &  out,
cv::Size  size,
std::vector< cv::Point2f >  points 
)
throw (cv::Exception
)

Given the iput image with markers, creates an output image with it in the canonical position

Parameters
ininput image
outimage with the marker
sizeof out
points4 corners of the marker in the image in
Returns
true if the operation succeed

Definition at line 568 of file markerdetector.cpp.

bool aruco::MarkerDetector::warp_cylinder ( cv::Mat &  in,
cv::Mat &  out,
cv::Size  size,
MarkerCandidate mc 
)
throw (cv::Exception
)
private

Definition at line 683 of file markerdetector.cpp.

Member Data Documentation

vector< std::vector< cv::Point2f > > aruco::MarkerDetector::_candidates
private

Definition at line 369 of file markerdetector.h.

Params aruco::MarkerDetector::_params
private

Definition at line 367 of file markerdetector.h.

cv::Mat aruco::MarkerDetector::grey
private

Definition at line 371 of file markerdetector.h.

vector<cv::Mat > aruco::MarkerDetector::imagePyramid
private

Definition at line 425 of file markerdetector.h.

cv::Ptr<MarkerLabeler> aruco::MarkerDetector::markerIdDetector
private

Definition at line 373 of file markerdetector.h.

cv::Mat aruco::MarkerDetector::thres
private

Definition at line 371 of file markerdetector.h.


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


tuw_aruco
Author(s): Lukas Pfeifhofer
autogenerated on Mon Jun 10 2019 15:41:03