Main class for marker detection.
More...
#include <markerdetector.h>
|
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 | detect (const cv::Mat &input, std::vector< Marker > &detectedMarkers, CameraParameters camParams, float markerSizeMeters=-1, bool setYPerperdicular=false) throw (cv::Exception) |
|
void | detectRectangles (const cv::Mat &thresImg, vector< std::vector< cv::Point2f > > &candidates) |
|
void | enableErosion (bool enable) |
|
void | enableLockedCornersMethod (bool enable) |
|
const vector< std::vector< cv::Point2f > > & | getCandidates () |
|
CornerRefinementMethod | getCornerRefinementMethod () const |
|
int | getDesiredSpeed () const |
|
void | getMinMaxSize (float &min, float &max) |
|
const cv::Mat & | getThresholdedImage () |
|
ThresholdMethods | getThresholdMethod () const |
|
void | getThresholdParams (double ¶m1, double ¶m2) const |
|
int | getWarpSize () const |
|
| MarkerDetector () |
|
void | pyrDown (unsigned int level) |
|
void | refineCandidateLines (MarkerCandidate &candidate, const cv::Mat &camMatrix, const cv::Mat &distCoeff) |
|
void | setCornerRefinementMethod (CornerRefinementMethod method) |
|
void | setDesiredSpeed (int val) |
|
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 | 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 () |
|
|
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) |
|
|
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 | findBestCornerInRegion_harris (const cv::Mat &grey, vector< cv::Point2f > &Corners, int blockSize) |
|
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) |
|
Main class for marker detection.
Definition at line 43 of file markerdetector.h.
◆ CornerRefinementMethod
Methods for corner refinement
Enumerator |
---|
NONE | |
HARRIS | |
SUBPIX | |
LINES | |
Definition at line 162 of file markerdetector.h.
◆ ThresholdMethods
This set the type of thresholding methods available
Enumerator |
---|
FIXED_THRES | |
ADPT_THRES | |
CANNY | |
Definition at line 103 of file markerdetector.h.
◆ MarkerDetector()
aruco::MarkerDetector::MarkerDetector |
( |
| ) |
|
◆ ~MarkerDetector()
aruco::MarkerDetector::~MarkerDetector |
( |
| ) |
|
◆ detect() [1/2]
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
- Parameters
-
input | input color image |
detectedMarkers | output vector with the markers detected |
camMatrix | intrinsic camera information. |
distCoeff | camera distorsion coefficient. If set Mat() if is assumed no camera distorion |
markerSizeMeters | size of the marker sides expressed in meters |
setYPerperdicular | If set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis |
◆ detect() [2/2]
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
-
input | input color image |
detectedMarkers | output vector with the markers detected |
camParams | Camera parameters |
markerSizeMeters | size of the marker sides expressed in meters |
setYPerperdicular | If set the Y axis will be perpendicular to the surface. Otherwise, it will be the Z axis |
Definition at line 108 of file markerdetector.cpp.
◆ detectRectangles() [1/2]
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 261 of file markerdetector.cpp.
◆ detectRectangles() [2/2]
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 272 of file markerdetector.cpp.
◆ distortPoints()
void aruco::MarkerDetector::distortPoints |
( |
vector< cv::Point2f > |
in, |
|
|
vector< cv::Point2f > & |
out, |
|
|
const cv::Mat & |
camMatrix, |
|
|
const cv::Mat & |
distCoeff |
|
) |
| |
|
private |
◆ draw()
void aruco::MarkerDetector::draw |
( |
cv::Mat |
out, |
|
|
const std::vector< Marker > & |
markers |
|
) |
| |
|
private |
◆ drawAllContours()
void aruco::MarkerDetector::drawAllContours |
( |
cv::Mat |
input, |
|
|
std::vector< std::vector< cv::Point > > & |
contours |
|
) |
| |
|
private |
◆ drawApproxCurve()
void aruco::MarkerDetector::drawApproxCurve |
( |
cv::Mat & |
in, |
|
|
std::vector< cv::Point > & |
approxCurve, |
|
|
cv::Scalar |
color |
|
) |
| |
|
private |
◆ drawContour()
void aruco::MarkerDetector::drawContour |
( |
cv::Mat & |
in, |
|
|
std::vector< cv::Point > & |
contour, |
|
|
cv::Scalar |
|
|
) |
| |
|
private |
◆ enableErosion()
void aruco::MarkerDetector::enableErosion |
( |
bool |
enable | ) |
|
|
inline |
Deprecated!!!
Enables/Disables erosion process that is REQUIRED for chessboard like boards. By default, this property is enabled
Definition at line 192 of file markerdetector.h.
◆ enableLockedCornersMethod()
void aruco::MarkerDetector::enableLockedCornersMethod |
( |
bool |
enable | ) |
|
This method assumes that the markers may have some of its corners joined either to another marker in a chessboard like pattern) or to a rectangle. This is the case in which the subpixel refinement method in opencv work best.
Enabling this does not force you to use locked corners, normals markers will be detected also. However, when using locked corners, enabling this option will increase robustness in detection at the cost of higher computational time. , Note for developer: Enabling this option forces a call to findCornerMaxima
Definition at line 117 of file markerdetector.cpp.
◆ findBestCornerInRegion_harris()
void aruco::MarkerDetector::findBestCornerInRegion_harris |
( |
const cv::Mat & |
grey, |
|
|
vector< cv::Point2f > & |
Corners, |
|
|
int |
blockSize |
|
) |
| |
|
private |
◆ findCornerMaxima()
void aruco::MarkerDetector::findCornerMaxima |
( |
vector< cv::Point2f > & |
Corners, |
|
|
const cv::Mat & |
grey, |
|
|
int |
wsize |
|
) |
| |
|
private |
◆ getCandidates()
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 261 of file markerdetector.h.
◆ getCornerRefinementMethod()
◆ getCrossPoint()
Point2f aruco::MarkerDetector::getCrossPoint |
( |
const cv::Point3f & |
line1, |
|
|
const cv::Point3f & |
line2 |
|
) |
| |
|
private |
◆ getDesiredSpeed()
int aruco::MarkerDetector::getDesiredSpeed |
( |
| ) |
const |
|
inline |
◆ getMinMaxSize()
void aruco::MarkerDetector::getMinMaxSize |
( |
float & |
min, |
|
|
float & |
max |
|
) |
| |
|
inline |
reads the min and max sizes employed
- Parameters
-
min | output size of the contour to consider a possible marker as valid (0,1] |
max | output size of the contour to consider a possible marker as valid [0,1) |
Definition at line 182 of file markerdetector.h.
◆ getThresholdedImage()
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 159 of file markerdetector.h.
◆ getThresholdMethod()
◆ getThresholdParams()
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 150 of file markerdetector.h.
◆ getWarpSize()
int aruco::MarkerDetector::getWarpSize |
( |
| ) |
const |
|
inline |
◆ glGetProjectionMatrix()
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
-
CamMatrix | arameters of the camera specified. |
orgImgSize | size of the original image |
size | of the image/window where to render (can be different from the real camera image). Please not that it must be related to CamMatrix |
proj_matrix | output projection matrix to give to opengl |
gnear,gfar | visible rendering range |
invert | indicates 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 1001 of file markerdetector.cpp.
◆ interpolate2Dline()
void aruco::MarkerDetector::interpolate2Dline |
( |
const vector< cv::Point2f > & |
inPoints, |
|
|
cv::Point3f & |
outLine |
|
) |
| |
|
private |
◆ isInto()
bool aruco::MarkerDetector::isInto |
( |
cv::Mat & |
contour, |
|
|
std::vector< cv::Point2f > & |
b |
|
) |
| |
|
private |
◆ joinVectors()
template<typename T >
void aruco::MarkerDetector::joinVectors |
( |
vector< vector< T > > & |
vv, |
|
|
vector< T > & |
v, |
|
|
bool |
clearv = false |
|
) |
| |
|
inlineprivate |
◆ perimeter()
int aruco::MarkerDetector::perimeter |
( |
std::vector< cv::Point2f > & |
a | ) |
|
|
private |
◆ pyrDown()
void aruco::MarkerDetector::pyrDown |
( |
unsigned int |
level | ) |
|
|
inline |
Deprecated
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
-
level | number of times the image size is divided by 2. Internally, we are performing a pyrdown. |
Definition at line 242 of file markerdetector.h.
◆ refineCandidateLines()
◆ removeElements()
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
-
Definition at line 359 of file markerdetector.h.
◆ setCornerRefinementMethod()
◆ setDesiredSpeed()
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 80 of file markerdetector.cpp.
◆ setMakerDetectorFunction()
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 232 of file markerdetector.h.
◆ setMinMaxSize()
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
-
min | size of the contour to consider a possible marker as valid (0,1] |
max | size of the contour to consider a possible marker as valid [0,1) |
Definition at line 1015 of file markerdetector.cpp.
◆ setThresholdMethod()
◆ setThresholdParamRange()
void aruco::MarkerDetector::setThresholdParamRange |
( |
size_t |
r1 = 0 , |
|
|
size_t |
r2 = 0 |
|
) |
| |
|
inline |
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 130 of file markerdetector.h.
◆ setThresholdParams()
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
-
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 119 of file markerdetector.h.
◆ setWarpSize()
void aruco::MarkerDetector::setWarpSize |
( |
int |
val | ) |
|
throw | ( | cv::Exception |
| ) | | |
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 1033 of file markerdetector.cpp.
◆ thresHold()
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.
Definition at line 422 of file markerdetector.cpp.
◆ warp()
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
-
in | input image |
out | image with the marker |
size | of out |
points | 4 corners of the marker in the image in |
- Returns
- true if the operation succeed
Definition at line 464 of file markerdetector.cpp.
◆ warp_cylinder()
bool aruco::MarkerDetector::warp_cylinder |
( |
cv::Mat & |
in, |
|
|
cv::Mat & |
out, |
|
|
cv::Size |
size, |
|
|
MarkerCandidate & |
mc |
|
) |
| |
throw | ( | cv::Exception |
| ) | | |
|
private |
◆ _borderDistThres
float aruco::MarkerDetector::_borderDistThres |
|
private |
◆ _candidates
vector< std::vector< cv::Point2f > > aruco::MarkerDetector::_candidates |
|
private |
◆ _cornerMethod
◆ _markerWarpSize
int aruco::MarkerDetector::_markerWarpSize |
|
private |
◆ _maxSize
float aruco::MarkerDetector::_maxSize |
|
private |
◆ _minSize
float aruco::MarkerDetector::_minSize |
|
private |
◆ _speed
int aruco::MarkerDetector::_speed |
|
private |
◆ _thresMethod
◆ _thresParam1
double aruco::MarkerDetector::_thresParam1 |
|
private |
◆ _thresParam1_range
double aruco::MarkerDetector::_thresParam1_range |
|
private |
◆ _thresParam2
double aruco::MarkerDetector::_thresParam2 |
|
private |
◆ _useLockedCorners
bool aruco::MarkerDetector::_useLockedCorners |
|
private |
◆ grey
cv::Mat aruco::MarkerDetector::grey |
|
private |
◆ markerIdDetector_ptrfunc
int(* aruco::MarkerDetector::markerIdDetector_ptrfunc) (const cv::Mat &in, int &nRotations) |
|
private |
◆ thres
cv::Mat aruco::MarkerDetector::thres |
|
private |
The documentation for this class was generated from the following files: