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/core/core.hpp>
00031 #include <cstdio>
00032 #include <iostream>
00033 #include "cameraparameters.h"
00034 #include "exports.h"
00035 #include "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(){}
00050 MarkerCandidate(const Marker &M): Marker(M){}
00051 MarkerCandidate(const MarkerCandidate &M): Marker(M){
00052 contour=M.contour;
00053 idx=M.idx;
00054 }
00055 MarkerCandidate & operator=(const MarkerCandidate &M){
00056 (*(Marker*)this)=(*(Marker*)&M);
00057 contour=M.contour;
00058 idx=M.idx;
00059 return *this;
00060 }
00061
00062 vector<cv::Point> contour;
00063 int idx;
00064 };
00065 public:
00066
00070 MarkerDetector();
00071
00074 ~MarkerDetector();
00075
00087 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);
00098 void detect(const cv::Mat &input,std::vector<Marker> &detectedMarkers, CameraParameters camParams,float markerSizeMeters=-1,bool setYPerperdicular=false) throw (cv::Exception);
00099
00103 enum ThresholdMethods {FIXED_THRES,ADPT_THRES,CANNY};
00104
00105
00106
00109 void setThresholdMethod(ThresholdMethods m) {
00110 _thresMethod=m;
00111 }
00114 ThresholdMethods getThresholdMethod()const {
00115 return _thresMethod;
00116 }
00123 void setThresholdParams(double param1,double param2) {
00124 _thresParam1=param1;
00125 _thresParam2=param2;
00126 }
00133 void getThresholdParams(double ¶m1,double ¶m2)const {
00134 param1=_thresParam1;
00135 param2=_thresParam2;
00136 }
00137
00138
00142 const cv::Mat & getThresholdedImage() {
00143 return thres;
00144 }
00147 enum CornerRefinementMethod {NONE,HARRIS,SUBPIX,LINES};
00150 void setCornerRefinementMethod(CornerRefinementMethod method) {
00151 _cornerMethod=method;
00152 }
00155 CornerRefinementMethod getCornerRefinementMethod()const {
00156 return _cornerMethod;
00157 }
00164 void setMinMaxSize(float min=0.03,float max=0.5)throw(cv::Exception);
00165
00171 void getMinMaxSize(float &min,float &max){min=_minSize;max=_maxSize;}
00172
00176 void enableErosion(bool enable){_doErosion=enable;}
00177
00185 void setDesiredSpeed(int val);
00188 int getDesiredSpeed()const {
00189 return _speed;
00190 }
00191
00196 void setWarpSize(int val)throw(cv::Exception);;
00199 int getWarpSize()const {
00200 return _markerWarpSize;
00201 }
00202
00218 void setMakerDetectorFunction(int (* markerdetector_func)(const cv::Mat &in,int &nRotations) ) {
00219 markerIdDetector_ptrfunc=markerdetector_func;
00220 }
00221
00228 void pyrDown(unsigned int level){pyrdown_level=level;}
00229
00234
00238 void thresHold(int method,const cv::Mat &grey,cv::Mat &thresImg,double param1=-1,double param2=-1)throw(cv::Exception);
00243 void detectRectangles(const cv::Mat &thresImg,vector<std::vector<cv::Point2f> > & candidates);
00244
00247 const vector<std::vector<cv::Point2f> > &getCandidates() {
00248 return _candidates;
00249 }
00250
00258 bool warp(cv::Mat &in,cv::Mat &out,cv::Size size, std::vector<cv::Point2f> points)throw (cv::Exception);
00259
00260
00261
00265 void refineCandidateLines(MarkerCandidate &candidate, const cv::Mat &camMatrix, const cv::Mat &distCoeff);
00266
00267
00281 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);
00282
00283 private:
00284
00285 bool warp_cylinder ( cv::Mat &in,cv::Mat &out,cv::Size size, MarkerCandidate& mc ) throw ( cv::Exception );
00290 void detectRectangles(const cv::Mat &thresImg,vector<MarkerCandidate> & candidates);
00291
00292 ThresholdMethods _thresMethod;
00293
00294 double _thresParam1,_thresParam2;
00295
00296 CornerRefinementMethod _cornerMethod;
00297
00298 float _minSize,_maxSize;
00299
00300 int _speed;
00301 int _markerWarpSize;
00302 bool _doErosion;
00303 float _borderDistThres;
00304
00305 vector<std::vector<cv::Point2f> > _candidates;
00306
00307 int pyrdown_level;
00308
00309 cv::Mat grey,thres,thres2,reduced;
00310
00311 int (* markerIdDetector_ptrfunc)(const cv::Mat &in,int &nRotations);
00312
00315 bool isInto(cv::Mat &contour,std::vector<cv::Point2f> &b);
00318 int perimeter(std::vector<cv::Point2f> &a);
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331 void findBestCornerInRegion_harris(const cv::Mat & grey,vector<cv::Point2f> & Corners,int blockSize);
00332
00333
00334
00335 void interpolate2Dline( const vector< cv::Point2f > &inPoints, cv::Point3f &outLine);
00336 cv::Point2f getCrossPoint(const cv::Point3f& line1, const cv::Point3f& line2);
00337 void distortPoints(vector<cv::Point2f> in, vector<cv::Point2f> &out, const cv::Mat &camMatrix, const cv::Mat &distCoeff);
00338
00339
00345 template<typename T>
00346 void removeElements(vector<T> & vinout,const vector<bool> &toRemove)
00347 {
00348
00349 size_t indexValid=0;
00350 for (size_t i=0;i<toRemove.size();i++) {
00351 if (!toRemove[i]) {
00352 if (indexValid!=i) vinout[indexValid]=vinout[i];
00353 indexValid++;
00354 }
00355 }
00356 vinout.resize(indexValid);
00357 }
00358
00359
00360 void drawApproxCurve(cv::Mat &in,std::vector<cv::Point> &approxCurve ,cv::Scalar color);
00361 void drawContour(cv::Mat &in,std::vector<cv::Point> &contour,cv::Scalar );
00362 void drawAllContours(cv::Mat input, std::vector<std::vector<cv::Point> > &contours);
00363 void draw(cv::Mat out,const std::vector<Marker> &markers );
00364
00365
00366 template<typename T> void joinVectors(vector<vector<T> > &vv,vector<T> &v,bool clearv=false){
00367 if (clearv) v.clear();
00368 for(size_t i=0;i<vv.size();i++)
00369 for(size_t j=0;j<vv[i].size();j++) v.push_back(vv[i][j]);
00370 }
00371 };
00372
00373
00374
00375
00376 };
00377 #endif