Classes | Public Types | Public Member Functions | Static 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
 

Public Types

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

Public Member Functions

void detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), float markerSizeMeters=-1, bool setYPerpendicular=true) 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 setYPerpendicular=true) throw (cv::Exception)
 
void detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, CameraParameters camParams, float markerSizeMeters=-1, bool setYPerpendicular=true) throw (cv::Exception)
 
void detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, CameraParameters camParams, float markerSizeMeters=-1, bool setYPerpendicular=true) throw (cv::Exception)
 
void detectRectangles (const cv::Mat &thresImg, vector< std::vector< cv::Point2f > > &candidates)
 
void detectRectangles (const cv::Mat &thresImg, vector< std::vector< cv::Point2f > > &candidates)
 
void enableErosion (bool enable)
 
void enableErosion (bool enable)
 
const vector< std::vector< cv::Point2f > > & getCandidates ()
 
const vector< std::vector< cv::Point2f > > & getCandidates ()
 
CornerRefinementMethod getCornerRefinementMethod () const
 
CornerRefinementMethod getCornerRefinementMethod () const
 
int getDesiredSpeed () const
 
int getDesiredSpeed () const
 
void getMinMaxSize (float &min, float &max)
 
void getMinMaxSize (float &min, float &max)
 
const cv::Mat & getThresholdedImage ()
 
const cv::Mat & getThresholdedImage ()
 
ThresholdMethods getThresholdMethod () const
 
ThresholdMethods getThresholdMethod () const
 
void getThresholdParams (double &param1, double &param2) const
 
void getThresholdParams (double &param1, double &param2) const
 
 MarkerDetector ()
 
 MarkerDetector ()
 
void pyrDown (unsigned int level)
 
void pyrDown (unsigned int level)
 
void refineCandidateLines (MarkerCandidate &candidate)
 
void refineCandidateLines (MarkerCandidate &candidate)
 
void setCornerRefinementMethod (CornerRefinementMethod method)
 
void setCornerRefinementMethod (CornerRefinementMethod method)
 
void setDesiredSpeed (int val)
 
void setDesiredSpeed (int val)
 
void setMakerDetectorFunction (int(*markerdetector_func)(const cv::Mat &in, int &nRotations))
 
void setMakerDetectorFunction (int(*markerdetector_func)(const cv::Mat &in, int &nRotations))
 
void setMinMaxSize (float min=0.03, float max=0.5) throw (cv::Exception)
 
void setMinMaxSize (float min=0.03, float max=0.5) throw (cv::Exception)
 
void setThresholdMethod (ThresholdMethods m)
 
void setThresholdMethod (ThresholdMethods m)
 
void setThresholdParams (double param1, double param2)
 
void setThresholdParams (double param1, double param2)
 
void thresHold (int method, const cv::Mat &grey, cv::Mat &thresImg, double param1=-1, double param2=-1) 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)
 
bool warp (cv::Mat &in, cv::Mat &out, cv::Size size, std::vector< cv::Point2f > points) throw (cv::Exception)
 
 ~MarkerDetector ()
 
 ~MarkerDetector ()
 

Static Public Member Functions

static void glGetProjectionMatrix (CameraParameters &CamMatrix, cv::Size orgImgSize, cv::Size size, double proj_matrix[16], double gnear, double gfar, bool invert=false) throw (cv::Exception)
 
static void glGetProjectionMatrix (CameraParameters &CamMatrix, cv::Size orgImgSize, cv::Size size, double proj_matrix[16], double gnear, double gfar, bool invert=false) throw (cv::Exception)
 

Private Member Functions

void detectRectangles (const cv::Mat &thresImg, vector< MarkerCandidate > &candidates)
 
void detectRectangles (const cv::Mat &thresImg, vector< MarkerCandidate > &candidates)
 
void draw (cv::Mat out, const std::vector< Marker > &markers)
 
void draw (cv::Mat out, const std::vector< Marker > &markers)
 
void drawAllContours (cv::Mat input, std::vector< std::vector< cv::Point > > &contours)
 
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 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 drawContour (cv::Mat &in, std::vector< cv::Point > &contour, cv::Scalar)
 
void findBestCornerInRegion_harris (const cv::Mat &grey, vector< cv::Point2f > &Corners, int blockSize)
 
void findBestCornerInRegion_harris (const cv::Mat &grey, vector< cv::Point2f > &Corners, int blockSize)
 
cv::Point2f getCrossPoint (const cv::Point3f &line1, const cv::Point3f &line2)
 
