markerdetector.h
Go to the documentation of this file.
00001 /*****************************
00002 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without modification, are
00005 permitted provided that the following conditions are met:
00006 
00007    1. Redistributions of source code must retain the above copyright notice, this list of
00008       conditions and the following disclaimer.
00009 
00010    2. Redistributions in binary form must reproduce the above copyright notice, this list
00011       of conditions and the following disclaimer in the documentation and/or other materials
00012       provided with the distribution.
00013 
00014 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
00015 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00016 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
00017 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00018 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00019 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
00020 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
00021 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00022 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00023 
00024 The views and conclusions contained in the software and documentation are those of the
00025 authors and should not be interpreted as representing official policies, either expressed
00026 or implied, of Rafael Muñoz Salinas.
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   //Represent a candidate to be a maker
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;//all the points of its contour
00063     int idx;//index position in the global contour list
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 &param1,double &param2)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     //Current threshold method
00292     ThresholdMethods _thresMethod;
00293     //Threshold parameters
00294     double _thresParam1,_thresParam2;
00295     //Current corner method
00296     CornerRefinementMethod _cornerMethod;
00297     //minimum and maximum size of a contour lenght
00298     float _minSize,_maxSize;
00299     //Speed control
00300     int _speed;
00301     int _markerWarpSize;
00302     bool _doErosion;
00303     float _borderDistThres;//border around image limits in which corners are not allowed to be detected.
00304     //vectr of candidates to be markers. This is a vector with a set of rectangles that have no valid id
00305     vector<std::vector<cv::Point2f> > _candidates;
00306     //level of image reduction
00307     int pyrdown_level;
00308     //Images
00309     cv::Mat grey,thres,thres2,reduced;
00310     //pointer to the function that analizes a rectangular region so as to detect its internal marker
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 //     //GL routines
00322 // 
00323 //     static void argConvGLcpara2( double cparam[3][4], int width, int height, double gnear, double gfar, double m[16], bool invert )throw(cv::Exception);
00324 //     static int  arParamDecompMat( double source[3][4], double cpara[3][4], double trans[3][4] )throw(cv::Exception);
00325 //     static double norm( double a, double b, double c );
00326 //     static double dot(  double a1, double a2, double a3,
00327 //                         double b1, double b2, double b3 );
00328 // 
00329 
00330     //detection of the
00331     void findBestCornerInRegion_harris(const cv::Mat  & grey,vector<cv::Point2f> &  Corners,int blockSize);
00332    
00333     
00334     // auxiliar functions to perform LINES refinement
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        //remove the invalid ones by setting the valid in the positions left by the invalids
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     //graphical debug
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


ar_sys
Author(s): Hamdi Sahloul , Rafael Muñoz Salinas , Bence Magyar
autogenerated on Thu Aug 27 2015 12:23:55