$search
00001 #include "aruco/markerdetector.h" 00002 #include <opencv/cv.h> 00003 #include <opencv/highgui.h> 00004 #include <iostream> 00005 #include <fstream> 00006 00007 using namespace std; 00008 using namespace cv; 00009 00010 namespace aruco 00011 { 00012 /************************************ 00013 * 00014 * 00015 * 00016 * 00017 ************************************/ 00018 MarkerDetector::MarkerDetector() 00019 { 00020 _thresMethod=ADPT_THRES; 00021 _thresParam1=_thresParam2=7; 00022 } 00023 /************************************ 00024 * 00025 * 00026 * 00027 * 00028 ************************************/ 00029 00030 MarkerDetector::~MarkerDetector() 00031 { 00032 00033 } 00034 00035 void MarkerDetector::detect(cv::Mat &input,std::vector<Marker> &detectedMarkers, CameraParameters camParams ,float markerSizeMeters ) throw (cv::Exception) 00036 { 00037 detect( input, detectedMarkers,camParams.CameraMatrix ,camParams.Distorsion, markerSizeMeters ); 00038 00039 } 00040 00041 /************************************ 00042 * 00043 * 00044 * 00045 * 00046 ************************************/ 00047 void MarkerDetector::detect(Mat &input,vector<Marker> &detectedMarkers,Mat camMatrix ,Mat distCoeff ,float markerSizeMeters ) throw (cv::Exception) 00048 { 00049 //it must be a 3 channel image 00050 if (input.type()!=CV_8UC3) throw cv::Exception(9000,"input.type()!=CV_8UC3","MarkerDetector::detect",__FILE__,__LINE__); 00051 vector<Marker> MarkerCanditates; 00052 detectedMarkers.clear(); 00053 00054 00056 cv::cvtColor(input,grey,CV_BGR2GRAY); 00057 thresHold(_thresMethod,grey,thres); 00058 //pass a copy to findContours because the function modifies it 00059 thres.copyTo(thres2); 00060 cv::findContours( thres2 , contours2, hierarchy2,CV_RETR_TREE, CV_CHAIN_APPROX_NONE ); 00061 vector<Point> approxCurve; 00063 for (unsigned int i=0;i<contours2.size();i++) 00064 { 00065 00066 00067 //check it is a possible element by first checking is has enough points 00068 // if (contours2[i].size()>(unsigned int)(input.cols /5)) 00069 { 00070 //approximate to a poligon 00071 approxPolyDP( Mat (contours2[i]),approxCurve , double(contours2[i].size())*0.05 , true); 00072 // drawApproxCurve(copy,approxCurve,Scalar(0,0,255)); 00073 //check that the poligon has 4 points 00074 if (approxCurve.size()==4) 00075 { 00076 00077 // drawContour(input,contours2[i],Scalar(255,0,225)); 00078 // namedWindow("input"); 00079 // imshow("input",input); 00080 // waitKey(0); 00081 //and is convex 00082 if (isContourConvex(Mat (approxCurve))) 00083 { 00084 // drawApproxCurve(input,approxCurve,Scalar(255,0,255)); 00085 // //ensure that the distace between consecutive points is large enough 00086 float minDist=1e10; 00087 for (int i=0;i<4;i++) 00088 { 00089 float d= sqrt( (approxCurve[i].x-approxCurve[(i+1)%4].x)*(approxCurve[i].x-approxCurve[(i+1)%4].x) + 00090 (approxCurve[i].y-approxCurve[(i+1)%4].y)*(approxCurve[i].y-approxCurve[(i+1)%4].y)); 00091 // norm(Mat(approxCurve[i]),Mat(approxCurve[(i+1)%4])); 00092 if (d<minDist) minDist=d; 00093 } 00094 //check that distance is not very small 00095 if (minDist>10) 00096 { 00097 //add the points 00098 // cout<<"ADDED"<<endl; 00099 MarkerCanditates.push_back(Marker()); 00100 for (int i=0;i<4;i++) 00101 { 00102 MarkerCanditates.back().push_back( Point2f(approxCurve[i].x,approxCurve[i].y)); 00103 } 00104 } 00105 } 00106 } 00107 } 00108 } 00109 // namedWindow("input"); 00110 // imshow("input",input); 00111 // waitKey(0); 00113 for (unsigned int i=0;i<MarkerCanditates.size();i++) 00114 { 00115 00116 //trace a line between the first and second point. 00117 //if the thrid point is at the right side, then the points are anti-clockwise 00118 double dx1 = MarkerCanditates[i][1].x - MarkerCanditates[i][0].x; 00119 double dy1 = MarkerCanditates[i][1].y - MarkerCanditates[i][0].y; 00120 double dx2 = MarkerCanditates[i][2].x - MarkerCanditates[i][0].x; 00121 double dy2 = MarkerCanditates[i][2].y - MarkerCanditates[i][0].y; 00122 double o = (dx1*dy2)-(dy1*dx2); 00123 00124 if (o < 0.0) //if the third point is in the left side, then sort in anti-clockwise order 00125 { 00126 swap(MarkerCanditates[i][1],MarkerCanditates[i][3]); 00127 00128 } 00129 } 00131 //first detect candidates 00132 00133 vector<pair<int,int> > TooNearCandidates; 00134 for (unsigned int i=0;i<MarkerCanditates.size();i++) 00135 { 00136 // cout<<"Marker i="<<i<<MarkerCanditates[i]<<endl; 00137 //calculate the average distance of each corner to the nearest corner of the other marker candidate 00138 for (unsigned int j=i+1;j<MarkerCanditates.size();j++) 00139 { 00140 float dist=0; 00141 for (int c=0;c<4;c++) 00142 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)); 00143 dist/=4; 00144 //if distance is too small 00145 if (dist< 10) { 00146 TooNearCandidates.push_back(pair<int,int>(i,j)); 00147 } 00148 } 00149 } 00150 //mark for removal the element of the pair with smaller perimeter 00151 vector<bool> toRemove (MarkerCanditates.size()); 00152 for (unsigned int i=0;i<toRemove.size();i++) toRemove[i]=false; 00153 00154 for (unsigned int i=0;i<TooNearCandidates.size();i++) { 00155 if ( perimeter(MarkerCanditates[TooNearCandidates[i].first ])>perimeter(MarkerCanditates[ TooNearCandidates[i].second] )) 00156 toRemove[TooNearCandidates[i].second]=true; 00157 else toRemove[TooNearCandidates[i].first]=true; 00158 } 00159 00161 for (unsigned int i=0;i<MarkerCanditates.size();i++) 00162 { 00163 if (!toRemove[i]) 00164 { 00165 // MarkerCanditates[i].draw(input,cv::Scalar(0,255,0),1,false); 00166 //Find proyective homography 00167 vector<Point2f> corners; 00168 corners.push_back(MarkerCanditates[i][0]); 00169 corners.push_back(MarkerCanditates[i][1]); 00170 corners.push_back(MarkerCanditates[i][2]); 00171 corners.push_back(MarkerCanditates[i][3]); 00172 cornerSubPix(grey, corners, cvSize(3, 3), cvSize(-1, -1), cvTermCriteria(CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, 15, 0.05)); 00173 MarkerCanditates[i][0] = corners[0]; 00174 MarkerCanditates[i][1] = corners[1]; 00175 MarkerCanditates[i][2] = corners[2]; 00176 MarkerCanditates[i][3] = corners[3]; 00177 Mat canonicalMarker; 00178 warp(input,canonicalMarker,Size(50,50),MarkerCanditates[i]); 00179 int nRotations; 00180 int id=getMarkerId(canonicalMarker,nRotations); 00181 if (id!=-1) 00182 { 00183 detectedMarkers.push_back(MarkerCanditates[i]); 00184 detectedMarkers.back().id=id; 00185 //sort the points so that they are always in the same order no matter the camera orientation 00186 std::rotate(detectedMarkers.back().begin(),detectedMarkers.back().begin()+4-nRotations,detectedMarkers.back().end()); 00187 } 00188 } 00189 } 00190 //namedWindow("input"); 00191 //imshow("input",input); 00192 // waitKey(0); 00194 /* 00195 if (detectedMarkers.size()>0) 00196 { 00197 vector<Point2f> Corners; 00198 for (unsigned int i=0;i<detectedMarkers.size();i++) 00199 for (int c=0;c<4;c++) 00200 Corners.push_back(detectedMarkers[i][c]); 00201 cornerSubPix(grey, Corners,cvSize(3,3), cvSize(-1,-1) ,cvTermCriteria ( CV_TERMCRIT_ITER|CV_TERMCRIT_EPS,15,0.05 )); 00202 //copy back 00203 for (unsigned int i=0;i<detectedMarkers.size();i++) 00204 for (int c=0;c<4;c++) detectedMarkers[i][c]=Corners[i*4+c]; 00205 } 00206 */ 00207 //sort by id 00208 std::sort(detectedMarkers.begin(),detectedMarkers.end()); 00209 //there might be still the case that a marker is detected twice because of the double border indicated earlier, 00210 //detect and remove these cases 00211 toRemove.resize(detectedMarkers.size()); 00212 for (unsigned int i=0;i<detectedMarkers.size();i++) toRemove[i]=false; 00213 00214 for (int i=0;i<int(detectedMarkers.size())-1;i++) { 00215 if (detectedMarkers[i].id==detectedMarkers[i+1].id && !toRemove[i+1] ) { 00216 //deletes the one with smaller perimeter 00217 if (perimeter(detectedMarkers[i])>perimeter(detectedMarkers[i+1])) toRemove[i+1]=true; 00218 else toRemove[i]=true; 00219 } 00220 } 00221 //now, remove 00222 vector<Marker>::iterator it=detectedMarkers.begin(); 00223 for (unsigned int i=0;i<toRemove.size();i++) { 00224 if (toRemove[i]) it=detectedMarkers.erase(it); 00225 else it++; 00226 } 00228 00229 if (camMatrix.rows!=0 && markerSizeMeters>0) 00230 { 00231 for (unsigned int i=0;i<detectedMarkers.size();i++) 00232 detectedMarkers[i].calculateExtrinsics(markerSizeMeters,camMatrix,distCoeff); 00233 } 00234 00235 00236 } 00237 00238 /************************************ 00239 * 00240 * 00241 * 00242 * 00243 ************************************/ 00244 void MarkerDetector::thresHold(int method,Mat &grey,Mat &out) 00245 { 00246 switch (method) 00247 { 00248 case FIXED_THRES: 00249 cv::threshold(grey, out, _thresParam1,255, CV_THRESH_BINARY_INV ); 00250 break; 00251 case ADPT_THRES://currently, this is the best method 00252 cv::adaptiveThreshold(grey,out,255,ADAPTIVE_THRESH_GAUSSIAN_C,THRESH_BINARY_INV,_thresParam1,_thresParam2); 00253 // cv::erode(out,grey,Mat()); 00254 // grey.copyTo(out); 00255 break; 00256 case CANNY: 00257 { 00258 //this should be the best method, and generally it is. 00259 //However, some times there are small holes in the marker contour that makes 00260 //the contour detector not to find it properly 00261 //if there is a missing pixel 00262 cv::Canny(grey, out, 10, 220); 00263 //I've tried a closing but it add many more points that some 00264 //times makes this even worse 00265 // Mat aux; 00266 // cv::morphologyEx(thres,aux,MORPH_CLOSE,Mat()); 00267 // out=aux; 00268 }break; 00269 } 00270 } 00271 /************************************ 00272 * 00273 * 00274 * 00275 * 00276 ************************************/ 00277 void MarkerDetector::drawAllContours(Mat input) 00278 { 00279 drawContours( input, contours2, -1,Scalar(255,0,255)); 00280 } 00281 00282 /************************************ 00283 * 00284 * 00285 * 00286 * 00287 ************************************/ 00288 void MarkerDetector:: drawContour(Mat &in,vector<Point> &contour,Scalar color ) 00289 { 00290 for (unsigned int i=0;i<contour.size();i++) 00291 { 00292 cv::rectangle(in,contour[i],contour[i],color); 00293 } 00294 } 00295 00296 void MarkerDetector:: drawApproxCurve(Mat &in,vector<Point> &contour,Scalar color ) 00297 { 00298 for (unsigned int i=0;i<contour.size();i++) 00299 { 00300 cv::line( in,contour[i],contour[(i+1)%contour.size()],color); 00301 } 00302 } 00303 /************************************ 00304 * 00305 * 00306 * 00307 * 00308 ************************************/ 00309 00310 void MarkerDetector::draw(Mat out,const vector<Marker> &markers ) 00311 { 00312 for (unsigned int i=0;i<markers.size();i++) 00313 { 00314 cv::line( out,markers[i][0],markers[i][1],cvScalar(255,0,0),2,CV_AA); 00315 cv::line( out,markers[i][1],markers[i][2],cvScalar(255,0,0),2,CV_AA); 00316 cv::line( out,markers[i][2],markers[i][3],cvScalar(255,0,0),2,CV_AA); 00317 cv::line( out,markers[i][3],markers[i][0],cvScalar(255,0,0),2,CV_AA); 00318 } 00319 } 00320 /************************************ 00321 * 00322 * 00323 * 00324 * 00325 ************************************/ 00326 00327 void MarkerDetector::warp(Mat &in,Mat &out,Size size, vector<Point2f> points)throw (cv::Exception) 00328 { 00329 00330 if (points.size()!=4) throw cv::Exception(9001,"point.size()!=4","PerpectiveWarper::warp",__FILE__,__LINE__); 00331 //obtain the perspective transform 00332 Point2f pointsRes[4],pointsIn[4]; 00333 for (int i=0;i<4;i++) pointsIn[i]=points[i]; 00334 pointsRes[0]=(Point2f(0,0)); 00335 pointsRes[1]= Point2f(size.width-1,0); 00336 pointsRes[2]= Point2f(size.width-1,size.height-1); 00337 pointsRes[3]= Point2f(0,size.height-1); 00338 // cout<<pointsIn[0].x<< " "<<pointsIn[0].y<< 00339 Mat M=getPerspectiveTransform(pointsIn,pointsRes); 00340 cv::warpPerspective(in, out, M, size); 00341 00342 } 00343 /************************************ 00344 * 00345 * 00346 * 00347 * 00348 ************************************/ 00349 int MarkerDetector::hammDistMarker(Mat bits) 00350 { 00351 int ids[4][5]= 00352 { 00353 { 00354 1,0,0,0,0 00355 } 00356 , 00357 { 00358 1,0,1,1,1 00359 } 00360 , 00361 { 00362 0,1,0,0,1 00363 } 00364 , 00365 { 00366 0, 1, 1, 1, 0 00367 } 00368 }; 00369 int dist=0; 00370 00371 for (int y=0;y<5;y++) 00372 { 00373 int minSum=1e5; 00374 //hamming distance to each possible word 00375 for (int p=0;p<4;p++) 00376 { 00377 int sum=0; 00378 //now, count 00379 for (int x=0;x<5;x++) 00380 sum+= bits.at<uchar>(y,x) == ids[p][x]?0:1; 00381 if (minSum>sum) minSum=sum; 00382 } 00383 //do the and 00384 dist+=minSum; 00385 } 00386 00387 return dist; 00388 } 00389 /************************************ 00390 * 00391 * 00392 * 00393 * 00394 ************************************/ 00395 00396 int MarkerDetector::mat2id(Mat &bits) 00397 { 00398 int val=0; 00399 for (int y=0;y<5;y++) 00400 { 00401 val<<=1; 00402 if ( bits.at<uchar>(y,1)) val|=1; 00403 val<<=1; 00404 if ( bits.at<uchar>(y,3)) val|=1; 00405 } 00406 return val; 00407 } 00408 /************************************ 00409 * 00410 * 00411 * 00412 * 00413 ************************************/ 00414 bool MarkerDetector::correctHammMarker(Mat &bits) 00415 { 00416 //detect this lines with errors 00417 bool errors[4]; 00418 int ids[4][5]= 00419 { 00420 { 00421 0,0,0,0,0 00422 } 00423 , 00424 { 00425 0,0,1,1,1 00426 } 00427 , 00428 { 00429 1,1,0,0,1 00430 } 00431 , 00432 { 00433 1, 1, 1, 1, 0 00434 } 00435 }; 00436 00437 for (int y=0;y<5;y++) 00438 { 00439 int minSum=1e5; 00440 //hamming distance to each possible word 00441 for (int p=0;p<4;p++) 00442 { 00443 int sum=0; 00444 //now, count 00445 for (int x=0;x<5;x++) 00446 sum+= bits.at<uchar>(y,x) == ids[p][x]?0:1; 00447 if (minSum>sum) minSum=sum; 00448 } 00449 if (minSum!=0) errors[y]=true; 00450 else errors[y]=false; 00451 } 00452 00453 return true; 00454 } 00455 00456 /************************************ 00457 * 00458 * 00459 * 00460 * 00461 ************************************/ 00462 Mat MarkerDetector::rotate(Mat in) 00463 { 00464 Mat out; 00465 in.copyTo(out); 00466 for (int i=0;i<in.rows;i++) 00467 { 00468 for (int j=0;j<in.cols;j++) 00469 { 00470 out.at<uchar>(i,j)=in.at<uchar>(in.cols-j-1,i); 00471 } 00472 } 00473 return out; 00474 } 00475 00476 /************************************ 00477 * 00478 * 00479 * 00480 * 00481 ************************************/ 00482 int MarkerDetector::getMarkerId(Mat &in,int &nRotations) 00483 { 00484 assert(in.rows==in.cols); 00485 Mat grey; 00486 if ( in.type()==CV_8UC1) grey=in; 00487 else cv::cvtColor(in,grey,CV_BGR2GRAY); 00488 //threshold image 00489 threshold(grey, grey,125, 255, THRESH_BINARY|THRESH_OTSU); 00490 00491 00492 00493 // namedWindow("m"); 00494 // imshow("m",in); 00495 /* 00496 namedWindow("m2"); 00497 imshow("m2",grey); */ 00498 00499 //Markers are divided in 7x7 regions, of which the inner 5x5 belongs to marker info 00500 //the external border shoould be entirely black 00501 00502 int swidth=in.rows/7; 00503 for (int y=0;y<7;y++) 00504 { 00505 int inc=6; 00506 if (y==0 || y==6) inc=1;//for first and last row, check the whole border 00507 for (int x=0;x<7;x+=inc) 00508 { 00509 int Xstart=(x)*(swidth); 00510 int Ystart=(y)*(swidth); 00511 Mat square=grey(Rect(Xstart,Ystart,swidth,swidth)); 00512 int nZ=countNonZero(square); 00513 if (nZ> (swidth*swidth) /2) { 00514 return -1;//can not be a marker because the border element is not black! 00515 } 00516 } 00517 } 00518 00519 //now, 00520 vector<int> markerInfo(5); 00521 Mat _bits=Mat::zeros(5,5,CV_8UC1); 00522 //get information(for each inner square, determine if it is black or white) 00523 00524 for (int y=0;y<5;y++) 00525 { 00526 00527 for (int x=0;x<5;x++) 00528 { 00529 int Xstart=(x+1)*(swidth); 00530 int Ystart=(y+1)*(swidth); 00531 Mat square=grey(Rect(Xstart,Ystart,swidth,swidth)); 00532 int nZ=countNonZero(square); 00533 if (nZ> (swidth*swidth) /2) _bits.at<uchar>( y,x)=1; 00534 } 00535 } 00536 // printMat<uchar>( _bits,"or mat"); 00537 00538 //checkl all possible rotations 00539 Mat _bitsFlip; 00540 Mat Rotations[4]; 00541 Rotations[0]=_bits; 00542 int dists[4]; 00543 dists[0]=hammDistMarker( Rotations[0]) ; 00544 pair<int,int> minDist( dists[0],0); 00545 for (int i=1;i<4;i++) 00546 { 00547 //rotate 00548 Rotations[i]=rotate(Rotations[i-1]); 00549 //get the hamming distance to the nearest possible word 00550 dists[i]=hammDistMarker( Rotations[i]) ; 00551 if (dists[i]<minDist.first) 00552 { 00553 minDist.first= dists[i]; 00554 minDist.second=i; 00555 } 00556 } 00557 // printMat<uchar>( Rotations [ minDist.second]); 00558 // cout<<"MinDist="<<minDist.first<<" "<<minDist.second<<endl; 00559 00560 nRotations=minDist.second; 00561 if (minDist.first!=0) //FUTURE WORK: correct if any error 00562 return -1; 00563 else return mat2id(Rotations [ minDist.second]); 00564 00566 /* if (! correctHammMarker(Rotations [ minDist.second] )) return -1; 00567 cout<<"ID="<<mat2id(Rotations [ minDist.second])<<endl; 00568 waitKey(0); 00569 return mat2id(Rotations [ minDist.second]);*/ 00570 } 00571 /************************************ 00572 * 00573 * 00574 * 00575 * 00576 00577 bool MarkerDetector::isInto(vector<Point2f> &a,vector<Point2f> &b) 00578 {//NOT TESTED 00579 CvMat contour(b.size(),1,CV_32FC2); 00580 float *ptr=contour.ptr<float>(0); 00581 for(unsigned int i=0;i<a.size();i++){ 00582 *(ptr++)=b[i].x; 00583 *(ptr++)=b[i].y; 00584 } 00585 for(unsigned int i=0;i<b.size();i++) 00586 if ( pointPolygonTest( contour,b[i],false)>0) return true; 00587 return false; 00588 } 00589 */ 00590 /************************************ 00591 * 00592 * 00593 * 00594 * 00595 ************************************/ 00596 bool MarkerDetector::isInto(Mat &contour,vector<Point2f> &b) 00597 { 00598 00599 for (unsigned int i=0;i<b.size();i++) 00600 if ( pointPolygonTest( contour,b[i],false)>0) return true; 00601 return false; 00602 } 00603 /************************************ 00604 * 00605 * 00606 * 00607 * 00608 ************************************/ 00609 int MarkerDetector:: perimeter(vector<Point2f> &a) 00610 { 00611 int sum=0; 00612 for (unsigned int i=0;i<a.size();i++) { 00613 int i2=(i+1)%a.size(); 00614 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) ) ; 00615 } 00616 return sum; 00617 } 00618 /************************************ 00619 * 00620 * 00621 * 00622 * 00623 ************************************/ 00624 // bool MarkerDetector::isInto(vector<Point2f> &a,vector<Point2f> &b) 00625 // { 00626 // Mat contour(1,a.size(),CV_32FC2); 00627 // float *ptr=(float *)a.ptr(0); 00628 // for(unsigned int p=0;p<detectedMarkers[i].size();p++) 00629 // { 00630 // *ptr++=a[p].x; 00631 // *ptr++=a[p].y; 00632 // } 00633 // for(unsigned int i=0;i<b.size();i++) 00634 // if ( pointPolygonTest( contour,b[i],false)>0) return true; 00635 // return false; 00636 // } 00637 00641 void MarkerDetector::glGetProjectionMatrix(CameraParameters & CP,Size orgImgSize,Size size,double proj_matrix[16],double gnear,double gfar,bool invert )throw(cv::Exception) 00642 { 00643 if (CP.isValid()==false) throw cv::Exception(9100,"invalid camera parameters","MarkerDetector::glGetProjectionMatrix",__FILE__,__LINE__); 00644 //Deterime the rsized info 00645 double Ax=double(size.width)/double(orgImgSize.width); 00646 double Ay=double(size.height)/double(orgImgSize.height); 00647 double _fx=CP.CameraMatrix.at<float>(0,0)*Ax; 00648 double _cx=CP.CameraMatrix.at<float>(0,2)*Ax; 00649 double _fy=CP.CameraMatrix.at<float>(1,1)*Ay; 00650 double _cy=CP.CameraMatrix.at<float>(1,2)*Ay; 00651 double cparam[3][4] = 00652 { 00653 { 00654 _fx, 0, _cx, 0 00655 }, 00656 {0, _fy, _cy, 0}, 00657 {0, 0, 1, 0} 00658 }; 00659 00660 argConvGLcpara2( cparam, size.width, size.height, gnear, gfar, proj_matrix, invert ); 00661 00662 } 00663 00664 void MarkerDetector::argConvGLcpara2( double cparam[3][4], int width, int height, double gnear, double gfar, double m[16], bool invert )throw(cv::Exception) 00665 { 00666 00667 double icpara[3][4]; 00668 double trans[3][4]; 00669 double p[3][3], q[4][4]; 00670 int i, j; 00671 00672 cparam[0][2] *= -1.0; 00673 cparam[1][2] *= -1.0; 00674 cparam[2][2] *= -1.0; 00675 00676 if ( arParamDecompMat(cparam, icpara, trans) < 0 ) 00677 throw cv::Exception(9002,"parameter error","MarkerDetector::argConvGLcpara2",__FILE__,__LINE__); 00678 00679 for ( i = 0; i < 3; i++ ) 00680 { 00681 for ( j = 0; j < 3; j++ ) 00682 { 00683 p[i][j] = icpara[i][j] / icpara[2][2]; 00684 } 00685 } 00686 q[0][0] = (2.0 * p[0][0] / width); 00687 q[0][1] = (2.0 * p[0][1] / width); 00688 q[0][2] = ((2.0 * p[0][2] / width) - 1.0); 00689 q[0][3] = 0.0; 00690 00691 q[1][0] = 0.0; 00692 q[1][1] = (2.0 * p[1][1] / height); 00693 q[1][2] = ((2.0 * p[1][2] / height) - 1.0); 00694 q[1][3] = 0.0; 00695 00696 q[2][0] = 0.0; 00697 q[2][1] = 0.0; 00698 q[2][2] = (gfar + gnear)/(gfar - gnear); 00699 q[2][3] = -2.0 * gfar * gnear / (gfar - gnear); 00700 00701 q[3][0] = 0.0; 00702 q[3][1] = 0.0; 00703 q[3][2] = 1.0; 00704 q[3][3] = 0.0; 00705 00706 for ( i = 0; i < 4; i++ ) 00707 { 00708 for ( j = 0; j < 3; j++ ) 00709 { 00710 m[i+j*4] = q[i][0] * trans[0][j] 00711 + q[i][1] * trans[1][j] 00712 + q[i][2] * trans[2][j]; 00713 } 00714 m[i+3*4] = q[i][0] * trans[0][3] 00715 + q[i][1] * trans[1][3] 00716 + q[i][2] * trans[2][3] 00717 + q[i][3]; 00718 } 00719 00720 if (!invert) 00721 { 00722 m[13]=-m[13] ; 00723 m[1]=-m[1]; 00724 m[5]=-m[5]; 00725 m[9]=-m[9]; 00726 } 00727 00728 } 00729 00730 int MarkerDetector::arParamDecompMat( double source[3][4], double cpara[3][4], double trans[3][4] )throw(cv::Exception) 00731 { 00732 int r, c; 00733 double Cpara[3][4]; 00734 double rem1, rem2, rem3; 00735 00736 if ( source[2][3] >= 0 ) 00737 { 00738 for ( r = 0; r < 3; r++ ) 00739 { 00740 for ( c = 0; c < 4; c++ ) 00741 { 00742 Cpara[r][c] = source[r][c]; 00743 } 00744 } 00745 } 00746 else 00747 { 00748 for ( r = 0; r < 3; r++ ) 00749 { 00750 for ( c = 0; c < 4; c++ ) 00751 { 00752 Cpara[r][c] = -(source[r][c]); 00753 } 00754 } 00755 } 00756 00757 for ( r = 0; r < 3; r++ ) 00758 { 00759 for ( c = 0; c < 4; c++ ) 00760 { 00761 cpara[r][c] = 0.0; 00762 } 00763 } 00764 cpara[2][2] = norm( Cpara[2][0], Cpara[2][1], Cpara[2][2] ); 00765 trans[2][0] = Cpara[2][0] / cpara[2][2]; 00766 trans[2][1] = Cpara[2][1] / cpara[2][2]; 00767 trans[2][2] = Cpara[2][2] / cpara[2][2]; 00768 trans[2][3] = Cpara[2][3] / cpara[2][2]; 00769 00770 cpara[1][2] = dot( trans[2][0], trans[2][1], trans[2][2], 00771 Cpara[1][0], Cpara[1][1], Cpara[1][2] ); 00772 rem1 = Cpara[1][0] - cpara[1][2] * trans[2][0]; 00773 rem2 = Cpara[1][1] - cpara[1][2] * trans[2][1]; 00774 rem3 = Cpara[1][2] - cpara[1][2] * trans[2][2]; 00775 cpara[1][1] = norm( rem1, rem2, rem3 ); 00776 trans[1][0] = rem1 / cpara[1][1]; 00777 trans[1][1] = rem2 / cpara[1][1]; 00778 trans[1][2] = rem3 / cpara[1][1]; 00779 00780 cpara[0][2] = dot( trans[2][0], trans[2][1], trans[2][2], 00781 Cpara[0][0], Cpara[0][1], Cpara[0][2] ); 00782 cpara[0][1] = dot( trans[1][0], trans[1][1], trans[1][2], 00783 Cpara[0][0], Cpara[0][1], Cpara[0][2] ); 00784 rem1 = Cpara[0][0] - cpara[0][1]*trans[1][0] - cpara[0][2]*trans[2][0]; 00785 rem2 = Cpara[0][1] - cpara[0][1]*trans[1][1] - cpara[0][2]*trans[2][1]; 00786 rem3 = Cpara[0][2] - cpara[0][1]*trans[1][2] - cpara[0][2]*trans[2][2]; 00787 cpara[0][0] = norm( rem1, rem2, rem3 ); 00788 trans[0][0] = rem1 / cpara[0][0]; 00789 trans[0][1] = rem2 / cpara[0][0]; 00790 trans[0][2] = rem3 / cpara[0][0]; 00791 00792 trans[1][3] = (Cpara[1][3] - cpara[1][2]*trans[2][3]) / cpara[1][1]; 00793 trans[0][3] = (Cpara[0][3] - cpara[0][1]*trans[1][3] 00794 - cpara[0][2]*trans[2][3]) / cpara[0][0]; 00795 00796 for ( r = 0; r < 3; r++ ) 00797 { 00798 for ( c = 0; c < 3; c++ ) 00799 { 00800 cpara[r][c] /= cpara[2][2]; 00801 } 00802 } 00803 00804 return 0; 00805 } 00806 00807 double MarkerDetector::norm( double a, double b, double c ) 00808 { 00809 return( sqrt( a*a + b*b + c*c ) ); 00810 } 00811 00812 double MarkerDetector::dot( double a1, double a2, double a3, 00813 double b1, double b2, double b3 ) 00814 { 00815 return( a1 * b1 + a2 * b2 + a3 * b3 ); 00816 } 00817 00818 /* 00819 void MarkerDetector::getExtrinsicsParams(double m_modelview[16], guimage::ExtrinsicParams &OutExt)throw(cv::Exception) 00820 { 00821 CvMat* inMatrix=cvCreateMat(3,3,CV_32FC1); 00822 CvMat* vectorRotation=cvCreateMat(1,3,CV_32FC1); 00823 00824 cvSet2D( inMatrix , 0,0, cvScalar(m_modelview[0 + 0*4] ) ); 00825 cvSet2D( inMatrix , 0,1, cvScalar(m_modelview[0 + 1*4] ) ); 00826 cvSet2D( inMatrix , 0,2, cvScalar(m_modelview[0 + 2*4] ) ); 00827 cvSet2D( inMatrix , 1,0, cvScalar(m_modelview[1 + 0*4] ) ); 00828 cvSet2D( inMatrix , 1,1, cvScalar(m_modelview[1 + 1*4] ) ); 00829 cvSet2D( inMatrix , 1,2, cvScalar(m_modelview[1 + 2*4] ) ); 00830 cvSet2D( inMatrix , 2,0, cvScalar(-m_modelview[2 + 0*4] ) ); 00831 cvSet2D( inMatrix , 2,1, cvScalar(-m_modelview[2 + 1*4] ) ); 00832 cvSet2D( inMatrix , 2,2, cvScalar(-m_modelview[2 + 2*4] ) ); 00833 00834 cvRodrigues2(inMatrix,vectorRotation) ; 00835 OutExt.setParams(m_modelview[0 + 3*4],m_modelview[1 + 3*4],-m_modelview[2 + 3*4],cvGet2D(vectorRotation,0,0).val[0],cvGet2D(vectorRotation,0,1).val[0],cvGet2D(vectorRotation,0,2).val[0]); 00836 00837 cvReleaseMat(&inMatrix); 00838 cvReleaseMat(&vectorRotation); 00839 00840 }*/ 00841 00842 00843 00844 00845 };