cv::Point2f getCrossPoint (const cv::Point3f &line1, const cv::Point3f &line2)
 
void interpolate2Dline (const vector< cv::Point > &inPoints, cv::Point3f &outLine)
 
void interpolate2Dline (const vector< cv::Point > &inPoints, cv::Point3f &outLine)
 
bool isInto (cv::Mat &contour, std::vector< cv::Point2f > &b)
 
bool isInto (cv::Mat &contour, std::vector< cv::Point2f > &b)
 
int perimeter (std::vector< cv::Point2f > &a)
 
int perimeter (std::vector< cv::Point2f > &a)
 
template<typename T >
void removeElements (vector< T > &vinout, const vector< bool > &toRemove)
 
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 )
 
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
 
CornerRefinementMethod _cornerMethod
 
bool _doErosion
 
bool _enableCylinderWarp
 
int _markerWarpSize
 
float _maxSize
 
float _minSize
 
int _speed
 
ThresholdMethods _thresMethod
 
double _thresParam1
 
double _thresParam2
 
cv::Mat grey
 
int(* markerIdDetector_ptrfunc )(const cv::Mat &in, int &nRotations)
 
int pyrdown_level
 
cv::Mat reduced
 
cv::Mat thres
 
cv::Mat thres2
 

Detailed Description

Main class for marker detection.

Definition at line 44 of file aruco/include/aruco/markerdetector.h.

Member Enumeration Documentation

Methods for corner refinement

Enumerator
NONE 
HARRIS 
SUBPIX 
LINES 
NONE 
HARRIS 
SUBPIX 
LINES 

Definition at line 144 of file aruco/include/aruco/markerdetector.h.

Methods for corner refinement

Enumerator
NONE 
HARRIS 
SUBPIX 
LINES 
NONE 
HARRIS 
SUBPIX 
LINES 

Definition at line 144 of file old/aruco/include/aruco/markerdetector.h.

This set the type of thresholding methods available

Enumerator
FIXED_THRES 
ADPT_THRES 
CANNY 
FIXED_THRES 
ADPT_THRES 
CANNY 

Definition at line 100 of file old/aruco/include/aruco/markerdetector.h.

This set the type of thresholding methods available

Enumerator
FIXED_THRES 
ADPT_THRES 
CANNY 
FIXED_THRES 
ADPT_THRES 
CANNY 

Definition at line 100 of file aruco/include/aruco/markerdetector.h.

Constructor & Destructor Documentation

aruco::MarkerDetector::MarkerDetector ( )

See

Definition at line 47 of file aruco/src/aruco/markerdetector.cpp.

aruco::MarkerDetector::~MarkerDetector ( )

Definition at line 68 of file aruco/src/aruco/markerdetector.cpp.

aruco::MarkerDetector::MarkerDetector ( )

See

aruco::MarkerDetector::~MarkerDetector ( )

Member Function Documentation

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  setYPerpendicular = true 
)
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
camMatrixintrinsic camera information.
distCoeffcamera distorsion coefficient. If set Mat() if is assumed no camera distorion
markerSizeMeterssize of the marker sides expressed in meters
setYPerpendicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
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  setYPerpendicular = true 
)
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
camMatrixintrinsic camera information.
distCoeffcamera distorsion coefficient. If set Mat() if is assumed no camera distorion
markerSizeMeterssize of the marker sides expressed in meters
setYPerpendicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis
void aruco::MarkerDetector::detect ( const cv::Mat &  input,
std::vector< Marker > &  detectedMarkers,
CameraParameters  camParams,
float  markerSizeMeters = -1,
bool  setYPerpendicular = true 
)
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
setYPerpendicularIf set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis

Definition at line 108 of file aruco/src/aruco/markerdetector.cpp.

void aruco::MarkerDetector::detect ( const cv::Mat &  input,
std::vector< Marker > &  detectedMarkers,
CameraParameters  camParams,
float  markerSizeMeters = -1,
bool  setYPerpendicular = true 
)
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
setYPerpendicularIf 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 262 of file aruco/src/aruco/markerdetector.cpp.

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

