All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines
Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
aruco::MarkerDetector Class Reference

Main class for marker detection. More...

#include <markerdetector.h>

List of all members.

Public Types

enum  ThresholdMethods { FIXED_THRES, ADPT_THRES, CANNY }

Public Member Functions

void detect (cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), float markerSizeMeters=-1) throw (cv::Exception)
void detect (cv::Mat &input, std::vector< Marker > &detectedMarkers, CameraParameters camParams=CameraParameters(), float markerSizeMeters=-1) throw (cv::Exception)
cv::Mat & getThresholdedImage ()
ThresholdMethods getThresholdMethod () const
void getThresholdParams (double &param1, double &param2) const
 MarkerDetector ()
void setThresholdMethod (ThresholdMethods m)
void setThresholdParams (double param1, double param2)
 ~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)

Private Member Functions

bool correctHammMarker (cv::Mat &bits)
void draw (cv::Mat out, const std::vector< Marker > &markers)
void drawAllContours (cv::Mat input)
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)
int getMarkerId (cv::Mat &in, int &nRotations)
int hammDistMarker (cv::Mat bits)
bool isInto (cv::Mat &contour, std::vector< cv::Point2f > &b)
int mat2id (cv::Mat &bits)
int perimeter (std::vector< cv::Point2f > &a)
template<typename T >
void printMat (cv::Mat M, std::string info="")
template<typename T >
void printMat (CvMat *M, std::string info="")
cv::Mat rotate (cv::Mat in)
void thresHold (int method, cv::Mat &grey, cv::Mat &out)
void warp (cv::Mat &in, cv::Mat &out, cv::Size size, std::vector< cv::Point2f > points) throw (cv::Exception)

Static Private Member Functions

static void argConvGLcpara2 (double cparam[3][4], int width, int height, double gnear, double gfar, double m[16], bool invert) throw (cv::Exception)
static int arParamDecompMat (double source[3][4], double cpara[3][4], double trans[3][4]) throw (cv::Exception)
static double dot (double a1, double a2, double a3, double b1, double b2, double b3)
static double norm (double a, double b, double c)

Private Attributes

ThresholdMethods _thresMethod
double _thresParam1
double _thresParam2
std::vector< std::vector
< cv::Point > > 
contours2
cv::Mat grey
std::vector< cv::Vec4i > hierarchy2
cv::Mat thres
cv::Mat thres2

Detailed Description

Main class for marker detection.

Definition at line 17 of file markerdetector.h.


Member Enumeration Documentation

This set the type of thresholding methods available

Enumerator:
FIXED_THRES 
ADPT_THRES 
CANNY 

Definition at line 54 of file markerdetector.h.


Constructor & Destructor Documentation

Definition at line 18 of file markerdetector.cpp.

Definition at line 30 of file markerdetector.cpp.


Member Function Documentation

void aruco::MarkerDetector::argConvGLcpara2 ( double  cparam[3][4],
int  width,
int  height,
double  gnear,
double  gfar,
double  m[16],
bool  invert 
) throw (cv::Exception) [static, private]

Definition at line 664 of file markerdetector.cpp.

int aruco::MarkerDetector::arParamDecompMat ( double  source[3][4],
double  cpara[3][4],
double  trans[3][4] 
) throw (cv::Exception) [static, private]

Definition at line 730 of file markerdetector.cpp.

bool aruco::MarkerDetector::correctHammMarker ( cv::Mat &  bits) [private]

Correct errors in the markers

Definition at line 414 of file markerdetector.cpp.

void aruco::MarkerDetector::detect ( cv::Mat &  input,
std::vector< Marker > &  detectedMarkers,
cv::Mat  camMatrix = cv::Mat(),
cv::Mat  distCoeff = cv::Mat(),
float  markerSizeMeters = -1 
) 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
void aruco::MarkerDetector::detect ( cv::Mat &  input,
std::vector< Marker > &  detectedMarkers,
CameraParameters  camParams = CameraParameters(),
float  markerSizeMeters = -1 
) 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

Definition at line 35 of file markerdetector.cpp.

double aruco::MarkerDetector::dot ( double  a1,
double  a2,
double  a3,
double  b1,
double  b2,
double  b3 
) [static, private]

Definition at line 812 of file markerdetector.cpp.

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

Definition at line 310 of file markerdetector.cpp.

void aruco::MarkerDetector::drawAllContours ( cv::Mat  input) [private]

Definition at line 277 of file markerdetector.cpp.

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

Definition at line 296 of file markerdetector.cpp.

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

Definition at line 288 of file markerdetector.cpp.

int aruco::MarkerDetector::getMarkerId ( cv::Mat &  in,
int &  nRotations 
) [private]

nRotations number of 90deg rotations in clowise direction needed to set the marker in correct position

Definition at line 482 of file markerdetector.cpp.

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

Definition at line 91 of file markerdetector.h.

Returns the current threshold method

Definition at line 63 of file 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 82 of file 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]

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,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 641 of file markerdetector.cpp.

int aruco::MarkerDetector::hammDistMarker ( cv::Mat  bits) [private]

Definition at line 349 of file markerdetector.cpp.

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

Definition at line 596 of file markerdetector.cpp.

int aruco::MarkerDetector::mat2id ( cv::Mat &  bits) [private]

Definition at line 396 of file markerdetector.cpp.

double aruco::MarkerDetector::norm ( double  a,
double  b,
double  c 
) [static, private]

Definition at line 807 of file markerdetector.cpp.

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

Definition at line 609 of file markerdetector.cpp.

template<typename T >
void aruco::MarkerDetector::printMat ( cv::Mat  M,
std::string  info = "" 
) [inline, private]

Definition at line 157 of file markerdetector.h.

template<typename T >
void aruco::MarkerDetector::printMat ( CvMat *  M,
std::string  info = "" 
) [inline, private]

Definition at line 175 of file markerdetector.h.

Mat aruco::MarkerDetector::rotate ( cv::Mat  in) [private]

Definition at line 462 of file markerdetector.cpp.

Sets the threshold method

Definition at line 58 of file 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:
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 72 of file markerdetector.h.

void aruco::MarkerDetector::thresHold ( int  method,
cv::Mat &  grey,
cv::Mat &  out 
) [private]

Definition at line 244 of file markerdetector.cpp.

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

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

Definition at line 327 of file markerdetector.cpp.


Member Data Documentation

Definition at line 116 of file markerdetector.h.

Definition at line 114 of file markerdetector.h.

Definition at line 114 of file markerdetector.h.

Definition at line 111 of file markerdetector.h.

cv::Mat aruco::MarkerDetector::grey [private]

Definition at line 110 of file markerdetector.h.

Definition at line 112 of file markerdetector.h.

cv::Mat aruco::MarkerDetector::thres [private]

Definition at line 110 of file markerdetector.h.

cv::Mat aruco::MarkerDetector::thres2 [private]

Definition at line 110 of file markerdetector.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


aruco_pose
Author(s): Julian Brunner
autogenerated on Thu May 23 2013 12:15:46