markerdetector.cpp
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 #include <aruco/markerdetector.h>
29 #include <opencv/cv.h>
30 #include <opencv/highgui.h>
31 #include <iostream>
32 #include <fstream>
33 #include <aruco/arucofidmarkers.h>
34 #include <valarray>
35 using namespace std;
36 using namespace cv;
37 
38 namespace aruco
39 {
40  /************************************
41  *
42  *
43  *
44  *
45  ************************************/
46  MarkerDetector::MarkerDetector()
47  {
48  _doErosion=false;
49  _enableCylinderWarp=false;
50  _thresMethod=ADPT_THRES;
51  _thresParam1=_thresParam2=7;
52  _cornerMethod=LINES;
53  _markerWarpSize=56;
54  _speed=0;
55  markerIdDetector_ptrfunc=aruco::FiducidalMarkers::detect;
56  pyrdown_level=0; // no image reduction
57  _minSize=0.04;
58  _maxSize=0.5;
59  }
60  /************************************
61  *
62  *
63  *
64  *
65  ************************************/
66 
67  MarkerDetector::~MarkerDetector()
68  {
69 
70  }
71 
72  /************************************
73  *
74  *
75  *
76  *
77  ************************************/
78  void MarkerDetector::setDesiredSpeed ( int val )
79  {
80  if ( val<0 ) val=0;
81  else if ( val>3 ) val=2;
82 
83  _speed=val;
84  switch ( _speed )
85  {
86 
87  case 0:
88  _markerWarpSize=56;
89  _cornerMethod=SUBPIX;
90  _doErosion=true;
91  break;
92 
93  case 1:
94  case 2:
95  _markerWarpSize=28;
96  _cornerMethod=NONE;
97  break;
98  };
99  }
100 
101  /************************************
102  *
103  *
104  *
105  *
106  ************************************/
107  void MarkerDetector::detect ( const cv::Mat &input,std::vector<Marker> &detectedMarkers, CameraParameters camParams ,float markerSizeMeters ,bool setYPerpendicular) throw ( cv::Exception )
108  {
109  detect ( input, detectedMarkers,camParams.CameraMatrix ,camParams.Distorsion, markerSizeMeters ,setYPerpendicular);
110  }
111 
112 
113  /************************************
114  *
115  * Main detection function. Performs all steps
116  *
117  *
118  ************************************/
119  void MarkerDetector::detect ( const cv::Mat &input,vector<Marker> &detectedMarkers,Mat camMatrix ,Mat distCoeff ,float markerSizeMeters ,bool setYPerpendicular) throw ( cv::Exception )
120  {
121 
122 
123  //it must be a 3 channel image
124  if ( input.type() ==CV_8UC3 ) cv::cvtColor ( input,grey,CV_BGR2GRAY );
125  else grey=input;
126 
127 
128  // cv::cvtColor(grey,_ssImC ,CV_GRAY2BGR); //DELETE
129 
130  //clear input data
131  detectedMarkers.clear();
132 
133 
134  cv::Mat imgToBeThresHolded=grey;
135  double ThresParam1=_thresParam1,ThresParam2=_thresParam2;
136  //Must the image be downsampled before continue processing?
137  if ( pyrdown_level!=0 )
138  {
139  reduced=grey;
140  for ( int i=0;i<pyrdown_level;i++ )
141  {
142  cv::Mat tmp;
143  cv::pyrDown ( reduced,tmp );
144  reduced=tmp;
145  }
146  int red_den=pow ( 2.0f,pyrdown_level );
147  imgToBeThresHolded=reduced;
148  ThresParam1/=float ( red_den );
149  ThresParam2/=float ( red_den );
150  }
151 
153  thresHold ( _thresMethod,imgToBeThresHolded,thres,ThresParam1,ThresParam2 );
154  //an erosion might be required to detect chessboard like boards
155 
156  if ( _doErosion )
157  {
158  erode ( thres,thres2,cv::Mat() );
159  thres2=thres;
160  // cv::bitwise_xor ( thres,thres2,thres );
161  }
162  //find all rectangles in the thresholdes image
163  vector<MarkerCandidate > MarkerCanditates;
164  detectRectangles ( thres,MarkerCanditates );
165  //if the image has been downsampled, then calcualte the location of the corners in the original image
166  if ( pyrdown_level!=0 )
167  {
168  float red_den=pow ( 2.0f,pyrdown_level );
169  float offInc= ( ( pyrdown_level/2. )-0.5 );
170  for ( unsigned int i=0;i<MarkerCanditates.size();++i ) {
171  for ( int c=0;c<4;c++ )
172  {
173  MarkerCanditates[i][c].x=MarkerCanditates[i][c].x*red_den+offInc;
174  MarkerCanditates[i][c].y=MarkerCanditates[i][c].y*red_den+offInc;
175  }
176  //do the same with the the contour points
177  for ( size_t c=0;c<MarkerCanditates[i].contour.size();++c )
178  {
179  MarkerCanditates[i].contour[c].x=MarkerCanditates[i].contour[c].x*red_den+offInc;
180  MarkerCanditates[i].contour[c].y=MarkerCanditates[i].contour[c].y*red_den+offInc;
181  }
182  }
183  }
184 
186  _candidates.clear();
187  for ( unsigned int i=0;i<MarkerCanditates.size();++i )
188  {
189  //Find proyective homography
190  Mat canonicalMarker;
191  bool resW=false;
192  if (_enableCylinderWarp)
193  resW=warp_cylinder( grey,canonicalMarker,Size ( _markerWarpSize,_markerWarpSize ),MarkerCanditates[i] );
194  else resW=warp ( grey,canonicalMarker,Size ( _markerWarpSize,_markerWarpSize ),MarkerCanditates[i] );
195  if (resW) {
196  int nRotations;
197  int id= ( *markerIdDetector_ptrfunc ) ( canonicalMarker,nRotations );
198  if ( id!=-1 )
199  {
200  if(_cornerMethod==LINES) refineCandidateLines( MarkerCanditates[i] ); // make LINES refinement before lose contour points
201  detectedMarkers.push_back ( MarkerCanditates[i] );
202  detectedMarkers.back().id=id;
203  //sort the points so that they are always in the same order no matter the camera orientation
204  std::rotate ( detectedMarkers.back().begin(),detectedMarkers.back().begin() +4-nRotations,detectedMarkers.back().end() );
205  }
206  else _candidates.push_back ( MarkerCanditates[i] );
207  }
208 
209  }
210 
211 
213  if ( detectedMarkers.size() >0 && _cornerMethod!=NONE && _cornerMethod!=LINES )
214  {
215  vector<Point2f> Corners;
216  for ( unsigned int i=0;i<detectedMarkers.size();++i )
217  for ( int c=0;c<4;c++ )
218  Corners.push_back ( detectedMarkers[i][c] );
219 
220  if ( _cornerMethod==HARRIS )
221  findBestCornerInRegion_harris ( grey, Corners,7 );
222  else if ( _cornerMethod==SUBPIX )
223  cornerSubPix ( grey, Corners,cvSize ( 5,5 ), cvSize ( -1,-1 ) ,cvTermCriteria ( CV_TERMCRIT_ITER|CV_TERMCRIT_EPS,3,0.05 ) );
224 
225  //copy back
226  for ( unsigned int i=0;i<detectedMarkers.size();++i )
227  for ( int c=0;c<4;c++ ) detectedMarkers[i][c]=Corners[i*4+c];
228  }
229  //sort by id
230  std::sort ( detectedMarkers.begin(),detectedMarkers.end() );
231  //there might be still the case that a marker is detected twice because of the double border indicated earlier,
232  //detect and remove these cases
233  vector<bool> toRemove ( detectedMarkers.size(),false );
234  for ( int i=0;i<int ( detectedMarkers.size() )-1;++i )
235  {
236  if ( detectedMarkers[i].id==detectedMarkers[i+1].id && !toRemove[i+1] )
237  {
238  //deletes the one with smaller perimeter
239  if ( perimeter ( detectedMarkers[i] ) >perimeter ( detectedMarkers[i+1] ) ) toRemove[i+1]=true;
240  else toRemove[i]=true;
241  }
242  }
243  //remove the markers marker
244  removeElements ( detectedMarkers, toRemove );
245 
247  if ( camMatrix.rows!=0 && markerSizeMeters>0 )
248  {
249  for ( unsigned int i=0;i<detectedMarkers.size();i++ )
250  detectedMarkers[i].calculateExtrinsics ( markerSizeMeters,camMatrix,distCoeff,setYPerpendicular );
251  }
252  }
253 
254 
255  /************************************
256  *
257  * Crucial step. Detects the rectangular regions of the thresholded image
258  *
259  *
260  ************************************/
261  void MarkerDetector::detectRectangles ( const cv::Mat &thresold,vector<std::vector<cv::Point2f> > &MarkerCanditates )
262  {
263  vector<MarkerCandidate> candidates;
264  detectRectangles(thresold,candidates);
265  //create the output
266  MarkerCanditates.resize(candidates.size());
267  for (size_t i=0;i<MarkerCanditates.size();i++)
268  MarkerCanditates[i]=candidates[i];
269  }
270 
271  void MarkerDetector::detectRectangles(const cv::Mat &thresImg,vector<MarkerCandidate> & OutMarkerCanditates)
272  {
273  vector<MarkerCandidate> MarkerCanditates;
274  //calcualte the min_max contour sizes
275  unsigned int minSize=_minSize*std::max(thresImg.cols,thresImg.rows)*4;
276  unsigned int maxSize=_maxSize*std::max(thresImg.cols,thresImg.rows)*4;
277  std::vector<std::vector<cv::Point> > contours2;
278  std::vector<cv::Vec4i> hierarchy2;
279 
280  thresImg.copyTo ( thres2 );
281  cv::findContours ( thres2 , contours2, hierarchy2,CV_RETR_TREE, CV_CHAIN_APPROX_NONE );
282  vector<Point> approxCurve;
284 
285  for ( unsigned int i=0;i<contours2.size();i++ )
286  {
287 
288 
289  //check it is a possible element by first checking is has enough points
290  if ( minSize< contours2[i].size() &&contours2[i].size()<maxSize )
291  {
292  //approximate to a poligon
293  approxPolyDP ( contours2[i] ,approxCurve , double ( contours2[i].size() ) *0.05 , true );
294  // drawApproxCurve(copy,approxCurve,Scalar(0,0,255));
295  //check that the poligon has 4 points
296  if ( approxCurve.size() ==4 )
297  {
298 
299  // drawContour(input,contours2[i],Scalar(255,0,225));
300  // namedWindow("input");
301  // imshow("input",input);
302  // waitKey(0);
303  //and is convex
304  if ( isContourConvex ( Mat ( approxCurve ) ) )
305  {
306  // drawApproxCurve(input,approxCurve,Scalar(255,0,255));
307  // //ensure that the distace between consecutive points is large enough
308  float minDist=1e10;
309  for ( int j=0;j<4;j++ )
310  {
311  float d= std::sqrt ( ( float ) ( approxCurve[j].x-approxCurve[ ( j+1 ) %4].x ) * ( approxCurve[j].x-approxCurve[ ( j+1 ) %4].x ) +
312  ( approxCurve[j].y-approxCurve[ ( j+1 ) %4].y ) * ( approxCurve[j].y-approxCurve[ ( j+1 ) %4].y ) );
313  // norm(Mat(approxCurve[i]),Mat(approxCurve[(i+1)%4]));
314  if ( d<minDist ) minDist=d;
315  }
316  //check that distance is not very small
317  if ( minDist>10 )
318  {
319  //add the points
320  // cout<<"ADDED"<<endl;
321  MarkerCanditates.push_back ( MarkerCandidate() );
322  MarkerCanditates.back().idx=i;
323  for ( int j=0;j<4;j++ )
324  {
325  MarkerCanditates.back().push_back ( Point2f ( approxCurve[j].x,approxCurve[j].y ) );
326  }
327  }
328  }
329  }
330  }
331  }
332 
333  // namedWindow("input");
334  // imshow("input",input);
335  // waitKey(0);
337  valarray<bool> swapped(false,MarkerCanditates.size());//used later
338  for ( unsigned int i=0;i<MarkerCanditates.size();i++ )
339  {
340 
341  //trace a line between the first and second point.
342  //if the thrid point is at the right side, then the points are anti-clockwise
343  double dx1 = MarkerCanditates[i][1].x - MarkerCanditates[i][0].x;
344  double dy1 = MarkerCanditates[i][1].y - MarkerCanditates[i][0].y;
345  double dx2 = MarkerCanditates[i][2].x - MarkerCanditates[i][0].x;
346  double dy2 = MarkerCanditates[i][2].y - MarkerCanditates[i][0].y;
347  double o = ( dx1*dy2 )- ( dy1*dx2 );
348 
349  if ( o < 0.0 ) //if the third point is in the left side, then sort in anti-clockwise order
350  {
351  swap ( MarkerCanditates[i][1],MarkerCanditates[i][3] );
352  swapped[i]=true;
353  //sort the contour points
354  // reverse(MarkerCanditates[i].contour.begin(),MarkerCanditates[i].contour.end());//????
355 
356  }
357  }
358 
360  //first detect candidates
361 
362  vector<pair<int,int> > TooNearCandidates;
363  for ( unsigned int i=0;i<MarkerCanditates.size();i++ )
364  {
365  // cout<<"Marker i="<<i<<MarkerCanditates[i]<<endl;
366  //calculate the average distance of each corner to the nearest corner of the other marker candidate
367  for ( unsigned int j=i+1;j<MarkerCanditates.size();j++ )
368  {
369  float dist=0;
370  for ( int c=0;c<4;c++ )
371  dist+= sqrt ( ( MarkerCanditates[i][c].x-MarkerCanditates[j][c].x ) * ( MarkerCanditates[i][c].x-MarkerCanditates[j][c].x ) + ( MarkerCanditates[i][c].y-MarkerCanditates[j][c].y ) * ( MarkerCanditates[i][c].y-MarkerCanditates[j][c].y ) );
372  dist/=4;
373  //if distance is too small
374  if ( dist< 10 )
375  {
376  TooNearCandidates.push_back ( pair<int,int> ( i,j ) );
377  }
378  }
379  }
380 
381  //mark for removal the element of the pair with smaller perimeter
382  valarray<bool> toRemove ( false,MarkerCanditates.size() );
383  for ( unsigned int i=0;i<TooNearCandidates.size();i++ )
384  {
385  if ( perimeter ( MarkerCanditates[TooNearCandidates[i].first ] ) >perimeter ( MarkerCanditates[ TooNearCandidates[i].second] ) )
386  toRemove[TooNearCandidates[i].second]=true;
387  else toRemove[TooNearCandidates[i].first]=true;
388  }
389 
390  //remove the invalid ones
391  // removeElements ( MarkerCanditates,toRemove );
392  //finally, assign to the remaining candidates the contour
393  OutMarkerCanditates.reserve(MarkerCanditates.size());
394  for (size_t i=0;i<MarkerCanditates.size();i++) {
395  if (!toRemove[i]) {
396  OutMarkerCanditates.push_back(MarkerCanditates[i]);
397  OutMarkerCanditates.back().contour=contours2[ MarkerCanditates[i].idx];
398  if (swapped[i] && _enableCylinderWarp )//if the corners where swapped, it is required to reverse here the points so that they are in the same order
399  reverse(OutMarkerCanditates.back().contour.begin(),OutMarkerCanditates.back().contour.end());//????
400  }
401  }
402 
403  }
404 
405  /************************************
406  *
407  *
408  *
409  *
410  ************************************/
411  void MarkerDetector::thresHold ( int method,const Mat &grey_m,Mat &out,double param1,double param2 ) throw ( cv::Exception )
412  {
413 #pragma GCC diagnostic push
414 #pragma GCC diagnostic ignored "-Wfloat-equal"
415  if (param1==-1) param1=_thresParam1;
416  if (param2==-1) param2=_thresParam2;
417 #pragma GCC diagnostic pop
418 
419  if ( grey_m.type() !=CV_8UC1 ) throw cv::Exception ( 9001,"grey_m.type()!=CV_8UC1","MarkerDetector::thresHold",__FILE__,__LINE__ );
420  switch ( method )
421  {
422  case FIXED_THRES:
423  cv::threshold ( grey_m, out, param1,255, CV_THRESH_BINARY_INV );
424  break;
425  case ADPT_THRES://currently, this is the best method
426  //ensure that _thresParam1%2==1
427  if ( param1<3 ) param1=3;
428  else if ( ( ( int ) param1 ) %2 !=1 ) param1= ( int ) ( param1+1 );
429 
430  cv::adaptiveThreshold ( grey_m,out,255,ADAPTIVE_THRESH_MEAN_C,THRESH_BINARY_INV,param1,param2 );
431  break;
432  case CANNY:
433  {
434  //this should be the best method, and generally it is.
435  //However, some times there are small holes in the marker contour that makes
436  //the contour detector not to find it properly
437  //if there is a missing pixel
438  cv::Canny ( grey_m, out, 10, 220 );
439  //I've tried a closing but it add many more points that some
440  //times makes this even worse
441  // Mat aux;
442  // cv::morphologyEx(thres,aux,MORPH_CLOSE,Mat());
443  // out=aux;
444  }
445  break;
446  }
447  }
448  /************************************
449  *
450  *
451  *
452  *
453  ************************************/
454  bool MarkerDetector::warp ( Mat &in,Mat &out,Size size, vector<Point2f> points ) throw ( cv::Exception )
455  {
456 
457  if ( points.size() !=4 ) throw cv::Exception ( 9001,"point.size()!=4","MarkerDetector::warp",__FILE__,__LINE__ );
458  //obtain the perspective transform
459  Point2f pointsRes[4],pointsIn[4];
460  for ( int i=0;i<4;i++ ) pointsIn[i]=points[i];
461  pointsRes[0]= ( Point2f ( 0,0 ) );
462  pointsRes[1]= Point2f ( size.width-1,0 );
463  pointsRes[2]= Point2f ( size.width-1,size.height-1 );
464  pointsRes[3]= Point2f ( 0,size.height-1 );
465  Mat M=getPerspectiveTransform ( pointsIn,pointsRes );
466  cv::warpPerspective ( in, out, M, size,cv::INTER_NEAREST );
467  return true;
468  }
469 
470  void findCornerPointsInContour(const vector<cv::Point2f>& points,const vector<cv::Point> &contour,vector<int> &idxs)
471  {
472  assert(points.size()==4);
473  int idxSegments[4]={-1,-1,-1,-1};
474  //the first point coincides with one
475  cv::Point points2i[4];
476  for (int i=0;i<4;i++) {
477  points2i[i].x=points[i].x;
478  points2i[i].y=points[i].y;
479  }
480 
481  for (size_t i=0;i<contour.size();++i) {
482  if (idxSegments[0]==-1)
483  if (contour[i]==points2i[0]) idxSegments[0]=i;
484  if (idxSegments[1]==-1)
485  if (contour[i]==points2i[1]) idxSegments[1]=i;
486  if (idxSegments[2]==-1)
487  if (contour[i]==points2i[2]) idxSegments[2]=i;
488  if (idxSegments[3]==-1)
489  if (contour[i]==points2i[3]) idxSegments[3]=i;
490  }
491  idxs.resize(4);
492  for (int i=0;i<4;i++) idxs[i]=idxSegments[i];
493  }
494 
495  int findDeformedSidesIdx(const vector<cv::Point> &contour,const vector<int> &idxSegments)
496  {
497  float distSum[4]={0,0,0,0};
498 
499  for (int i=0;i<3;i++) {
500  cv::Point p1=contour[ idxSegments[i]];
501  cv::Point p2=contour[ idxSegments[i+1]];
502  float inv_den=1./ sqrt(float(( p2.x-p1.x)*(p2.x-p1.x)+ (p2.y-p1.y)*(p2.y-p1.y)));
503  // d=|v^^·r|=(|(x_2-x_1)(y_1-y_0)-(x_1-x_0)(y_2-y_1)|)/(sqrt((x_2-x_1)^2+(y_2-y_1)^2)).
504  // cerr<<"POSS="<<idxSegments[i]<<" "<<idxSegments[i+1]<<endl;
505  for (int j=idxSegments[i];j<idxSegments[i+1];++j) {
506  float dist=std::fabs( float( (p2.x-p1.x)*(p1.y-contour[j].y)- (p1.x-contour[j].x)*(p2.y-p1.y)) )*inv_den;
507  distSum[i]+=dist;
508  // cerr<< dist<<" ";
509  // cv::rectangle(_ssImC,contour[j],contour[j],colors[i],-1);
510  }
511  distSum[i]/=float(idxSegments[i+1]-idxSegments[i]);
512  // cout<<endl<<endl;
513  }
514 
515 
516  //for the last one
517  cv::Point p1=contour[ idxSegments[0]];
518  cv::Point p2=contour[ idxSegments[3]];
519  float inv_den=1./ std::sqrt(float(( p2.x-p1.x)*(p2.x-p1.x)+ (p2.y-p1.y)*(p2.y-p1.y)));
520  // d=|v^^·r|=(|(x_2-x_1)(y_1-y_0)-(x_1-x_0)(y_2-y_1)|)/(sqrt((x_2-x_1)^2+(y_2-y_1)^2)).
521  for (int j=0;j<idxSegments[0];++j)
522  distSum[3]+=std::fabs( float((p2.x-p1.x)*(p1.y-contour[j].y)- (p1.x-contour[j].x)*(p2.y-p1.y)))*inv_den;
523  for (int j=idxSegments[3];j<static_cast<int>(contour.size());++j)
524  distSum[3]+=std::fabs( float((p2.x-p1.x)*(p1.y-contour[j].y)- (p1.x-contour[j].x)*(p2.y-p1.y)))*inv_den;
525 
526  distSum[3]/=float( idxSegments[0]+ (contour.size()-idxSegments[3]));
527  //now, get the maximum
528  /* for (int i=0;i<4;i++)
529  cout<<"DD="<<distSum[i]<<endl;*/
530  //check the two combinations to see the one with higher error
531  if ( distSum[0]+distSum[2]> distSum[1]+distSum[3])
532  return 0;
533  else return 1;
534  }
535 
536  void setPointIntoImage(cv::Point2f &p,cv::Size s) {
537  if (p.x<0) p.x=0;
538  else if (p.x>=s.width )p.x=s.width-1;
539  if (p.y<0)p.y=0;
540  else if (p.y>=s.height)p.y=s.height-1;
541 
542  }
543 
544  void setPointIntoImage(cv::Point &p,cv::Size s) {
545  if (p.x<0) p.x=0;
546  else if (p.x>=s.width )p.x=s.width-1;
547  if (p.y<0)p.y=0;
548  else if (p.y>=s.height)p.y=s.height-1;
549 
550  }
551  /************************************
552  *
553  *
554  *
555  *
556  ************************************/
557  bool MarkerDetector::warp_cylinder ( Mat &in,Mat &out,Size size, MarkerCandidate& mcand ) throw ( cv::Exception )
558  {
559 
560  if ( mcand.size() !=4 ) throw cv::Exception ( 9001,"point.size()!=4","MarkerDetector::warp",__FILE__,__LINE__ );
561 
562  //check first the real need for cylinder warping
563  // cout<<"im="<<mcand.contour.size()<<endl;
564 
565  // for (size_t i=0;i<mcand.contour.size();i++) {
566  // cv::rectangle(_ssImC ,mcand.contour[i],mcand.contour[i],cv::Scalar(111,111,111),-1 );
567  // }
568  // mcand.draw(imC,cv::Scalar(0,255,0));
569  //find the 4 different segments of the contour
570  vector<int> idxSegments;
571  findCornerPointsInContour(mcand,mcand.contour,idxSegments);
572  //let us rearrange the points so that the first corner is the one whith smaller idx
573  int minIdx=0;
574  for (int i=1;i<4;i++)
575  if (idxSegments[i] <idxSegments[minIdx]) minIdx=i;
576  //now, rotate the points to be in this order
577  std::rotate(idxSegments.begin(),idxSegments.begin()+minIdx,idxSegments.end());
578  std::rotate(mcand.begin(),mcand.begin()+minIdx,mcand.end());
579 
580  // cout<<"idxSegments="<<idxSegments[0]<< " "<<idxSegments[1]<< " "<<idxSegments[2]<<" "<<idxSegments[3]<<endl;
581  //now, determine the sides that are deformated by cylinder perspective
582  int defrmdSide=findDeformedSidesIdx(mcand.contour,idxSegments);
583  // cout<<"Def="<<defrmdSide<<endl;
584 
585  //instead of removing perspective distortion of the rectangular region
586  //given by the rectangle, we enlarge it a bit to include the deformed parts
587  Point2f enlargedRegion[4];
588  for (int i=0;i<4;i++) enlargedRegion[i]=mcand[i];
589  if (defrmdSide==0) {
590  enlargedRegion[0]=mcand[0]+(mcand[3]-mcand[0])*1.2;
591  enlargedRegion[1]=mcand[1]+(mcand[2]-mcand[1])*1.2;
592  enlargedRegion[2]=mcand[2]+(mcand[1]-mcand[2])*1.2;
593  enlargedRegion[3]=mcand[3]+(mcand[0]-mcand[3])*1.2;
594  }
595  else {
596  enlargedRegion[0]=mcand[0]+(mcand[1]-mcand[0])*1.2;
597  enlargedRegion[1]=mcand[1]+(mcand[0]-mcand[1])*1.2;
598  enlargedRegion[2]=mcand[2]+(mcand[3]-mcand[2])*1.2;
599  enlargedRegion[3]=mcand[3]+(mcand[2]-mcand[3])*1.2;
600  }
601  for (size_t i=0;i<4;i++)
602  setPointIntoImage(enlargedRegion[i],in.size());
603 
604  /*
605  cv::Scalar colors[4]={cv::Scalar(0,0,255),cv::Scalar(255,0,0),cv::Scalar(0,255,0),cv::Scalar(111,111,0)};
606  for (int i=0;i<4;i++) {
607  cv::rectangle(_ssImC,mcand.contour[idxSegments[i]]-cv::Point(2,2),mcand.contour[idxSegments[i]]+cv::Point(2,2),colors[i],-1 );
608  cv::rectangle(_ssImC,enlargedRegion[i]-cv::Point2f(2,2),enlargedRegion[i]+cv::Point2f(2,2),colors[i],-1 );
609 
610  }*/
611  // cv::imshow("imC",_ssImC);
612 
613 
614  //calculate the max distance from each contour point the line of the corresponding segment it belongs to
615  // calculate
616  // cv::waitKey(0);
617  //check that the region is into image limits
618  //obtain the perspective transform
619  Point2f pointsRes[4];
620 
621  cv::Size enlargedSize=size;
622  enlargedSize.width+=2*enlargedSize.width*0.2;
623  pointsRes[0]= ( Point2f ( 0,0 ) );
624  pointsRes[1]= Point2f ( enlargedSize.width-1,0 );
625  pointsRes[2]= Point2f ( enlargedSize.width-1,enlargedSize.height-1 );
626  pointsRes[3]= Point2f ( 0,enlargedSize.height-1 );
627  //rotate to ensure that deformed sides are in the horizontal axis when warping
628  if (defrmdSide==0) rotate(pointsRes,pointsRes+1,pointsRes+4);
629  cv::Mat imAux,imAux2(enlargedSize,CV_8UC1);
630  Mat M=getPerspectiveTransform ( enlargedRegion,pointsRes );
631  cv::warpPerspective ( in, imAux, M, enlargedSize,cv::INTER_NEAREST);
632 
633  //now, transform all points to the new image
634  vector<cv::Point> pointsCO(mcand.contour.size());
635  assert(M.type()==CV_64F);
636  assert(M.cols==3 && M.rows==3);
637  // cout<<M<<endl;
638  double *mptr=M.ptr<double>(0);
639  imAux2.setTo(cv::Scalar::all(0));
640 
641 
642  for (size_t i=0;i<mcand.contour.size();i++) {
643  float inX=mcand.contour[i].x;
644  float inY=mcand.contour[i].y;
645  float w= inX * mptr[6]+inY * mptr[7]+mptr[8];
646  cv::Point2f pres;
647  pointsCO[i].x=( (inX * mptr[0]+inY* mptr[1]+mptr[2])/w)+0.5;
648  pointsCO[i].y=( (inX * mptr[3]+inY* mptr[4]+mptr[5])/w)+0.5;
649  //make integers
650  setPointIntoImage(pointsCO[i],imAux.size());//ensure points are into image limits
651  // cout<<"p="<<pointsCO[i]<<" "<<imAux.size().width<<" "<<imAux.size().height<<endl;
652  imAux2.at<uchar>(pointsCO[i].y,pointsCO[i].x)=255;
653  if (pointsCO[i].y>0)
654  imAux2.at<uchar>(pointsCO[i].y-1,pointsCO[i].x)=255;
655  if (pointsCO[i].y<imAux2.rows-1 )
656  imAux2.at<uchar>(pointsCO[i].y+1,pointsCO[i].x)=255;
657  }
658 
659  cv::Mat outIm(enlargedSize,CV_8UC1);
660  outIm.setTo(cv::Scalar::all(0));
661  //now, scan in lines to determine the required displacement
662  for (int y=0;y<imAux2.rows;y++) {
663  uchar *_offInfo=imAux2.ptr<uchar>(y);
664  int start=-1,end=-1;
665  //determine the start and end of markerd regions
666  for (int x=0;x<imAux.cols;x++) {
667  if (_offInfo[x]) {
668  if (start==-1) start=x;
669  else end=x;
670  }
671  }
672  // cout<<"S="<<start<<" "<<end<<" "<<end-start<<" "<<(size.width>>1)<<endl;
673  //check that the size is big enough and
674  assert(start!=-1 && end!=-1 && (end-start)> size.width>>1);
675  uchar *In_image=imAux.ptr<uchar>(y);
676  uchar *Out_image=outIm.ptr<uchar>(y);
677  memcpy(Out_image,In_image+start,imAux.cols-start );
678  }
679 
680 
681  // cout<<"SS="<<mcand.contour.size()<<" "<<pointsCO.size()<<endl;
682  //get the central region with the size specified
683  cv::Mat centerReg=outIm(cv::Range::all(),cv::Range(0,size.width));
684  out=centerReg.clone();
685  // cv::perspectiveTransform(mcand.contour,pointsCO,M);
686  //draw them
687  // cv::imshow("out2",out);
688  // cv::imshow("imm",imAux2);
689  // cv::waitKey(0);
690  return true;
691  }
692  /************************************
693  *
694  *
695  *
696  *
697  ************************************/
698  bool MarkerDetector::isInto ( Mat &contour,vector<Point2f> &b )
699  {
700 
701  for ( size_t i=0;i<b.size();i++ )
702  if ( pointPolygonTest ( contour,b[i],false ) >0 ) return true;
703  return false;
704  }
705  /************************************
706  *
707  *
708  *
709  *
710  ************************************/
711  int MarkerDetector:: perimeter ( vector<Point2f> &a )
712  {
713  int sum=0;
714  for ( size_t i=0;i<a.size();i++ )
715  {
716  int i2= ( i+1 ) %a.size();
717  sum+= sqrt ( ( a[i].x-a[i2].x ) * ( a[i].x-a[i2].x ) + ( a[i].y-a[i2].y ) * ( a[i].y-a[i2].y ) ) ;
718  }
719  return sum;
720  }
721 
722 
727  void MarkerDetector::findBestCornerInRegion_harris ( const cv::Mat & grey_m,vector<cv::Point2f> & Corners,int blockSize )
728  {
729  int halfSize=blockSize/2;
730  for ( size_t i=0;i<Corners.size();i++ )
731  {
732  //check that the region is into the image limits
733  cv::Point2f min ( Corners[i].x-halfSize,Corners[i].y-halfSize );
734  cv::Point2f max ( Corners[i].x+halfSize,Corners[i].y+halfSize );
735  if ( min.x>=0 && min.y>=0 && max.x<grey_m.cols && max.y<grey_m.rows )
736  {
737  cv::Mat response;
738  cv::Mat subImage ( grey_m,cv::Rect ( Corners[i].x-halfSize,Corners[i].y-halfSize,blockSize ,blockSize ) );
739  vector<Point2f> corners2;
740  goodFeaturesToTrack ( subImage, corners2, 10, 0.001, halfSize );
741  float minD=9999;
742  int bIdx=-1;
743  cv::Point2f Center ( halfSize,halfSize );
744  for ( size_t j=0;j<corners2.size();j++ )
745  {
746  float dist=cv::norm ( corners2[j]-Center );
747  if ( dist<minD )
748  {
749  minD=dist;
750  bIdx=j;
751  }
752  if ( minD<halfSize ) Corners[i]+= ( corners2[bIdx]-Center );
753  }
754  }
755  }
756  }
757 
758 
763  void MarkerDetector::refineCandidateLines(MarkerDetector::MarkerCandidate& candidate)
764  {
765  // search corners on the contour vector
766  vector<size_t> cornerIndex;
767  cornerIndex.resize(4);
768  for(size_t j=0; j<candidate.contour.size(); ++j) {
769  for(size_t k=0; k<4; ++k) {
770 #pragma GCC diagnostic push
771 #pragma GCC diagnostic ignored "-Wfloat-equal"
772  if(candidate.contour[j].x==candidate[k].x && candidate.contour[j].y==candidate[k].y) {
773  cornerIndex[k] = j;
774  }
775 #pragma GCC diagnostic pop
776  }
777  }
778 
779  // contour pixel in inverse order or not?
780  bool inverse;
781  if( (cornerIndex[1] > cornerIndex[0]) && (cornerIndex[2]>cornerIndex[1] || cornerIndex[2]<cornerIndex[0]) )
782  inverse = false;
783  else if( cornerIndex[2]>cornerIndex[1] && cornerIndex[2]<cornerIndex[0] )
784  inverse = false;
785  else inverse = true;
786 
787 
788  // get pixel vector for each line of the marker
789  int inc = 1;
790  if(inverse) inc = -1;
791 
792  vector<std::vector<cv::Point> > contourLines;
793  contourLines.resize(4);
794  for(unsigned int l=0; l<4; ++l) {
795  for(int j=(int)cornerIndex[l]; j!=(int)cornerIndex[(l+1)%4]; j+=inc) {
796  if(j==(int)candidate.contour.size() && !inverse) j=0;
797  else if(j==0 && inverse) j=candidate.contour.size()-1;
798  contourLines[l].push_back(candidate.contour[j]);
799  if(j==(int)cornerIndex[(l+1)%4]) break; // this has to be added because of the previous ifs
800  }
801 
802  }
803 
804  // interpolate marker lines
805  vector<Point3f> lines;
806  lines.resize(4);
807  for(unsigned int j=0; j<lines.size(); ++j)
808  interpolate2Dline(contourLines[j], lines[j]);
809 
810  // get cross points of lines
811  vector<Point2f> crossPoints;
812  crossPoints.resize(4);
813  for(unsigned int i=0; i<4; ++i)
814  crossPoints[i] = getCrossPoint( lines[(i-1)%4], lines[i] );
815 
816  // reassing points
817  for(unsigned int j=0; j<4; ++j)
818  candidate[j] = crossPoints[j];
819  }
820 
821 
824  void MarkerDetector::interpolate2Dline( const std::vector< Point >& inPoints, Point3f& outLine)
825  {
826 
827  float minX, maxX, minY, maxY;
828  minX = maxX = inPoints[0].x;
829  minY = maxY = inPoints[0].y;
830  for(unsigned int i=1; i<inPoints.size(); ++i) {
831  if(inPoints[i].x < minX) minX = inPoints[i].x;
832  if(inPoints[i].x > maxX) maxX = inPoints[i].x;
833  if(inPoints[i].y < minY) minY = inPoints[i].y;
834  if(inPoints[i].y > maxY) maxY = inPoints[i].y;
835  }
836 
837  // create matrices of equation system
838  Mat A(inPoints.size(),2,CV_32FC1, Scalar(0));
839  Mat B(inPoints.size(),1,CV_32FC1, Scalar(0));
840  Mat X;
841 
842 
843 
844  if( maxX-minX > maxY-minY ) {
845  // Ax + C = y
846  for (size_t i=0; i<inPoints.size(); ++i) {
847 
848  A.at<float>(i, 0) = inPoints[i].x;
849  A.at<float>(i, 1) = 1.;
850  B.at<float>(i, 0) = inPoints[i].y;
851 
852  }
853 
854  // solve system
855  solve(A,B,X, DECOMP_SVD);
856  // return Ax + By + C
857  outLine = Point3f(X.at<float>(0,0), -1., X.at<float>(1,0));
858  }
859  else {
860  // By + C = x
861  for (size_t i=0; i<inPoints.size(); ++i) {
862 
863  A.at<float>(i, 0) = inPoints[i].y;
864  A.at<float>(i, 1) = 1.;
865  B.at<float>(i, 0) = inPoints[i].x;
866 
867  }
868 
869  // solve system
870  solve(A,B,X, DECOMP_SVD);
871  // return Ax + By + C
872  outLine = Point3f(-1., X.at<float>(0,0), X.at<float>(1,0));
873  }
874 
875  }
876 
879  Point2f MarkerDetector::getCrossPoint(const cv::Point3f& line1, const cv::Point3f& line2)
880  {
881 
882  // create matrices of equation system
883  Mat A(2,2,CV_32FC1, Scalar(0));
884  Mat B(2,1,CV_32FC1, Scalar(0));
885  Mat X;
886 
887  A.at<float>(0, 0) = line1.x;
888  A.at<float>(0, 1) = line1.y;
889  B.at<float>(0, 0) = -line1.z;
890 
891  A.at<float>(1, 0) = line2.x;
892  A.at<float>(1, 1) = line2.y;
893  B.at<float>(1, 0) = -line2.z;
894 
895  // solve system
896  solve(A,B,X, DECOMP_SVD);
897  return Point2f(X.at<float>(0,0), X.at<float>(1,0));
898 
899  }
900 
901 
902 
903 
904 
905 
906 
907 
908  /************************************
909  *
910  *
911  *
912  *
913  ************************************/
914  void MarkerDetector::drawAllContours ( Mat input, std::vector<std::vector<cv::Point> > &contours )
915  {
916  drawContours ( input, contours, -1,Scalar ( 255,0,255 ) );
917  }
918 
919  /************************************
920  *
921  *
922  *
923  *
924  ************************************/
925  void MarkerDetector:: drawContour ( Mat &in,vector<Point> &contour,Scalar color )
926  {
927  for ( size_t i=0;i<contour.size();++i )
928  {
929  cv::rectangle ( in,contour[i],contour[i],color );
930  }
931  }
932 
933  void MarkerDetector:: drawApproxCurve ( Mat &in,vector<Point> &contour,Scalar color )
934  {
935  for ( size_t i=0;i<contour.size();++i )
936  {
937  cv::line ( in,contour[i],contour[ ( i+1 ) %contour.size() ],color );
938  }
939  }
940  /************************************
941  *
942  *
943  *
944  *
945  ************************************/
946 
947  void MarkerDetector::draw ( Mat out,const vector<Marker> &markers )
948  {
949  for ( size_t i=0;i<markers.size();++i )
950  {
951  cv::line ( out,markers[i][0],markers[i][1],cvScalar ( 255,0,0 ),2,CV_AA );
952  cv::line ( out,markers[i][1],markers[i][2],cvScalar ( 255,0,0 ),2,CV_AA );
953  cv::line ( out,markers[i][2],markers[i][3],cvScalar ( 255,0,0 ),2,CV_AA );
954  cv::line ( out,markers[i][3],markers[i][0],cvScalar ( 255,0,0 ),2,CV_AA );
955  }
956  }
957  /* Attempt to make it faster than in opencv. I could not :( Maybe trying with SSE3...
958 void MarkerDetector::warpPerspective(const cv::Mat &in,cv::Mat & out, const cv::Mat & M,cv::Size size)
959 {
960  //inverse the matrix
961  out.create(size,in.type());
962  //convert to float to speed up operations
963  const double *m=M.ptr<double>(0);
964  float mf[9];
965  mf[0]=m[0];mf[1]=m[1];mf[2]=m[2];
966  mf[3]=m[3];mf[4]=m[4];mf[5]=m[5];
967  mf[6]=m[6];mf[7]=m[7];mf[8]=m[8];
968 
969  for(int y=0;y<out.rows;y++){
970  uchar *_ptrout=out.ptr<uchar>(y);
971  for(int x=0;x<out.cols;x++){
972  //get the x,y position
973  float den=1./(x*mf[6]+y*mf[7]+mf[8]);
974  float ox= (x*mf[0]+y*mf[1]+mf[2])*den;
975  float oy= (x*mf[3]+y*mf[4]+mf[5])*den;
976  _ptrout[x]=in.at<uchar>(oy,ox);
977  }
978  }
979 }
980 */
981 
982  /************************************
983  *
984  *
985  *
986  *
987  ************************************/
988 
989  void MarkerDetector::glGetProjectionMatrix ( CameraParameters & CamMatrix,cv::Size orgImgSize, cv::Size size,double proj_matrix[16],double gnear,double gfar,bool invert )
990  throw ( cv::Exception )
991  {
992  cerr<<"MarkerDetector::glGetProjectionMatrix . This a deprecated function. Use CameraParameters::glGetProjectionMatrix instead. "<<__FILE__<<" "<<__LINE__<<endl;
993  CamMatrix.glGetProjectionMatrix ( orgImgSize,size,proj_matrix,gnear,gfar,invert );
994  }
995 
996  /************************************
997 *
998 *
999 *
1000 *
1001 ************************************/
1002 
1003  void MarkerDetector::setMinMaxSize(float min ,float max )throw(cv::Exception)
1004  {
1005  if (min<=0 || min>1) throw cv::Exception(1," min parameter out of range","MarkerDetector::setMinMaxSize",__FILE__,__LINE__);
1006  if (max<=0 || max>1) throw cv::Exception(1," max parameter out of range","MarkerDetector::setMinMaxSize",__FILE__,__LINE__);
1007  if (min>max) throw cv::Exception(1," min>max","MarkerDetector::setMinMaxSize",__FILE__,__LINE__);
1008  _minSize=min;
1009  _maxSize=max;
1010  }
1011 
1012 }
1013 
d
void findCornerPointsInContour(const vector< cv::Point2f > &points, const vector< cv::Point > &contour, vector< int > &idxs)
f
int findDeformedSidesIdx(const vector< cv::Point > &contour, const vector< int > &idxSegments)
void setPointIntoImage(cv::Point &p, cv::Size s)
static int detect(const cv::Mat &in, int &nRotations)
Parameters of the camera.
Mat rotate(Mat in)


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