29 #include <opencv/cv.h> 30 #include <opencv/highgui.h> 46 MarkerDetector::MarkerDetector()
49 _enableCylinderWarp=
false;
50 _thresMethod=ADPT_THRES;
51 _thresParam1=_thresParam2=7;
67 MarkerDetector::~MarkerDetector()
78 void MarkerDetector::setDesiredSpeed (
int val )
81 else if ( val>3 ) val=2;
107 void MarkerDetector::detect (
const cv::Mat &input,std::vector<Marker> &detectedMarkers,
CameraParameters camParams ,
float markerSizeMeters ,
bool setYPerpendicular)
throw ( cv::Exception )
109 detect ( input, detectedMarkers,camParams.CameraMatrix ,camParams.Distorsion, markerSizeMeters ,setYPerpendicular);
119 void MarkerDetector::detect (
const cv::Mat &input,vector<Marker> &detectedMarkers,Mat camMatrix ,Mat distCoeff ,
float markerSizeMeters ,
bool setYPerpendicular)
throw ( cv::Exception )
124 if ( input.type() ==CV_8UC3 ) cv::cvtColor ( input,grey,CV_BGR2GRAY );
131 detectedMarkers.clear();
134 cv::Mat imgToBeThresHolded=grey;
135 double ThresParam1=_thresParam1,ThresParam2=_thresParam2;
137 if ( pyrdown_level!=0 )
140 for (
int i=0;i<pyrdown_level;i++ )
143 cv::pyrDown ( reduced,tmp );
146 int red_den=pow ( 2.0
f,pyrdown_level );
147 imgToBeThresHolded=reduced;
148 ThresParam1/=float ( red_den );
149 ThresParam2/=float ( red_den );
153 thresHold ( _thresMethod,imgToBeThresHolded,thres,ThresParam1,ThresParam2 );
158 erode ( thres,thres2,cv::Mat() );
163 vector<MarkerCandidate > MarkerCanditates;
164 detectRectangles ( thres,MarkerCanditates );
166 if ( pyrdown_level!=0 )
168 float red_den=pow ( 2.0
f,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++ )
173 MarkerCanditates[i][c].x=MarkerCanditates[i][c].x*red_den+offInc;
174 MarkerCanditates[i][c].y=MarkerCanditates[i][c].y*red_den+offInc;
177 for (
size_t c=0;c<MarkerCanditates[i].contour.size();++c )
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;
187 for (
unsigned int i=0;i<MarkerCanditates.size();++i )
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] );
197 int id= ( *markerIdDetector_ptrfunc ) ( canonicalMarker,nRotations );
200 if(_cornerMethod==LINES) refineCandidateLines( MarkerCanditates[i] );
201 detectedMarkers.push_back ( MarkerCanditates[i] );
202 detectedMarkers.back().id=id;
204 std::rotate ( detectedMarkers.back().begin(),detectedMarkers.back().begin() +4-nRotations,detectedMarkers.back().end() );
206 else _candidates.push_back ( MarkerCanditates[i] );
213 if ( detectedMarkers.size() >0 && _cornerMethod!=NONE && _cornerMethod!=LINES )
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] );
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 ) );
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];
230 std::sort ( detectedMarkers.begin(),detectedMarkers.end() );
233 vector<bool> toRemove ( detectedMarkers.size(),false );
234 for (
int i=0;i<int ( detectedMarkers.size() )-1;++i )
236 if ( detectedMarkers[i].
id==detectedMarkers[i+1].
id && !toRemove[i+1] )
239 if ( perimeter ( detectedMarkers[i] ) >perimeter ( detectedMarkers[i+1] ) ) toRemove[i+1]=
true;
240 else toRemove[i]=
true;
244 removeElements ( detectedMarkers, toRemove );
247 if ( camMatrix.rows!=0 && markerSizeMeters>0 )
249 for (
unsigned int i=0;i<detectedMarkers.size();i++ )
250 detectedMarkers[i].calculateExtrinsics ( markerSizeMeters,camMatrix,distCoeff,setYPerpendicular );
261 void MarkerDetector::detectRectangles (
const cv::Mat &thresold,vector<std::vector<cv::Point2f> > &MarkerCanditates )
263 vector<MarkerCandidate> candidates;
264 detectRectangles(thresold,candidates);
266 MarkerCanditates.resize(candidates.size());
267 for (
size_t i=0;i<MarkerCanditates.size();i++)
268 MarkerCanditates[i]=candidates[i];
271 void MarkerDetector::detectRectangles(
const cv::Mat &thresImg,vector<MarkerCandidate> & OutMarkerCanditates)
273 vector<MarkerCandidate> MarkerCanditates;
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;
280 thresImg.copyTo ( thres2 );
281 cv::findContours ( thres2 , contours2, hierarchy2,CV_RETR_TREE, CV_CHAIN_APPROX_NONE );
282 vector<Point> approxCurve;
285 for (
unsigned int i=0;i<contours2.size();i++ )
290 if ( minSize< contours2[i].size() &&contours2[i].size()<maxSize )
293 approxPolyDP ( contours2[i] ,approxCurve ,
double ( contours2[i].size() ) *0.05 ,
true );
296 if ( approxCurve.size() ==4 )
304 if ( isContourConvex ( Mat ( approxCurve ) ) )
309 for (
int j=0;j<4;j++ )
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 ) );
314 if ( d<minDist ) minDist=d;
322 MarkerCanditates.back().idx=i;
323 for (
int j=0;j<4;j++ )
325 MarkerCanditates.back().push_back ( Point2f ( approxCurve[j].x,approxCurve[j].y ) );
337 valarray<bool> swapped(
false,MarkerCanditates.size());
338 for (
unsigned int i=0;i<MarkerCanditates.size();i++ )
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 );
351 swap ( MarkerCanditates[i][1],MarkerCanditates[i][3] );
362 vector<pair<int,int> > TooNearCandidates;
363 for (
unsigned int i=0;i<MarkerCanditates.size();i++ )
367 for (
unsigned int j=i+1;j<MarkerCanditates.size();j++ )
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 ) );
376 TooNearCandidates.push_back ( pair<int,int> ( i,j ) );
382 valarray<bool> toRemove (
false,MarkerCanditates.size() );
383 for (
unsigned int i=0;i<TooNearCandidates.size();i++ )
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;
393 OutMarkerCanditates.reserve(MarkerCanditates.size());
394 for (
size_t i=0;i<MarkerCanditates.size();i++) {
396 OutMarkerCanditates.push_back(MarkerCanditates[i]);
397 OutMarkerCanditates.back().contour=contours2[ MarkerCanditates[i].idx];
398 if (swapped[i] && _enableCylinderWarp )
399 reverse(OutMarkerCanditates.back().contour.begin(),OutMarkerCanditates.back().contour.end());
411 void MarkerDetector::thresHold (
int method,
const Mat &grey_m,Mat &out,
double param1,
double param2 )
throw ( cv::Exception )
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 419 if ( grey_m.type() !=CV_8UC1 )
throw cv::Exception ( 9001,
"grey_m.type()!=CV_8UC1",
"MarkerDetector::thresHold",__FILE__,__LINE__ );
423 cv::threshold ( grey_m, out, param1,255, CV_THRESH_BINARY_INV );
427 if ( param1<3 ) param1=3;
428 else if ( ( (
int ) param1 ) %2 !=1 ) param1= ( int ) ( param1+1 );
430 cv::adaptiveThreshold ( grey_m,out,255,ADAPTIVE_THRESH_MEAN_C,THRESH_BINARY_INV,param1,param2 );
438 cv::Canny ( grey_m, out, 10, 220 );
454 bool MarkerDetector::warp ( Mat &in,Mat &out,Size size, vector<Point2f> points )
throw ( cv::Exception )
457 if ( points.size() !=4 )
throw cv::Exception ( 9001,
"point.size()!=4",
"MarkerDetector::warp",__FILE__,__LINE__ );
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 );
472 assert(points.size()==4);
473 int idxSegments[4]={-1,-1,-1,-1};
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;
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;
492 for (
int i=0;i<4;i++) idxs[i]=idxSegments[i];
497 float distSum[4]={0,0,0,0};
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)));
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;
511 distSum[i]/=float(idxSegments[i+1]-idxSegments[i]);
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)));
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;
526 distSum[3]/=float( idxSegments[0]+ (contour.size()-idxSegments[3]));
531 if ( distSum[0]+distSum[2]> distSum[1]+distSum[3])
538 else if (p.x>=s.width )p.x=s.width-1;
540 else if (p.y>=s.height)p.y=s.height-1;
546 else if (p.x>=s.width )p.x=s.width-1;
548 else if (p.y>=s.height)p.y=s.height-1;
557 bool MarkerDetector::warp_cylinder ( Mat &in,Mat &out,Size size,
MarkerCandidate& mcand )
throw ( cv::Exception )
560 if ( mcand.size() !=4 )
throw cv::Exception ( 9001,
"point.size()!=4",
"MarkerDetector::warp",__FILE__,__LINE__ );
570 vector<int> idxSegments;
574 for (
int i=1;i<4;i++)
575 if (idxSegments[i] <idxSegments[minIdx]) minIdx=i;
577 std::rotate(idxSegments.begin(),idxSegments.begin()+minIdx,idxSegments.end());
578 std::rotate(mcand.begin(),mcand.begin()+minIdx,mcand.end());
587 Point2f enlargedRegion[4];
588 for (
int i=0;i<4;i++) enlargedRegion[i]=mcand[i];
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;
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;
601 for (
size_t i=0;i<4;i++)
619 Point2f pointsRes[4];
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 );
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);
634 vector<cv::Point> pointsCO(mcand.contour.size());
635 assert(M.type()==CV_64F);
636 assert(M.cols==3 && M.rows==3);
638 double *mptr=M.ptr<
double>(0);
639 imAux2.setTo(cv::Scalar::all(0));
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];
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;
652 imAux2.at<uchar>(pointsCO[i].y,pointsCO[i].x)=255;
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;
659 cv::Mat outIm(enlargedSize,CV_8UC1);
660 outIm.setTo(cv::Scalar::all(0));
662 for (
int y=0;y<imAux2.rows;y++) {
663 uchar *_offInfo=imAux2.ptr<uchar>(y);
666 for (
int x=0;x<imAux.cols;x++) {
668 if (start==-1) start=x;
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 );
683 cv::Mat centerReg=outIm(cv::Range::all(),cv::Range(0,size.width));
684 out=centerReg.clone();
698 bool MarkerDetector::isInto ( Mat &contour,vector<Point2f> &b )
701 for (
size_t i=0;i<b.size();i++ )
702 if ( pointPolygonTest ( contour,b[i],
false ) >0 )
return true;
711 int MarkerDetector:: perimeter ( vector<Point2f> &a )
714 for (
size_t i=0;i<a.size();i++ )
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 ) ) ;
727 void MarkerDetector::findBestCornerInRegion_harris (
const cv::Mat & grey_m,vector<cv::Point2f> & Corners,
int blockSize )
729 int halfSize=blockSize/2;
730 for (
size_t i=0;i<Corners.size();i++ )
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 )
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 );
743 cv::Point2f Center ( halfSize,halfSize );
744 for (
size_t j=0;j<corners2.size();j++ )
746 float dist=cv::norm ( corners2[j]-Center );
752 if ( minD<halfSize ) Corners[i]+= ( corners2[bIdx]-Center );
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) {
775 #pragma GCC diagnostic pop 781 if( (cornerIndex[1] > cornerIndex[0]) && (cornerIndex[2]>cornerIndex[1] || cornerIndex[2]<cornerIndex[0]) )
783 else if( cornerIndex[2]>cornerIndex[1] && cornerIndex[2]<cornerIndex[0] )
790 if(inverse) inc = -1;
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;
805 vector<Point3f> lines;
807 for(
unsigned int j=0; j<lines.size(); ++j)
808 interpolate2Dline(contourLines[j], lines[j]);
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] );
817 for(
unsigned int j=0; j<4; ++j)
818 candidate[j] = crossPoints[j];
824 void MarkerDetector::interpolate2Dline(
const std::vector< Point >& inPoints, Point3f& outLine)
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;
838 Mat A(inPoints.size(),2,CV_32FC1, Scalar(0));
839 Mat B(inPoints.size(),1,CV_32FC1, Scalar(0));
844 if( maxX-minX > maxY-minY ) {
846 for (
size_t i=0; i<inPoints.size(); ++i) {
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;
855 solve(A,B,X, DECOMP_SVD);
857 outLine = Point3f(X.at<
float>(0,0), -1., X.at<
float>(1,0));
861 for (
size_t i=0; i<inPoints.size(); ++i) {
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;
870 solve(A,B,X, DECOMP_SVD);
872 outLine = Point3f(-1., X.at<
float>(0,0), X.at<
float>(1,0));
879 Point2f MarkerDetector::getCrossPoint(
const cv::Point3f& line1,
const cv::Point3f& line2)
883 Mat A(2,2,CV_32FC1, Scalar(0));
884 Mat B(2,1,CV_32FC1, Scalar(0));
887 A.at<
float>(0, 0) = line1.x;
888 A.at<
float>(0, 1) = line1.y;
889 B.at<
float>(0, 0) = -line1.z;
891 A.at<
float>(1, 0) = line2.x;
892 A.at<
float>(1, 1) = line2.y;
893 B.at<
float>(1, 0) = -line2.z;
896 solve(A,B,X, DECOMP_SVD);
897 return Point2f(X.at<
float>(0,0), X.at<
float>(1,0));
914 void MarkerDetector::drawAllContours ( Mat input, std::vector<std::vector<cv::Point> > &contours )
916 drawContours ( input, contours, -1,Scalar ( 255,0,255 ) );
925 void MarkerDetector:: drawContour ( Mat &in,vector<Point> &contour,Scalar color )
927 for (
size_t i=0;i<contour.size();++i )
929 cv::rectangle ( in,contour[i],contour[i],color );
933 void MarkerDetector:: drawApproxCurve ( Mat &in,vector<Point> &contour,Scalar color )
935 for (
size_t i=0;i<contour.size();++i )
937 cv::line ( in,contour[i],contour[ ( i+1 ) %contour.size() ],color );
947 void MarkerDetector::draw ( Mat out,
const vector<Marker> &markers )
949 for (
size_t i=0;i<markers.size();++i )
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 );
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 )
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 );
1003 void MarkerDetector::setMinMaxSize(
float min ,
float max )
throw(cv::Exception)
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__);
void findCornerPointsInContour(const vector< cv::Point2f > &points, const vector< cv::Point > &contour, vector< int > &idxs)
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)
vector< cv::Point > contour
Parameters of the camera.