00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 #include <aruco/boarddetector.h>
00029 #define _USE_MATH_DEFINES
00030 #include <math.h>
00031 #include <cstdlib>
00032 #include <ctime>
00033 #include <cassert>
00034 #include <fstream>
00035 #include <opencv2/calib3d/calib3d.hpp>
00036 using namespace std;
00037 using namespace cv;
00038 namespace aruco {
00041     BoardDetector::BoardDetector ( bool  setYPerpendicular ) {
00042         _setYPerpendicular=setYPerpendicular;
00043         _areParamsSet=false;
00044         repj_err_thres=-1;
00045     }
00049     void BoardDetector::setParams ( const BoardConfiguration &bc,const CameraParameters &cp, float markerSizeMeters ) {
00050         _camParams=cp;
00051         _markerSize=markerSizeMeters;
00052         _bconf=bc;
00053         _areParamsSet=true;
00054     }
00059     void BoardDetector::setParams ( const BoardConfiguration &bc ) {
00060         _bconf=bc;
00061         _areParamsSet=true;
00062     }
00063 
00068     float  BoardDetector::detect ( const cv::Mat &im ) throw ( cv::Exception ) {
00069         _mdetector.detect ( im,_vmarkers );
00070 
00071         float res;
00072 
00073         if ( _camParams.isValid() )
00074             res=detect ( _vmarkers,_bconf,_boardDetected,_camParams.CameraMatrix,_camParams.Distorsion,_markerSize );
00075         else res=detect ( _vmarkers,_bconf,_boardDetected );
00076         return res;
00077     }
00082     float BoardDetector::detect ( const vector<Marker> &detectedMarkers,const  BoardConfiguration &BConf, Board &Bdetected,const CameraParameters &cp, float markerSizeMeters ) throw ( cv::Exception ) {
00083         return detect ( detectedMarkers, BConf,Bdetected,cp.CameraMatrix,cp.Distorsion,markerSizeMeters );
00084     }
00089     float BoardDetector::detect ( const vector<Marker> &detectedMarkers,const  BoardConfiguration &BConf, Board &Bdetected, Mat camMatrix,Mat distCoeff,float markerSizeMeters ) throw ( cv::Exception ) {
00090         if ( BConf.size() ==0 ) throw cv::Exception ( 8881,"BoardDetector::detect","Invalid BoardConfig that is empty",__FILE__,__LINE__ );
00091         if ( BConf[0].size() <2 ) throw cv::Exception ( 8881,"BoardDetector::detect","Invalid BoardConfig that is empty 2",__FILE__,__LINE__ );
00092         
00093         float ssize;
00094         if ( BConf.mInfoType==BoardConfiguration::PIX && markerSizeMeters>0 ) ssize=markerSizeMeters;
00095         else if ( BConf.mInfoType==BoardConfiguration::METERS ) {
00096             ssize=cv::norm ( BConf[0][0]-BConf[0][1] );
00097         }
00098 
00099         
00100         Bdetected.clear();
00102         for ( unsigned int i=0; i<detectedMarkers.size(); i++ ) {
00103             int idx=BConf.getIndexOfMarkerId ( detectedMarkers[i].id );
00104             if ( idx!=-1 ) {
00105                 Bdetected.push_back ( detectedMarkers[i] );
00106                 Bdetected.back().ssize=ssize;
00107             }
00108         }
00109         
00110         Bdetected.conf=BConf;
00111 
00112 
00113         bool hasEnoughInfoForRTvecCalculation=false;
00114         if ( Bdetected.size() >=1 ) {
00115             if ( camMatrix.rows!=0 ) {
00116                 if ( markerSizeMeters>0 && BConf.mInfoType==BoardConfiguration::PIX ) hasEnoughInfoForRTvecCalculation=true;
00117                 else if ( BConf.mInfoType==BoardConfiguration::METERS ) hasEnoughInfoForRTvecCalculation=true;
00118             }
00119         }
00120 
00121 
00122         if ( hasEnoughInfoForRTvecCalculation ) {
00123 
00124             
00125             double marker_meter_per_pix=0;
00126             if ( BConf.mInfoType==BoardConfiguration::PIX ) marker_meter_per_pix=markerSizeMeters /  cv::norm ( BConf[0][0]-BConf[0][1] );
00127             else marker_meter_per_pix=1;
00128 
00129             
00130             vector<cv::Point3f> objPoints;
00131             vector<cv::Point2f> imagePoints;
00132             for ( size_t i=0; i<Bdetected.size(); i++ ) {
00133                 int idx=Bdetected.conf.getIndexOfMarkerId ( Bdetected[i].id );
00134                 assert ( idx!=-1 );
00135                 for ( int p=0; p<4; p++ ) {
00136                     imagePoints.push_back ( Bdetected[i][p] );
00137                     const aruco::MarkerInfo &Minfo=Bdetected.conf.getMarkerInfo ( Bdetected[i].id );
00138                     objPoints.push_back ( Minfo[p]*marker_meter_per_pix );
00139 
00140                 }
00141             }
00142             if ( distCoeff.total() ==0 ) distCoeff=cv::Mat::zeros ( 1,4,CV_32FC1 );
00143 
00144 
00145 
00146 
00147 
00148             cv::Mat rvec,tvec;
00149             cv::solvePnP ( objPoints,imagePoints,camMatrix,distCoeff,rvec,tvec );
00150             rvec.convertTo ( Bdetected.Rvec,CV_32FC1 );
00151             tvec.convertTo ( Bdetected.Tvec,CV_32FC1 );
00152 
00153 
00154             {
00155                 vector<cv::Point2f> reprojected;
00156                 cv::projectPoints ( objPoints,rvec,tvec,camMatrix,distCoeff,reprojected );
00157                 double errSum=0;
00158                 
00159                 for ( size_t i=0; i<reprojected.size(); i++ ) {
00160                     errSum+=cv::norm ( reprojected[i]-imagePoints[i] );
00161                 }
00162 
00163 
00164             }
00165             
00166             if ( repj_err_thres>0 ) {
00167                 vector<cv::Point2f> reprojected;
00168                 cv::projectPoints ( objPoints,rvec,tvec,camMatrix,distCoeff,reprojected );
00169 
00170                 vector<int> pointsThatPassTest;
00171                 
00172                 for ( size_t i=0; i<reprojected.size(); i++ ) {
00173                     float err=cv::norm ( reprojected[i]-imagePoints[i] );
00174                     if ( err<repj_err_thres ) pointsThatPassTest.push_back ( i );
00175                 }
00176                 cout<<"Number of points after reprjection test "<<pointsThatPassTest.size() <<"/"<<objPoints.size() <<endl;
00177                 
00178                 vector<cv::Point3f> objPoints_filtered;
00179                 vector<cv::Point2f> imagePoints_filtered;
00180                 for ( size_t i=0; i<pointsThatPassTest.size(); i++ ) {
00181                     objPoints_filtered.push_back ( objPoints[pointsThatPassTest[i] ] );
00182                     imagePoints_filtered.push_back ( imagePoints[pointsThatPassTest[i] ] );
00183                 }
00184 
00185                 cv::solvePnP ( objPoints,imagePoints,camMatrix,distCoeff,rvec,tvec );
00186                 rvec.convertTo ( Bdetected.Rvec,CV_32FC1 );
00187                 tvec.convertTo ( Bdetected.Tvec,CV_32FC1 );
00188             }
00189 
00190 
00191             
00192             if ( _setYPerpendicular )
00193                 rotateXAxis ( Bdetected.Rvec );
00194 
00195 
00196         }
00197 
00198         float prob=float ( Bdetected.size() ) /double ( Bdetected.conf.size() );
00199         return prob;
00200     }
00201 
00202     void BoardDetector::rotateXAxis ( Mat &rotation ) {
00203         cv::Mat R ( 3,3,CV_32FC1 );
00204         Rodrigues ( rotation, R );
00205         
00206         cv::Mat RX=cv::Mat::eye ( 3,3,CV_32FC1 );
00207         float angleRad=-M_PI/2;
00208         RX.at<float> ( 1,1 ) =cos ( angleRad );
00209         RX.at<float> ( 1,2 ) =-sin ( angleRad );
00210         RX.at<float> ( 2,1 ) =sin ( angleRad );
00211         RX.at<float> ( 2,2 ) =cos ( angleRad );
00212         
00213         R=R*RX;
00214         
00215         Rodrigues ( R,rotation );
00216 
00217     }
00218 
00221     Board BoardDetector::detect ( const cv::Mat &Image, const BoardConfiguration &bc,const CameraParameters &cp, float markerSizeMeters ) {
00222         BoardDetector BD;
00223         BD.setParams ( bc,cp,markerSizeMeters );
00224         BD.detect ( Image );
00225         return BD.getDetectedBoard();
00226     }
00227 };
00228