marker.cpp
Go to the documentation of this file.
00001 /*****************************
00002 Copyright 2011 Rafael Muñoz Salinas. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without modification, are
00005 permitted provided that the following conditions are met:
00006 
00007    1. Redistributions of source code must retain the above copyright notice, this list of
00008       conditions and the following disclaimer.
00009 
00010    2. Redistributions in binary form must reproduce the above copyright notice, this list
00011       of conditions and the following disclaimer in the documentation and/or other materials
00012       provided with the distribution.
00013 
00014 THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''AS IS'' AND ANY EXPRESS OR IMPLIED
00015 WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00016 FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL Rafael Muñoz Salinas OR
00017 CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00018 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00019 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
00020 ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
00021 NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00022 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00023 
00024 The views and conclusions contained in the software and documentation are those of the
00025 authors and should not be interpreted as representing official policies, either expressed
00026 or implied, of Rafael Muñoz Salinas.
00027 ********************************/
00028 #include <aruco/marker.h>
00029 #define _USE_MATH_DEFINES
00030 #include <math.h>
00031 #include <cstdio>
00032 #include <opencv2/calib3d/calib3d.hpp>
00033 #include <opencv2/highgui/highgui.hpp>
00034 using namespace cv;
00035 namespace aruco {
00039 Marker::Marker()
00040 {
00041     id=-1;
00042     ssize=-1;
00043     Rvec.create(3,1,CV_32FC1);
00044     Tvec.create(3,1,CV_32FC1);
00045     for (int i=0;i<3;i++)
00046         Tvec.at<float>(i,0)=Rvec.at<float>(i,0)=-999999;
00047 }
00051 Marker::Marker(const Marker &M):std::vector<cv::Point2f>(M)
00052 {
00053     M.Rvec.copyTo(Rvec);
00054     M.Tvec.copyTo(Tvec);
00055     id=M.id;
00056     ssize=M.ssize;
00057 }
00058 
00062 Marker::Marker(const  std::vector<cv::Point2f> &corners,int _id):std::vector<cv::Point2f>(corners)
00063 {
00064     id=_id;
00065     ssize=-1;
00066     Rvec.create(3,1,CV_32FC1);
00067     Tvec.create(3,1,CV_32FC1);
00068     for (int i=0;i<3;i++)
00069         Tvec.at<float>(i,0)=Rvec.at<float>(i,0)=-999999;
00070 }
00071 
00075 void Marker::glGetModelViewMatrix(   double modelview_matrix[16])throw(cv::Exception)
00076 {
00077     //check if paremeters are valid
00078     bool invalid=false;
00079     for (int i=0;i<3 && !invalid ;i++)
00080     {
00081         if (Tvec.at<float>(i,0)!=-999999) invalid|=false;
00082         if (Rvec.at<float>(i,0)!=-999999) invalid|=false;
00083     }
00084     if (invalid) throw cv::Exception(9003,"extrinsic parameters are not set","Marker::getModelViewMatrix",__FILE__,__LINE__);
00085     Mat Rot(3,3,CV_32FC1),Jacob;
00086     Rodrigues(Rvec, Rot, Jacob);
00087 
00088     double para[3][4];
00089     for (int i=0;i<3;i++)
00090         for (int j=0;j<3;j++) para[i][j]=Rot.at<float>(i,j);
00091     //now, add the translation
00092     para[0][3]=Tvec.at<float>(0,0);
00093     para[1][3]=Tvec.at<float>(1,0);
00094     para[2][3]=Tvec.at<float>(2,0);
00095     double scale=1;
00096 
00097     modelview_matrix[0 + 0*4] = para[0][0];
00098     // R1C2
00099     modelview_matrix[0 + 1*4] = para[0][1];
00100     modelview_matrix[0 + 2*4] = para[0][2];
00101     modelview_matrix[0 + 3*4] = para[0][3];
00102     // R2
00103     modelview_matrix[1 + 0*4] = para[1][0];
00104     modelview_matrix[1 + 1*4] = para[1][1];
00105     modelview_matrix[1 + 2*4] = para[1][2];
00106     modelview_matrix[1 + 3*4] = para[1][3];
00107     // R3
00108     modelview_matrix[2 + 0*4] = -para[2][0];
00109     modelview_matrix[2 + 1*4] = -para[2][1];
00110     modelview_matrix[2 + 2*4] = -para[2][2];
00111     modelview_matrix[2 + 3*4] = -para[2][3];
00112     modelview_matrix[3 + 0*4] = 0.0;
00113     modelview_matrix[3 + 1*4] = 0.0;
00114     modelview_matrix[3 + 2*4] = 0.0;
00115     modelview_matrix[3 + 3*4] = 1.0;
00116     if (scale != 0.0)
00117     {
00118         modelview_matrix[12] *= scale;
00119         modelview_matrix[13] *= scale;
00120         modelview_matrix[14] *= scale;
00121     }
00122 
00123 
00124 }
00125 
00126 
00127 
00128 /****
00129  * 
00130  */
00131 void Marker::OgreGetPoseParameters(double position[3], double orientation[4]) throw(cv::Exception)
00132 {
00133   
00134     //check if paremeters are valid
00135     bool invalid=false;
00136     for (int i=0;i<3 && !invalid ;i++)
00137     {
00138         if (Tvec.at<float>(i,0)!=-999999) invalid|=false;
00139         if (Rvec.at<float>(i,0)!=-999999) invalid|=false;
00140     }
00141     if (invalid) throw cv::Exception(9003,"extrinsic parameters are not set","Marker::getModelViewMatrix",__FILE__,__LINE__);  
00142     
00143     // calculate position vector
00144     position[0] = -Tvec.ptr<float>(0)[0];
00145     position[1] = -Tvec.ptr<float>(0)[1];
00146     position[2] = +Tvec.ptr<float>(0)[2];
00147     
00148     // now calculare orientation quaternion
00149     cv::Mat Rot(3,3,CV_32FC1);
00150     cv::Rodrigues(Rvec, Rot);
00151     
00152     // calculate axes for quaternion
00153     double stAxes[3][3];
00154     // x axis
00155     stAxes[0][0] = -Rot.at<float>(0,0);
00156     stAxes[0][1] = -Rot.at<float>(1,0);
00157     stAxes[0][2] = +Rot.at<float>(2,0);
00158     // y axis
00159     stAxes[1][0] = -Rot.at<float>(0,1);
00160     stAxes[1][1] = -Rot.at<float>(1,1);
00161     stAxes[1][2] = +Rot.at<float>(2,1);    
00162     // for z axis, we use cross product
00163     stAxes[2][0] = stAxes[0][1]*stAxes[1][2] - stAxes[0][2]*stAxes[1][1];
00164     stAxes[2][1] = - stAxes[0][0]*stAxes[1][2] + stAxes[0][2]*stAxes[1][0];
00165     stAxes[2][2] = stAxes[0][0]*stAxes[1][1] - stAxes[0][1]*stAxes[1][0];
00166     
00167     // transposed matrix
00168     double axes[3][3];
00169     axes[0][0] = stAxes[0][0];
00170     axes[1][0] = stAxes[0][1];
00171     axes[2][0] = stAxes[0][2];
00172     
00173     axes[0][1] = stAxes[1][0];
00174     axes[1][1] = stAxes[1][1];
00175     axes[2][1] = stAxes[1][2];  
00176     
00177     axes[0][2] = stAxes[2][0];
00178     axes[1][2] = stAxes[2][1];
00179     axes[2][2] = stAxes[2][2];    
00180     
00181     // Algorithm in Ken Shoemake's article in 1987 SIGGRAPH course notes
00182     // article "Quaternion Calculus and Fast Animation".
00183     double fTrace = axes[0][0]+axes[1][1]+axes[2][2];
00184     double fRoot;
00185       
00186     if ( fTrace > 0.0 )
00187     {
00188         // |w| > 1/2, may as well choose w > 1/2
00189         fRoot = sqrt(fTrace + 1.0);  // 2w
00190         orientation[0] = 0.5*fRoot;
00191         fRoot = 0.5/fRoot;  // 1/(4w)
00192         orientation[1] = (axes[2][1]-axes[1][2])*fRoot;
00193         orientation[2] = (axes[0][2]-axes[2][0])*fRoot;
00194         orientation[3] = (axes[1][0]-axes[0][1])*fRoot;
00195     }
00196     else
00197     {
00198         // |w| <= 1/2
00199         static unsigned int s_iNext[3] = { 1, 2, 0 };
00200         unsigned int i = 0;
00201         if ( axes[1][1] > axes[0][0] )
00202             i = 1;
00203         if ( axes[2][2] > axes[i][i] )
00204             i = 2;
00205         unsigned int j = s_iNext[i];
00206         unsigned int k = s_iNext[j];
00207 
00208         fRoot = sqrt(axes[i][i]-axes[j][j]-axes[k][k] + 1.0);
00209         double* apkQuat[3] = { &orientation[1], &orientation[2], &orientation[3] };
00210         *apkQuat[i] = 0.5*fRoot;
00211         fRoot = 0.5/fRoot;
00212         orientation[0] = (axes[k][j]-axes[j][k])*fRoot;
00213         *apkQuat[j] = (axes[j][i]+axes[i][j])*fRoot;
00214         *apkQuat[k] = (axes[k][i]+axes[i][k])*fRoot;
00215     }
00216     
00217     
00218 }
00219 
00220 
00221 
00222 void Marker::draw(Mat &in, Scalar color, int lineWidth ,bool writeId)const
00223 {
00224     if (size()!=4) return;
00225     cv::line( in,(*this)[0],(*this)[1],color,lineWidth,CV_AA);
00226     cv::line( in,(*this)[1],(*this)[2],color,lineWidth,CV_AA);
00227     cv::line( in,(*this)[2],(*this)[3],color,lineWidth,CV_AA);
00228     cv::line( in,(*this)[3],(*this)[0],color,lineWidth,CV_AA);
00229     cv::rectangle( in,(*this)[0]-Point2f(2,2),(*this)[0]+Point2f(2,2),Scalar(0,0,255,255),lineWidth,CV_AA);
00230     cv::rectangle( in,(*this)[1]-Point2f(2,2),(*this)[1]+Point2f(2,2),Scalar(0,255,0,255),lineWidth,CV_AA);
00231     cv::rectangle( in,(*this)[2]-Point2f(2,2),(*this)[2]+Point2f(2,2),Scalar(255,0,0,255),lineWidth,CV_AA);
00232     if (writeId) {
00233         char cad[100];
00234         sprintf(cad,"id=%d",id);
00235         //determine the centroid
00236         Point cent(0,0);
00237         for (int i=0;i<4;i++)
00238         {
00239             cent.x+=(*this)[i].x;
00240             cent.y+=(*this)[i].y;
00241         }
00242         cent.x/=4.;
00243         cent.y/=4.;
00244         putText(in,cad, cent,FONT_HERSHEY_SIMPLEX, 0.5,  Scalar(255-color[0],255-color[1],255-color[2],255),2);
00245     }
00246 }
00247 
00250 void Marker::calculateExtrinsics(float markerSize,const CameraParameters &CP,bool setYPerpendicular)throw(cv::Exception)
00251 {
00252     if (!CP.isValid()) throw cv::Exception(9004,"!CP.isValid(): invalid camera parameters. It is not possible to calculate extrinsics","calculateExtrinsics",__FILE__,__LINE__);
00253     calculateExtrinsics( markerSize,CP.CameraMatrix,CP.Distorsion,setYPerpendicular);
00254 }
00255 
00256 void print(cv::Point3f p,string cad){
00257  cout<<cad<<" "<<p.x<<" "<<p.y<< " "<<p.z<<endl; 
00258 }
00261 void Marker::calculateExtrinsics(float markerSizeMeters,cv::Mat  camMatrix,cv::Mat distCoeff ,bool setYPerpendicular)throw(cv::Exception)
00262 {
00263     if (!isValid()) throw cv::Exception(9004,"!isValid(): invalid marker. It is not possible to calculate extrinsics","calculateExtrinsics",__FILE__,__LINE__);
00264     if (markerSizeMeters<=0)throw cv::Exception(9004,"markerSize<=0: invalid markerSize","calculateExtrinsics",__FILE__,__LINE__);
00265     if ( camMatrix.rows==0 || camMatrix.cols==0) throw cv::Exception(9004,"CameraMatrix is empty","calculateExtrinsics",__FILE__,__LINE__);
00266  
00267      double halfSize=markerSizeMeters/2.;
00268     cv::Mat ObjPoints(4,3,CV_32FC1);
00269     ObjPoints.at<float>(1,0)=-halfSize;
00270     ObjPoints.at<float>(1,1)=halfSize;
00271     ObjPoints.at<float>(1,2)=0;
00272     ObjPoints.at<float>(2,0)=halfSize;
00273     ObjPoints.at<float>(2,1)=halfSize;
00274     ObjPoints.at<float>(2,2)=0;
00275     ObjPoints.at<float>(3,0)=halfSize;
00276     ObjPoints.at<float>(3,1)=-halfSize;
00277     ObjPoints.at<float>(3,2)=0;
00278     ObjPoints.at<float>(0,0)=-halfSize;
00279     ObjPoints.at<float>(0,1)=-halfSize;
00280     ObjPoints.at<float>(0,2)=0;
00281 
00282     cv::Mat ImagePoints(4,2,CV_32FC1);
00283 
00284     //Set image points from the marker
00285     for (int c=0;c<4;c++)
00286     {
00287         ImagePoints.at<float>(c,0)=((*this)[c].x);
00288         ImagePoints.at<float>(c,1)=((*this)[c].y);
00289     }
00290     
00291     cv::Mat raux,taux;
00292     cv::solvePnP(ObjPoints, ImagePoints, camMatrix, distCoeff,raux,taux);
00293     raux.convertTo(Rvec,CV_32F);
00294     taux.convertTo(Tvec ,CV_32F);
00295     //rotate the X axis so that Y is perpendicular to the marker plane
00296    if (setYPerpendicular) rotateXAxis(Rvec);
00297     ssize=markerSizeMeters; 
00298     cout<<(*this)<<endl;
00299     
00300 }
00301 
00302 
00306 void Marker::rotateXAxis(Mat &rotation)
00307 {
00308     cv::Mat R(3,3,CV_32F);
00309     Rodrigues(rotation, R);
00310     //create a rotation matrix for x axis
00311     cv::Mat RX=cv::Mat::eye(3,3,CV_32F);
00312     float angleRad=M_PI/2;
00313     RX.at<float>(1,1)=cos(angleRad);
00314     RX.at<float>(1,2)=-sin(angleRad);
00315     RX.at<float>(2,1)=sin(angleRad);
00316     RX.at<float>(2,2)=cos(angleRad);
00317     //now multiply
00318     R=R*RX;
00319     //finally, the the rodrigues back
00320     Rodrigues(R,rotation);
00321 }
00322 
00323 
00324 
00327 cv::Point2f Marker::getCenter()const
00328 {
00329   cv::Point2f cent(0,0);
00330   for(size_t i=0;i<size();i++){
00331    cent.x+=(*this)[i].x;
00332    cent.y+=(*this)[i].y;
00333   }
00334    cent.x/=float(size());
00335    cent.y/=float(size());
00336    return cent;
00337 }
00338 
00341 float Marker::getArea()const
00342 {
00343     assert(size()==4);
00344     //use the cross products
00345     cv::Point2f v01=(*this)[1]-(*this)[0];
00346     cv::Point2f v03=(*this)[3]-(*this)[0];
00347     float area1=fabs(v01.x*v03.y - v01.y*v03.x);
00348     cv::Point2f v21=(*this)[1]-(*this)[2];
00349     cv::Point2f v23=(*this)[3]-(*this)[2];
00350     float area2=fabs(v21.x*v23.y - v21.y*v23.x);
00351     return (area2+area1)/2.;
00352     
00353   
00354 }
00357 float Marker::getPerimeter()const
00358 {
00359   assert(size()==4);
00360   float sum=0;
00361   for(int i=0;i<4;i++)
00362     sum+=norm( (*this)[i]-(*this)[(i+1)%4]);
00363   return sum;
00364 }
00365 
00366 
00367 }


ar_sys
Author(s): Hamdi Sahloul , Rafael Muñoz Salinas , Bence Magyar
autogenerated on Thu Aug 27 2015 12:23:55