00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef _ARUCO_MarkerDetector_H
00029 #define _ARUCO_MarkerDetector_H
00030 #include <opencv2/opencv.hpp>
00031 #include <cstdio>
00032 #include <iostream>
00033 #include <aruco/cameraparameters.h>
00034 #include <aruco/exports.h>
00035 #include <aruco/marker.h>
00036 using namespace std;
00037
00038 namespace aruco
00039 {
00040
00044 class ARUCO_EXPORTS MarkerDetector
00045 {
00046
00047 class MarkerCandidate: public Marker{
00048 public:
00049 MarkerCandidate(): idx(-1) {}
00050 MarkerCandidate(const Marker &M): Marker(M), idx(-1) {}
00051 MarkerCandidate(const MarkerCandidate &M): Marker(M), contour(M.contour), idx(M.idx) {}
00052 MarkerCandidate & operator=(const MarkerCandidate &M){
00053 Marker::operator=(M);
00054 contour=M.contour;
00055 idx=M.idx;
00056 return *this;
00057 }
00058
00059 vector<cv::Point> contour;
00060 int idx;
00061 };
00062 public:
00063
00067 MarkerDetector();
00068
00071 ~MarkerDetector();
00072
00084 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);
00095 void detect(const cv::Mat &input, std::vector<Marker> &detectedMarkers, CameraParameters camParams, float markerSizeMeters=-1, bool setYPerpendicular=true) throw (cv::Exception);
00096
00100 enum ThresholdMethods {FIXED_THRES,ADPT_THRES,CANNY};
00101
00102
00103
00106 void setThresholdMethod(ThresholdMethods m) {
00107 _thresMethod=m;
00108 }
00111 ThresholdMethods getThresholdMethod()const {
00112 return _thresMethod;
00113 }
00120 void setThresholdParams(double param1,double param2) {
00121 _thresParam1=param1;
00122 _thresParam2=param2;
00123 }
00130 void getThresholdParams(double ¶m1,double ¶m2)const {
00131 param1=_thresParam1;
00132 param2=_thresParam2;
00133 }
00134
00135
00139 const cv::Mat & getThresholdedImage() {
00140 return thres;
00141 }
00144 enum CornerRefinementMethod {NONE,HARRIS,SUBPIX,LINES};
00147 void setCornerRefinementMethod(CornerRefinementMethod method) {
00148 _cornerMethod=method;
00149 }
00152 CornerRefinementMethod getCornerRefinementMethod()const {
00153 return _cornerMethod;
00154 }
00161 void setMinMaxSize(float min=0.03,float max=0.5)throw(cv::Exception);
00162
00168 void getMinMaxSize(float &min,float &max){min=_minSize;max=_maxSize;}
00169
00173 void enableErosion(bool enable){_doErosion=enable;}
00174
00182 void setDesiredSpeed(int val);
00185 int getDesiredSpeed()const {
00186 return _speed;
00187 }
00188
00204 void setMakerDetectorFunction(int (* markerdetector_func)(const cv::Mat &in,int &nRotations) ) {
00205 markerIdDetector_ptrfunc=markerdetector_func;
00206 }
00207
00214 void pyrDown(unsigned int level){pyrdown_level=level;}
00215
00220
00224 void thresHold(int method,const cv::Mat &grey,cv::Mat &thresImg,double param1=-1,double param2=-1)throw(cv::Exception);
00229 void detectRectangles(const cv::Mat &thresImg,vector<std::vector<cv::Point2f> > & candidates);
00230
00233 const vector<std::vector<cv::Point2f> > &getCandidates() {
00234 return _candidates;
00235 }
00236
00244 bool warp(cv::Mat &in,cv::Mat &out,cv::Size size, std::vector<cv::Point2f> points)throw (cv::Exception);
00245
00246
00247
00251 void refineCandidateLines(MarkerCandidate &candidate);
00252
00253
00267 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);
00268
00269 private:
00270
00271 bool _enableCylinderWarp;
00272 bool warp_cylinder ( cv::Mat &in,cv::Mat &out,cv::Size size, MarkerCandidate& mc ) throw ( cv::Exception );
00277 void detectRectangles(const cv::Mat &thresImg,vector<MarkerCandidate> & candidates);
00278
00279 ThresholdMethods _thresMethod;
00280
00281 double _thresParam1,_thresParam2;
00282
00283 CornerRefinementMethod _cornerMethod;
00284
00285 float _minSize,_maxSize;
00286
00287 int _speed;
00288 int _markerWarpSize;
00289 bool _doErosion;
00290
00291 vector<std::vector<cv::Point2f> > _candidates;
00292
00293 int pyrdown_level;
00294
00295 cv::Mat grey,thres,thres2,reduced;
00296
00297 int (* markerIdDetector_ptrfunc)(const cv::Mat &in,int &nRotations);
00298
00301 bool isInto(cv::Mat &contour,std::vector<cv::Point2f> &b);
00304 int perimeter(std::vector<cv::Point2f> &a);
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317 void findBestCornerInRegion_harris(const cv::Mat & grey,vector<cv::Point2f> & Corners,int blockSize);
00318
00319
00320
00321 void interpolate2Dline( const vector< cv::Point > &inPoints, cv::Point3f &outLine);
00322 cv::Point2f getCrossPoint(const cv::Point3f& line1, const cv::Point3f& line2);
00323
00324
00330 template<typename T>
00331 void removeElements(vector<T> & vinout,const vector<bool> &toRemove)
00332 {
00333
00334 size_t indexValid=0;
00335 for (size_t i=0;i<toRemove.size();i++) {
00336 if (!toRemove[i]) {
00337 if (indexValid!=i) vinout[indexValid]=vinout[i];
00338 indexValid++;
00339 }
00340 }
00341 vinout.resize(indexValid);
00342 }
00343
00344
00345 void drawApproxCurve(cv::Mat &in,std::vector<cv::Point> &approxCurve ,cv::Scalar color);
00346 void drawContour(cv::Mat &in,std::vector<cv::Point> &contour,cv::Scalar );
00347 void drawAllContours(cv::Mat input, std::vector<std::vector<cv::Point> > &contours);
00348 void draw(cv::Mat out,const std::vector<Marker> &markers );
00349
00350 };
00351
00352
00353
00354
00355 };
00356 #endif