28 #ifndef _ARUCO_MarkerDetector_H 29 #define _ARUCO_MarkerDetector_H 30 #include <opencv2/opencv.hpp> 84 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);
95 void detect(const
cv::Mat &input,
std::vector<
Marker> &detectedMarkers,
CameraParameters camParams,
float markerSizeMeters=-1,
bool setYPerpendicular=true) throw (
cv::Exception);
148 _cornerMethod=method;
153 return _cornerMethod;
161 void setMinMaxSize(
float min=0.03,
float max=0.5)
throw(cv::Exception);
182 void setDesiredSpeed(
int val);
205 markerIdDetector_ptrfunc=markerdetector_func;
214 void pyrDown(
unsigned int level){pyrdown_level=level;}
224 void thresHold(
int method,
const cv::Mat &grey,cv::Mat &thresImg,
double param1=-1,
double param2=-1)
throw(cv::Exception);
229 void detectRectangles(
const cv::Mat &thresImg,vector<std::vector<cv::Point2f> > & candidates);
244 bool warp(cv::Mat &in,cv::Mat &out,cv::Size size, std::vector<cv::Point2f> points)
throw (cv::Exception);
267 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);
272 bool warp_cylinder ( cv::Mat &in,cv::Mat &out,cv::Size size,
MarkerCandidate& mc )
throw ( cv::Exception );
277 void detectRectangles(
const cv::Mat &thresImg,vector<MarkerCandidate> & candidates);
297 int (* markerIdDetector_ptrfunc)(
const cv::Mat &in,
int &nRotations);
301 bool isInto(cv::Mat &contour,std::vector<cv::Point2f> &b);
304 int perimeter(std::vector<cv::Point2f> &a);
317 void findBestCornerInRegion_harris(
const cv::Mat & grey,vector<cv::Point2f> & Corners,
int blockSize);
321 void interpolate2Dline(
const vector< cv::Point > &inPoints, cv::Point3f &outLine);
322 cv::Point2f getCrossPoint(
const cv::Point3f& line1,
const cv::Point3f& line2);
335 for (
size_t i=0;i<toRemove.size();i++) {
337 if (indexValid!=i) vinout[indexValid]=vinout[i];
341 vinout.resize(indexValid);
345 void drawApproxCurve(cv::Mat &in,std::vector<cv::Point> &approxCurve ,cv::Scalar color);
346 void drawContour(cv::Mat &in,std::vector<cv::Point> &contour,cv::Scalar );
347 void drawAllContours(cv::Mat input, std::vector<std::vector<cv::Point> > &contours);
348 void draw(cv::Mat out,
const std::vector<Marker> &markers );
void setThresholdParams(double param1, double param2)
void getMinMaxSize(float &min, float &max)
void pyrDown(unsigned int level)
vector< std::vector< cv::Point2f > > _candidates
CornerRefinementMethod _cornerMethod
void getThresholdParams(double ¶m1, double ¶m2) const
void removeElements(vector< T > &vinout, const vector< bool > &toRemove)
CornerRefinementMethod getCornerRefinementMethod() const
MarkerCandidate & operator=(const MarkerCandidate &M)
const vector< std::vector< cv::Point2f > > & getCandidates()
MarkerCandidate(const MarkerCandidate &M)
ThresholdMethods _thresMethod
ThresholdMethods getThresholdMethod() const
This class represents a marker. It is a vector of the fours corners ot the marker.
Main class for marker detection.
vector< cv::Point > contour
const cv::Mat & getThresholdedImage()
Parameters of the camera.
MarkerCandidate(const Marker &M)
void enableErosion(bool enable)
int getDesiredSpeed() const
void setMakerDetectorFunction(int(*markerdetector_func)(const cv::Mat &in, int &nRotations))
void setThresholdMethod(ThresholdMethods m)
void setCornerRefinementMethod(CornerRefinementMethod method)