markerdetector.h
Go to the documentation of this file.
1 /*****************************
2 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without modification, are
5 permitted provided that the following conditions are met:
6 
7  1. Redistributions of source code must retain the above copyright notice, this list of
8  conditions and the following disclaimer.
9 
10  2. Redistributions in binary form must reproduce the above copyright notice, this list
11  of conditions and the following disclaimer in the documentation and/or other materials
12  provided with the distribution.
13 
14 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
15 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
16 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
17 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
18 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
19 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
20 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
21 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
22 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23 
24 The views and conclusions contained in the software and documentation are those of the
25 authors and should not be interpreted as representing official policies, either expressed
26 or implied, of Rafael Muñoz Salinas.
27 ********************************/
28 #ifndef _ARUCO_MarkerDetector_H
29 #define _ARUCO_MarkerDetector_H
30 #include <opencv2/opencv.hpp>
31 #include <cstdio>
32 #include <iostream>
33 #include <aruco/cameraparameters.h>
34 #include <aruco/exports.h>
35 #include <aruco/marker.h>
36 using namespace std;
37 
38 namespace aruco
39 {
40 
45 {
46  //Represent a candidate to be a maker
47  class MarkerCandidate: public Marker{
48  public:
49  MarkerCandidate(): idx(-1) {}
50  MarkerCandidate(const Marker &M): Marker(M), idx(-1) {}
51  MarkerCandidate(const MarkerCandidate &M): Marker(M), contour(M.contour), idx(M.idx) {}
53  Marker::operator=(M);
54  contour=M.contour;
55  idx=M.idx;
56  return *this;
57  }
58 
59  vector<cv::Point> contour;//all the points of its contour
60  int idx;//index position in the global contour list
61  };
62 public:
63 
68 
71  ~MarkerDetector();
72 
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);
96 
100  enum ThresholdMethods {FIXED_THRES,ADPT_THRES,CANNY};
101 
102 
103 
107  _thresMethod=m;
108  }
112  return _thresMethod;
113  }
120  void setThresholdParams(double param1,double param2) {
121  _thresParam1=param1;
122  _thresParam2=param2;
123  }
130  void getThresholdParams(double &param1,double &param2)const {
131  param1=_thresParam1;
132  param2=_thresParam2;
133  }
134 
135 
139  const cv::Mat & getThresholdedImage() {
140  return thres;
141  }
144  enum CornerRefinementMethod {NONE,HARRIS,SUBPIX,LINES};
148  _cornerMethod=method;
149  }
153  return _cornerMethod;
154  }
161  void setMinMaxSize(float min=0.03,float max=0.5)throw(cv::Exception);
162 
168  void getMinMaxSize(float &min,float &max){min=_minSize;max=_maxSize;}
169 
173  void enableErosion(bool enable){_doErosion=enable;}
174 
182  void setDesiredSpeed(int val);
185  int getDesiredSpeed()const {
186  return _speed;
187  }
188 
204  void setMakerDetectorFunction(int (* markerdetector_func)(const cv::Mat &in,int &nRotations) ) {
205  markerIdDetector_ptrfunc=markerdetector_func;
206  }
207 
214  void pyrDown(unsigned int level){pyrdown_level=level;}
215 
220 
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);
230 
233  const vector<std::vector<cv::Point2f> > &getCandidates() {
234  return _candidates;
235  }
236 
244  bool warp(cv::Mat &in,cv::Mat &out,cv::Size size, std::vector<cv::Point2f> points)throw (cv::Exception);
245 
246 
247 
251  void refineCandidateLines(MarkerCandidate &candidate);
252 
253 
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);
268 
269 private:
270 
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);
278  //Current threshold method
280  //Threshold parameters
281  double _thresParam1,_thresParam2;
282  //Current corner method
284  //minimum and maximum size of a contour lenght
285  float _minSize,_maxSize;
286  //Speed control
287  int _speed;
290  //vectr of candidates to be markers. This is a vector with a set of rectangles that have no valid id
291  vector<std::vector<cv::Point2f> > _candidates;
292  //level of image reduction
294  //Images
295  cv::Mat grey,thres,thres2,reduced;
296  //pointer to the function that analizes a rectangular region so as to detect its internal marker
297  int (* markerIdDetector_ptrfunc)(const cv::Mat &in,int &nRotations);
298 
301  bool isInto(cv::Mat &contour,std::vector<cv::Point2f> &b);
304  int perimeter(std::vector<cv::Point2f> &a);
305 
306 
307 // //GL routines
308 //
309 // static void argConvGLcpara2( double cparam[3][4], int width, int height, double gnear, double gfar, double m[16], bool invert )throw(cv::Exception);
310 // static int arParamDecompMat( double source[3][4], double cpara[3][4], double trans[3][4] )throw(cv::Exception);
311 // static double norm( double a, double b, double c );
312 // static double dot( double a1, double a2, double a3,
313 // double b1, double b2, double b3 );
314 //
315 
316  //detection of the
317  void findBestCornerInRegion_harris(const cv::Mat & grey,vector<cv::Point2f> & Corners,int blockSize);
318 
319 
320  // auxiliar functions to perform LINES refinement
321  void interpolate2Dline( const vector< cv::Point > &inPoints, cv::Point3f &outLine);
322  cv::Point2f getCrossPoint(const cv::Point3f& line1, const cv::Point3f& line2);
323 
324 
330  template<typename T>
331  void removeElements(vector<T> & vinout,const vector<bool> &toRemove)
332  {
333  //remove the invalid ones by setting the valid in the positions left by the invalids
334  size_t indexValid=0;
335  for (size_t i=0;i<toRemove.size();i++) {
336  if (!toRemove[i]) {
337  if (indexValid!=i) vinout[indexValid]=vinout[i];
338  indexValid++;
339  }
340  }
341  vinout.resize(indexValid);
342  }
343 
344  //graphical debug
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 );
349 
350 };
351 
352 
353 
354 
355 };
356 #endif
void setThresholdParams(double param1, double param2)
void getMinMaxSize(float &min, float &max)
#define ARUCO_EXPORTS
Definition: exports.h:42
void pyrDown(unsigned int level)
vector< std::vector< cv::Point2f > > _candidates
CornerRefinementMethod _cornerMethod
void getThresholdParams(double &param1, double &param2) 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.
Definition: marker.h:41
Main class for marker detection.
const cv::Mat & getThresholdedImage()
Parameters of the camera.
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)


aruco
Author(s): Rafael Muñoz Salinas , Bence Magyar
autogenerated on Wed Sep 2 2020 04:02:09