void aruco::MarkerDetector::detectRectangles ( const cv::Mat &  thresImg,
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 whise corners are too close to each other

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

sort the points in anti-clockwise order

remove these elements whise corners are too close to each other

Definition at line 272 of file aruco/src/aruco/markerdetector.cpp.

void aruco::MarkerDetector::detectRectangles ( const cv::Mat &  thresImg,
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

void aruco::MarkerDetector::draw ( cv::Mat  out,
const std::vector< Marker > &  markers 
)
private
void aruco::MarkerDetector::draw ( cv::Mat  out,
const std::vector< Marker > &  markers 
)
private
void aruco::MarkerDetector::drawAllContours ( cv::Mat  input,
std::vector< std::vector< cv::Point > > &  contours 
)
private
void aruco::MarkerDetector::drawAllContours ( cv::Mat  input,
std::vector< std::vector< cv::Point > > &  contours 
)
private
void aruco::MarkerDetector::drawApproxCurve ( cv::Mat &  in,
std::vector< cv::Point > &  approxCurve,
cv::Scalar  color 
)
private
void aruco::MarkerDetector::drawApproxCurve ( cv::Mat &  in,
std::vector< cv::Point > &  approxCurve,
cv::Scalar  color 
)
private
void aruco::MarkerDetector::drawContour ( cv::Mat &  in,
std::vector< cv::Point > &  contour,
cv::Scalar   
)
private
void aruco::MarkerDetector::drawContour ( cv::Mat &  in,
std::vector< cv::Point > &  contour,
cv::Scalar   
)
private
void aruco::MarkerDetector::enableErosion ( bool  enable)
inline

Enables/Disables erosion process that is REQUIRED for chessboard like boards. By default, this property is enabled

Definition at line 173 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::enableErosion ( bool  enable)
inline

Enables/Disables erosion process that is REQUIRED for chessboard like boards. By default, this property is enabled

Definition at line 173 of file aruco/include/aruco/markerdetector.h.

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

Definition at line 728 of file aruco/src/aruco/markerdetector.cpp.

void aruco::MarkerDetector::findBestCornerInRegion_harris ( const cv::Mat &  grey,
vector< cv::Point2f > &  Corners,
int  blockSize 
)
private
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 233 of file aruco/include/aruco/markerdetector.h.

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 233 of file old/aruco/include/aruco/markerdetector.h.

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

Definition at line 152 of file aruco/include/aruco/markerdetector.h.

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

Definition at line 152 of file old/aruco/include/aruco/markerdetector.h.

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

Definition at line 880 of file aruco/src/aruco/markerdetector.cpp.

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

Definition at line 185 of file old/aruco/include/aruco/markerdetector.h.

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

Definition at line 185 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::getMinMaxSize ( float &  min,
float &  max 
)
inline

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 168 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::getMinMaxSize ( float &  min,
float &  max 
)
inline

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 168 of file old/aruco/include/aruco/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 139 of file old/aruco/include/aruco/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 139 of file aruco/include/aruco/markerdetector.h.

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

Returns the current threshold method

Definition at line 111 of file aruco/include/aruco/markerdetector.h.

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

Returns the current threshold method

Definition at line 111 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::getThresholdParams ( double &  param1,
double &  param2 
) const
inline

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 130 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::getThresholdParams ( double &  param1,
double &  param2 
) const
inline

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 130 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::glGetProjectionMatrix ( CameraParameters CamMatrix,
cv::Size  orgImgSize,
cv::Size  size,
double  proj_matrix[16],
double  gnear,
double  gfar,
bool  invert = false 
)
throw (cv::Exception
)
static

DEPRECATED!!! Use the member function in CameraParameters

Given the intrinsic camera parameters returns the GL_PROJECTION matrix for opengl. PLease NOTE that when using OpenGL, it is assumed no camera distorsion! So, if it is not true, you should have undistor image

Parameters
CamMatrixarameters of the camera specified.
orgImgSizesize of the original image
sizeof the image/window where to render (can be different from the real camera image). Please not that it must be related to CamMatrix
proj_matrixoutput projection matrix to give to opengl
gnear,gfarvisible rendering range
invertindicates if the output projection matrix has to yield a horizontally inverted image because image data has not been stored in the order of glDrawPixels: bottom-to-top.

Definition at line 990 of file aruco/src/aruco/markerdetector.cpp.

static void aruco::MarkerDetector::glGetProjectionMatrix ( CameraParameters CamMatrix,
cv::Size  orgImgSize,
cv::Size  size,
double  proj_matrix[16],
double  gnear,
double  gfar,
bool  invert = false 
)
throw (cv::Exception
)
static

DEPRECATED!!! Use the member function in CameraParameters

Given the intrinsic camera parameters returns the GL_PROJECTION matrix for opengl. PLease NOTE that when using OpenGL, it is assumed no camera distorsion! So, if it is not true, you should have undistor image

Parameters
CamMatrixarameters of the camera specified.
orgImgSizesize of the original image
sizeof the image/window where to render (can be different from the real camera image). Please not that it must be related to CamMatrix
proj_matrixoutput projection matrix to give to opengl
gnear,gfarvisible rendering range
invertindicates if the output projection matrix has to yield a horizontally inverted image because image data has not been stored in the order of glDrawPixels: bottom-to-top.
void aruco::MarkerDetector::interpolate2Dline ( const vector< cv::Point > &  inPoints,
cv::Point3f &  outLine 
)
private
void aruco::MarkerDetector::interpolate2Dline ( const vector< cv::Point > &  inPoints,
cv::Point3f &  outLine 
)
private
bool aruco::MarkerDetector::isInto ( cv::Mat &  contour,
std::vector< cv::Point2f > &  b 
)
private
bool aruco::MarkerDetector::isInto ( cv::Mat &  contour,
std::vector< cv::Point2f > &  b 
)
private
int aruco::MarkerDetector::perimeter ( std::vector< cv::Point2f > &  a)
private
int aruco::MarkerDetector::perimeter ( std::vector< cv::Point2f > &  a)
private
void aruco::MarkerDetector::pyrDown ( unsigned int  level)
inline

Use an smaller version of the input image for marker detection. If your marker is small enough, you can employ an smaller image to perform the detection without noticeable reduction in the precision. Internally, we are performing a pyrdown operation

Parameters
levelnumber of times the image size is divided by 2. Internally, we are performing a pyrdown.

Definition at line 214 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::pyrDown ( unsigned int  level)
inline

Use an smaller version of the input image for marker detection. If your marker is small enough, you can employ an smaller image to perform the detection without noticeable reduction in the precision. Internally, we are performing a pyrdown operation

Parameters
levelnumber of times the image size is divided by 2. Internally, we are performing a pyrdown.

Definition at line 214 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::refineCandidateLines ( MarkerCandidate candidate)

Refine MarkerCandidate Corner using LINES method

Parameters
candidatecandidate to refine corners
void aruco::MarkerDetector::refineCandidateLines ( MarkerDetector::MarkerCandidate candidate)

Refine MarkerCandidate Corner using LINES method

Parameters
candidatecandidate to refine corners

Definition at line 764 of file aruco/src/aruco/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 331 of file old/aruco/include/aruco/markerdetector.h.

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 331 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setCornerRefinementMethod ( CornerRefinementMethod  method)
inline

Definition at line 147 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setCornerRefinementMethod ( CornerRefinementMethod  method)
inline

Definition at line 147 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setDesiredSpeed ( int  val)

Specifies a value to indicate the required speed for the internal processes. If you need maximum speed (at the cost of a lower detection rate), use the value 3, If you rather a more precise and slow detection, set it to 0.

Actually, the main differences are that in highspeed mode, we employ setCornerRefinementMethod(NONE) and internally, we use a small canonical image to detect the marker. In low speed mode, we use setCornerRefinementMethod(HARRIS) and a bigger size for the canonical marker image

void aruco::MarkerDetector::setDesiredSpeed ( int  val)

Specifies a value to indicate the required speed for the internal processes. If you need maximum speed (at the cost of a lower detection rate), use the value 3, If you rather a more precise and slow detection, set it to 0.

Actually, the main differences are that in highspeed mode, we employ setCornerRefinementMethod(NONE) and internally, we use a small canonical image to detect the marker. In low speed mode, we use setCornerRefinementMethod(HARRIS) and a bigger size for the canonical marker image

Definition at line 79 of file aruco/src/aruco/markerdetector.cpp.

void aruco::MarkerDetector::setMakerDetectorFunction ( int(*)(const cv::Mat &in, int &nRotations)  markerdetector_func)
inline

Allows to specify the function that identifies a marker. Therefore, you can create your own type of markers different from these employed by default in the library. The marker function must have the following structure:

int myMarkerIdentifier(const cv::Mat &in,int &nRotations);

The marker function receives the image 'in' with the region that migh contain one of your markers. These are the rectangular regions with black in the image.

As output your marker function must indicate the following information. First, the output parameter nRotations must indicate how many times the marker must be rotated clockwise 90 deg to be in its ideal position. (The way you would see it when you print it). This is employed to know always which is the corner that acts as reference system. Second, the function must return -1 if the image does not contains one of your markers, and its id otherwise.

Definition at line 204 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setMakerDetectorFunction ( int(*)(const cv::Mat &in, int &nRotations)  markerdetector_func)
inline

Allows to specify the function that identifies a marker. Therefore, you can create your own type of markers different from these employed by default in the library. The marker function must have the following structure:

int myMarkerIdentifier(const cv::Mat &in,int &nRotations);

The marker function receives the image 'in' with the region that migh contain one of your markers. These are the rectangular regions with black in the image.

As output your marker function must indicate the following information. First, the output parameter nRotations must indicate how many times the marker must be rotated clockwise 90 deg to be in its ideal position. (The way you would see it when you print it). This is employed to know always which is the corner that acts as reference system. Second, the function must return -1 if the image does not contains one of your markers, and its id otherwise.

Definition at line 204 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setMinMaxSize ( float  min = 0.03,
float  max = 0.5 
)
throw (cv::Exception
)

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)
void aruco::MarkerDetector::setMinMaxSize ( float  min = 0.03,
float  max = 0.5 
)
throw (cv::Exception
)

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 1004 of file aruco/src/aruco/markerdetector.cpp.

void aruco::MarkerDetector::setThresholdMethod ( ThresholdMethods  m)
inline

Sets the threshold method

Definition at line 106 of file old/aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setThresholdMethod ( ThresholdMethods  m)
inline

Sets the threshold method

Definition at line 106 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setThresholdParams ( double  param1,
double  param2 
)
inline

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 120 of file aruco/include/aruco/markerdetector.h.

void aruco::MarkerDetector::setThresholdParams ( double  param1,
double  param2 
)
inline

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 120 of file old/aruco/include/aruco/markerdetector.h.

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

Methods you may not need

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

Thesholds the passed image with the specified method.

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

Methods you may not need

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

Thesholds the passed image with the specified method.

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
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
bool aruco::MarkerDetector::warp_cylinder ( cv::Mat &  in,
cv::Mat &  out,
cv::Size  size,
MarkerCandidate mc 
)
throw (cv::Exception
)
private
bool aruco::MarkerDetector::warp_cylinder ( cv::Mat &  in,
cv::Mat &  out,
cv::Size  size,
MarkerCandidate mc 
)
throw (cv::Exception
)
private

Member Data Documentation

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

Definition at line 291 of file aruco/include/aruco/markerdetector.h.

CornerRefinementMethod aruco::MarkerDetector::_cornerMethod
private

Definition at line 283 of file aruco/include/aruco/markerdetector.h.

bool aruco::MarkerDetector::_doErosion
private

Definition at line 289 of file aruco/include/aruco/markerdetector.h.

bool aruco::MarkerDetector::_enableCylinderWarp
private

Definition at line 271 of file aruco/include/aruco/markerdetector.h.

int aruco::MarkerDetector::_markerWarpSize
private

Definition at line 288 of file aruco/include/aruco/markerdetector.h.

float aruco::MarkerDetector::_maxSize
private

Definition at line 285 of file aruco/include/aruco/markerdetector.h.

float aruco::MarkerDetector::_minSize
private

Definition at line 285 of file aruco/include/aruco/markerdetector.h.

int aruco::MarkerDetector::_speed
private

Definition at line 287 of file aruco/include/aruco/markerdetector.h.

ThresholdMethods aruco::MarkerDetector::_thresMethod
private

Definition at line 279 of file aruco/include/aruco/markerdetector.h.

double aruco::MarkerDetector::_thresParam1
private

Definition at line 281 of file aruco/include/aruco/markerdetector.h.

double aruco::MarkerDetector::_thresParam2
private

Definition at line 281 of file aruco/include/aruco/markerdetector.h.

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

Definition at line 295 of file aruco/include/aruco/markerdetector.h.

int(* aruco::MarkerDetector::markerIdDetector_ptrfunc)(const cv::Mat &in, int &nRotations)
private

Definition at line 297 of file aruco/include/aruco/markerdetector.h.

int aruco::MarkerDetector::pyrdown_level
private

Definition at line 293 of file aruco/include/aruco/markerdetector.h.

cv::Mat aruco::MarkerDetector::reduced
private

Definition at line 295 of file aruco/include/aruco/markerdetector.h.

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

Definition at line 295 of file aruco/include/aruco/markerdetector.h.

cv::Mat aruco::MarkerDetector::thres2
private

Definition at line 295 of file aruco/include/aruco/markerdetector.h.


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


lidar_camera_calibration
Author(s):
autogenerated on Sat Feb 6 2021 03:39:37