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/opencv.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     }
00060     
00061     vector<cv::Point> contour;//all the points of its contour
00062     int idx;//index position in the global contour list
00063   };
00064 public:
00065 
00069     MarkerDetector();
00070 
00073     ~MarkerDetector();
00074 
00086     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=true) throw (cv::Exception);
00087 
00088     void detect2(const cv::Mat &input,
00089                  std::vector<Marker> &detectedMarkers,
00090                  cv::Mat camMatrix,
00091                  cv::Mat distCoeff,
00092                  std::vector<float> markerSizeMeters,
00093                  std::vector<cv::Point3f> markerPositionMeters,
00094                  bool setYPerperdicular=true)
00095     throw (cv::Exception);
00096 
00097 
00098 
00099     //TEST
00100     void detect_diffs ( const  cv::Mat &input,vector<Marker> &detectedMarkers,cv::Mat camMatrix ,cv::Mat distCoeff ,float markerSizeMeters ,bool setYPerperdicular) throw ( cv::Exception );
00101 
00102 
00103 
00114     void detect(const cv::Mat &input,std::vector<Marker> &detectedMarkers, CameraParameters camParams,float markerSizeMeters=-1,bool setYPerperdicular=true) throw (cv::Exception);
00115 
00116     void detect2(const cv::Mat &input,std::vector<Marker> &detectedMarkers, CameraParameters camParams,std::vector<float> markerSizeMeters, std::vector<cv::Point3f>  markerPositionMeters ,bool setYPerperdicular=true) throw (cv::Exception);
00117 
00118 
00122     enum ThresholdMethods {FIXED_THRES,ADPT_THRES,CANNY};
00123 
00124 
00125 
00128     void setThresholdMethod(ThresholdMethods m) {
00129         _thresMethod=m;
00130     }
00133     ThresholdMethods getThresholdMethod()const {
00134         return _thresMethod;
00135     }
00142     void setThresholdParams(double param1,double param2) {
00143         _thresParam1=param1;
00144         _thresParam2=param2;
00145     }
00152     void getThresholdParams(double &param1,double &param2)const {
00153         param1=_thresParam1;
00154         param2=_thresParam2;
00155     }
00156 
00157 
00161     const cv::Mat & getThresholdedImage() {
00162         return thres;
00163     }
00166     enum CornerRefinementMethod {NONE,HARRIS,SUBPIX,LINES};
00169     void setCornerRefinementMethod(CornerRefinementMethod method) {
00170         _cornerMethod=method;
00171     }
00174     CornerRefinementMethod getCornerRefinementMethod()const {
00175         return _cornerMethod;
00176     }
00183     void setMinMaxSize(float min=0.03,float max=0.5)throw(cv::Exception);
00184     
00190     void getMinMaxSize(float &min,float &max){min=_minSize;max=_maxSize;}
00191     
00195     void enableErosion(bool enable){_doErosion=enable;}
00196 
00204     void setDesiredSpeed(int val);
00207     int getDesiredSpeed()const {
00208         return _speed;
00209     }
00210 
00226     void setMakerDetectorFunction(int (* markerdetector_func)(const cv::Mat &in,int &nRotations) ) {
00227         markerIdDetector_ptrfunc=markerdetector_func;
00228     }
00229 
00236     void pyrDown(unsigned int level){pyrdown_level=level;}
00237 
00242 
00246     void thresHold(int method,const cv::Mat &grey,cv::Mat &thresImg,double param1=-1,double param2=-1)throw(cv::Exception);
00251     void detectRectangles(const cv::Mat &thresImg,vector<std::vector<cv::Point2f> > & candidates);
00252 
00255     const vector<std::vector<cv::Point2f> > &getCandidates() {
00256         return _candidates;
00257     }
00258 
00266     bool warp(cv::Mat &in,cv::Mat &out,cv::Size size, std::vector<cv::Point2f> points)throw (cv::Exception);
00267     
00268     
00269     
00273     void refineCandidateLines(MarkerCandidate &candidate);    
00274     
00275     
00289     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);
00290 
00291 private:
00292 
00293     bool _enableCylinderWarp;
00294     bool warp_cylinder ( cv::Mat &in,cv::Mat &out,cv::Size size, MarkerCandidate& mc ) throw ( cv::Exception );
00299     void detectRectangles(const cv::Mat &thresImg,vector<MarkerCandidate> & candidates);
00300     //Current threshold method
00301     ThresholdMethods _thresMethod;
00302     //Threshold parameters
00303     double _thresParam1,_thresParam2;
00304     //Current corner method
00305     CornerRefinementMethod _cornerMethod;
00306     //minimum and maximum size of a contour lenght
00307     float _minSize,_maxSize;
00308     //Speed control
00309     int _speed;
00310     int _markerWarpSize;
00311     bool _doErosion;
00312     //vectr of candidates to be markers. This is a vector with a set of rectangles that have no valid id
00313     vector<std::vector<cv::Point2f> > _candidates;
00314     //level of image reduction
00315     int pyrdown_level;
00316     //Images
00317     cv::Mat grey,thres,thres2,reduced;
00318     //pointer to the function that analizes a rectangular region so as to detect its internal marker
00319     int (* markerIdDetector_ptrfunc)(const cv::Mat &in,int &nRotations);
00320 
00323     bool isInto(cv::Mat &contour,std::vector<cv::Point2f> &b);
00326     int perimeter(std::vector<cv::Point2f> &a);
00327 
00328     
00329 //     //GL routines
00330 // 
00331 //     static void argConvGLcpara2( double cparam[3][4], int width, int height, double gnear, double gfar, double m[16], bool invert )throw(cv::Exception);
00332 //     static int  arParamDecompMat( double source[3][4], double cpara[3][4], double trans[3][4] )throw(cv::Exception);
00333 //     static double norm( double a, double b, double c );
00334 //     static double dot(  double a1, double a2, double a3,
00335 //                         double b1, double b2, double b3 );
00336 // 
00337 
00338     //detection of the
00339     void findBestCornerInRegion_harris(const cv::Mat  & grey,vector<cv::Point2f> &  Corners,int blockSize);
00340    
00341     
00342     // auxiliar functions to perform LINES refinement
00343     void interpolate2Dline( const vector< cv::Point > &inPoints, cv::Point3f &outLine);
00344     cv::Point2f getCrossPoint(const cv::Point3f& line1, const cv::Point3f& line2);      
00345     
00346     
00352     template<typename T>
00353     void removeElements(vector<T> & vinout,const vector<bool> &toRemove)
00354     {
00355        //remove the invalid ones by setting the valid in the positions left by the invalids
00356       size_t indexValid=0;
00357       for (size_t i=0;i<toRemove.size();i++) {
00358         if (!toRemove[i]) {
00359             if (indexValid!=i) vinout[indexValid]=vinout[i];
00360             indexValid++;
00361         }
00362       }
00363       vinout.resize(indexValid);
00364     }
00365 
00366     //graphical debug
00367     void drawApproxCurve(cv::Mat &in,std::vector<cv::Point>  &approxCurve ,cv::Scalar color);
00368     void drawContour(cv::Mat &in,std::vector<cv::Point>  &contour,cv::Scalar  );
00369     void drawAllContours(cv::Mat input, std::vector<std::vector<cv::Point> > &contours);
00370     void draw(cv::Mat out,const std::vector<Marker> &markers );
00371 
00372 };
00373 
00374 
00375 
00376 
00377 };
00378 #endif


camera_pose_aruco
Author(s): tcarreira
autogenerated on Mon Jan 6 2014 11:47:56