checkerboard_detector.cpp
Go to the documentation of this file.
00001 // Software License Agreement (BSD License)
00002 // Copyright (c) 2008, Willow Garage, Inc.
00003 // Redistribution and use in source and binary forms, with or without
00004 // modification, are permitted provided that the following conditions are met:
00005 //   * Redistributions of source code must retain the above copyright notice,
00006 //     this list of conditions and the following disclaimer.
00007 //   * Redistributions in binary form must reproduce the above copyright
00008 //     notice, this list of conditions and the following disclaimer in the
00009 //     documentation and/or other materials provided with the distribution.
00010 //   * The name of the author may not be used to endorse or promote products
00011 //     derived from this software without specific prior written permission.
00012 //
00013 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00014 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00015 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00016 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00017 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00018 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00019 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00020 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00021 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00022 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00023 // POSSIBILITY OF SUCH DAMAGE.
00024 //
00025 // author: Rosen Diankov
00026 #include <cstdio>
00027 #include <vector>
00028 #include <sstream>
00029 #include <ros/ros.h>
00030 
00031 #include <boost/thread/mutex.hpp>
00032 
00033 #include "opencv/cv.h"
00034 #include "opencv/highgui.h"
00035 #include "cv_bridge/CvBridge.h"
00036 #include "sensor_msgs/CameraInfo.h"
00037 #include "sensor_msgs/Image.h"
00038 #include "posedetection_msgs/ObjectDetection.h"
00039 #include "posedetection_msgs/Detect.h"
00040 #include "math.h"
00041 
00042 #include <sys/timeb.h>    // ftime(), struct timeb
00043 #include <sys/time.h>
00044 
00045 using namespace std;
00046 using namespace ros;
00047 
00048 class CheckerboardDetector
00049 {
00050     template <typename T>
00051     static vector<T> tokenizevector(const string& s)
00052     {
00053         stringstream ss(s);
00054         return vector<T>((istream_iterator<T>(ss)), istream_iterator<T>());
00055     }
00056 
00057 public:
00058     struct CHECKERBOARD
00059     {
00060         CvSize griddims; 
00061         vector<Vector> grid3d;
00062         vector<CvPoint2D32f> corners;
00063         TransformMatrix tlocaltrans;
00064     };
00065 
00066     posedetection_msgs::ObjectDetection _objdetmsg;
00067     sensor_msgs::CvBridge _cvbridge;
00068     sensor_msgs::CameraInfo _camInfoMsg;
00069 
00070     ros::Subscriber camInfoSubscriber,camInfoSubscriber2;
00071     ros::Subscriber imageSubscriber,imageSubscriber2;
00072     ros::Publisher _pubDetection;
00073     ros::ServiceServer _srvDetect;
00074 
00075     string frame_id; // tf frame id
00076 
00077     int display, verbose, maxboard;
00078     vector<CHECKERBOARD> vcheckers; // grid points for every checkerboard
00079     vector< string > vstrtypes; // type names for every grid point
00080     map<string,int> maptypes;
00081     ros::Time lasttime;
00082     CvMat *intrinsic_matrix; // intrinsic matrices
00083     boost::mutex mutexcalib;
00084     IplImage* frame;
00085 
00086     ros::NodeHandle _node;
00087 
00089     // Constructor
00090     CheckerboardDetector() : intrinsic_matrix(NULL), frame(NULL)
00091     {
00092         _node.param("display", display, 0);
00093         _node.param("verbose", verbose, 1);
00094         _node.param("maxboard", maxboard, -1);
00095         
00096         char str[32];
00097         int index = 0;
00098 
00099         while(1) {
00100             int dimx, dimy;
00101             double fRectSize[2];
00102             string type;
00103 
00104             sprintf(str,"grid%d_size_x",index);
00105             if( !_node.getParam(str,dimx) )
00106                 break;
00107             if (dimx < 3) {
00108                 ROS_ERROR("Param: %s must be greater than 2",str);
00109                 return;
00110             }
00111 
00112             sprintf(str,"grid%d_size_y",index);
00113             if( !_node.getParam(str,dimy) )
00114                 break;
00115             if (dimy < 3) {
00116                 ROS_ERROR("Param: %s must be greater than 2",str);
00117                 return;
00118             }
00119 
00120             sprintf(str,"rect%d_size_x",index);
00121             if( !_node.getParam(str,fRectSize[0]) )
00122                 break;
00123 
00124             sprintf(str,"rect%d_size_y",index);
00125             if( !_node.getParam(str,fRectSize[1]) )
00126                 break;
00127 
00128             sprintf(str,"type%d",index);
00129             if( !_node.getParam(str,type) ) {
00130                 sprintf(str,"checker%dx%d", dimx, dimy);
00131                 type = str;
00132             }
00133 
00134             string strtranslation,strrotation;
00135             sprintf(str,"translation%d",index);
00136             _node.param(str,strtranslation,string());
00137 
00138             vector<float> vtranslation = tokenizevector<float>(strtranslation);
00139             sprintf(str,"rotation%d",index);
00140             _node.param(str,strrotation,string());
00141 
00142             vector<float> vrotation = tokenizevector<float>(strrotation);
00143 
00144             CHECKERBOARD cb;
00145             cb.griddims = cvSize(dimx,dimy);
00146 
00147             cb.grid3d.resize(dimx*dimy);
00148             int j=0;
00149             for(int y=0; y<dimy; ++y)
00150                 for(int x=0; x<dimx; ++x)
00151                     cb.grid3d[j++] = Vector(x*fRectSize[0], y*fRectSize[1], 0);
00152 
00153             if( vtranslation.size() == 3 )
00154                 cb.tlocaltrans.trans = 
00155                     Vector(vtranslation[0],vtranslation[1],vtranslation[2]);
00156 
00157             if( vrotation.size() == 9 )  {
00158                 for(int k = 0; k < 3; ++k) {
00159                     cb.tlocaltrans.m[4*k+0] = vrotation[3*k+0];
00160                     cb.tlocaltrans.m[4*k+1] = vrotation[3*k+1];
00161                     cb.tlocaltrans.m[4*k+2] = vrotation[3*k+2];
00162                 }
00163             }
00164 
00165             vcheckers.push_back(cb);
00166             vstrtypes.push_back(type);
00167             maptypes[vstrtypes.back()] = index;
00168             index++;
00169         }
00170 
00171         _node.param("frame_id", frame_id,string(""));
00172 
00173         if( maptypes.size() == 0 ) {
00174             ROS_ERROR("no checkerboards to detect");
00175             return;
00176         }
00177 
00178         if( display ) {
00179           // enable to set other window flag // use display value if display != 1 because only CV_WINDOW_AUTOSIZE is supported officially
00180           cvNamedWindow("Checkerboard Detector", (display == 1? CV_WINDOW_AUTOSIZE : display));
00181             cvStartWindowThread();
00182         }
00183 
00184         lasttime = ros::Time::now();
00185 
00186         ros::SubscriberStatusCallback connect_cb = boost::bind( &CheckerboardDetector::connectCb, this);
00187         _pubDetection =
00188           _node.advertise<posedetection_msgs::ObjectDetection> ("ObjectDetection", 1,
00189                                                                 connect_cb, connect_cb);
00190 
00191         //this->camInfoSubscriber = _node.subscribe("camera_info", 1, &CheckerboardDetector::caminfo_cb, this);
00192         //this->imageSubscriber = _node.subscribe("image",1, &CheckerboardDetector::image_cb, this);
00193         //this->camInfoSubscriber2 = _node.subscribe("CameraInfo", 1, &CheckerboardDetector::caminfo_cb2, this);
00194         //this->imageSubscriber2 = _node.subscribe("Image",1, &CheckerboardDetector::image_cb2, this);
00195         _srvDetect = _node.advertiseService("Detect",&CheckerboardDetector::detect_cb,this);
00196     }
00197 
00199     // Destructor
00200     virtual ~CheckerboardDetector()
00201     {
00202         if( frame )
00203             cvReleaseImage(&frame);
00204         if( this->intrinsic_matrix )
00205             cvReleaseMat(&this->intrinsic_matrix);
00206         _srvDetect.shutdown();
00207         this->camInfoSubscriber.shutdown();
00208         this->imageSubscriber.shutdown();
00209         this->camInfoSubscriber2.shutdown();
00210         this->imageSubscriber2.shutdown();
00211     }
00212 
00214     // Camera info callback
00215     void caminfo_cb(const sensor_msgs::CameraInfoConstPtr &msg)
00216     {
00217         boost::mutex::scoped_lock lock(this->mutexcalib);
00218 
00219         this->_camInfoMsg = *msg;
00220 
00221         // only get the camera info once <- this is dumb
00222         //this->camInfoSubscriber.shutdown();
00223         //this->camInfoSubscriber2.shutdown();
00224     }
00225     void caminfo_cb2(const sensor_msgs::CameraInfoConstPtr &msg)
00226     {
00227         ROS_WARN("The topic CameraInfo has been deprecated.  Please change your launch file to use camera_info instead.");
00228         caminfo_cb(msg);
00229     }
00230 
00231     void image_cb2(const sensor_msgs::ImageConstPtr &msg)
00232     {
00233         ROS_WARN("The topic Image has been deprecated.  Please change your launch file to use image instead.");
00234         boost::mutex::scoped_lock lock(this->mutexcalib);
00235         if( Detect(_objdetmsg,*msg,this->_camInfoMsg) )
00236             _pubDetection.publish(_objdetmsg);
00237     }
00238 
00240     // Image data callback
00241     void image_cb(const sensor_msgs::ImageConstPtr &msg)
00242     {
00243         boost::mutex::scoped_lock lock(this->mutexcalib);
00244         if( Detect(_objdetmsg,*msg,this->_camInfoMsg) )
00245             _pubDetection.publish(_objdetmsg);
00246     }
00247 
00248     bool detect_cb(posedetection_msgs::Detect::Request& req, posedetection_msgs::Detect::Response& res)
00249     {
00250         return Detect(res.object_detection,req.image,req.camera_info);
00251     }
00252 
00253     //
00254     void connectCb( )
00255     {
00256       boost::mutex::scoped_lock lock(this->mutexcalib);
00257       if (_pubDetection.getNumSubscribers() == 0)
00258         {
00259           camInfoSubscriber.shutdown();
00260           camInfoSubscriber2.shutdown();
00261           imageSubscriber.shutdown();
00262           imageSubscriber2.shutdown();
00263         }
00264       else
00265         {
00266           if ( camInfoSubscriber == NULL )
00267             camInfoSubscriber = _node.subscribe("camera_info", 1, &CheckerboardDetector::caminfo_cb, this);
00268           if ( imageSubscriber == NULL )
00269             imageSubscriber = _node.subscribe("image", 1, &CheckerboardDetector::image_cb, this);
00270           if ( camInfoSubscriber2 == NULL )
00271             camInfoSubscriber2 = _node.subscribe("CameraInfo", 1, &CheckerboardDetector::caminfo_cb2, this);
00272           if ( imageSubscriber2 == NULL )
00273             imageSubscriber2 = _node.subscribe("Image",1, &CheckerboardDetector::image_cb2, this);
00274         }
00275     }
00276 
00277     bool Detect(posedetection_msgs::ObjectDetection& objdetmsg, const sensor_msgs::Image& imagemsg, const sensor_msgs::CameraInfo& camInfoMsg)
00278     {
00279         if( this->intrinsic_matrix == NULL )
00280             this->intrinsic_matrix = cvCreateMat(3,3,CV_32FC1);
00281 
00282         for(int i = 0; i < 3; ++i)
00283             for(int j = 0; j < 3; ++j)
00284                 this->intrinsic_matrix->data.fl[3*i+j] = camInfoMsg.P[4*i+j];
00285 
00286         if( !_cvbridge.fromImage(imagemsg, "mono8") ) {
00287             ROS_ERROR("failed to get image");
00288             return false;
00289         }
00290 
00291         IplImage *pimggray = _cvbridge.toIpl();
00292         if( display ) {
00293             // copy the raw image
00294             if( frame != NULL && (frame->width != (int)imagemsg.width || frame->height != (int)imagemsg.height) ) {
00295                 cvReleaseImage(&frame);
00296                 frame = NULL;
00297             }
00298 
00299             if( frame == NULL ) 
00300                 frame = cvCreateImage(cvSize(imagemsg.width,imagemsg.height),IPL_DEPTH_8U, 3);
00301 
00302             cvCvtColor(pimggray,frame,CV_GRAY2RGB);
00303         }
00304 
00305         vector<posedetection_msgs::Object6DPose> vobjects;
00306 
00307 #pragma omp parallel for schedule(dynamic,1)
00308         for(int i = 0; i < (int)vcheckers.size(); ++i) {
00309             CHECKERBOARD& cb = vcheckers[i];
00310             int ncorners, board=0;
00311             posedetection_msgs::Object6DPose objpose;
00312 
00313             // do until no more checkerboards detected
00314             while((maxboard==-1)?1:((++board)<=maxboard)) {
00315                 cb.corners.resize(200);
00316                 int allfound = cvFindChessboardCorners( pimggray, cb.griddims, &cb.corners[0], &ncorners,
00317                                                         CV_CALIB_CB_ADAPTIVE_THRESH );
00318                 cb.corners.resize(ncorners);
00319 
00320                 //cvDrawChessboardCorners(pimgGray, itbox->second.griddims, &corners[0], ncorners, allfound);
00321                 //cvSaveImage("temp.jpg", pimgGray);
00322 
00323                 if(!allfound || ncorners != (int)cb.grid3d.size())
00324                     break;
00325 
00326                 // remove any corners that are close to the border
00327                 const int borderthresh = 30;
00328 
00329                 for(int j = 0; j < ncorners; ++j) {
00330                     int x = cb.corners[j].x;
00331                     int y = cb.corners[j].y;
00332                     if( x < borderthresh || x > pimggray->width-borderthresh ||
00333                         y < borderthresh || y > pimggray->height-borderthresh )
00334                     {
00335                         allfound = 0;
00336                         break;
00337                     }
00338                 }
00339 
00340                 // mark out the image
00341                 CvPoint upperleft, lowerright;
00342                 upperleft.x = lowerright.x = cb.corners[0].x;
00343                 upperleft.y = lowerright.y = cb.corners[0].y;
00344                 for(int j = 1; j < (int)cb.corners.size(); ++j) {
00345                     if( upperleft.x > cb.corners[j].x ) upperleft.x = cb.corners[j].x;
00346                     if( upperleft.y > cb.corners[j].y ) upperleft.y = cb.corners[j].y;
00347                     if( lowerright.x < cb.corners[j].x ) lowerright.x = cb.corners[j].x;
00348                     if( lowerright.y < cb.corners[j].y ) lowerright.y = cb.corners[j].y;
00349                 }
00350 
00351                 float step_size =
00352                   (double)( ((upperleft.x - lowerright.x) * (upperleft.x - lowerright.x)) +
00353                             ((upperleft.y - lowerright.y) * (upperleft.y - lowerright.y)) )
00354                   /
00355                   ( ((cb.griddims.width - 1) * (cb.griddims.width - 1)) +
00356                     ((cb.griddims.height - 1) * (cb.griddims.height - 1)) );
00357 #if 0
00358                 ROS_INFO("(%d %d) - (%d %d) -> %f ",
00359                          upperleft.x, upperleft.y, lowerright.x, lowerright.y, sqrt(step_size));
00360 #endif
00361                 int size = (int)(0.5*sqrt(step_size) + 0.5);
00362 
00363                 if( allfound ) {
00364                     cvFindCornerSubPix(pimggray, &cb.corners[0], cb.corners.size(), cvSize(size,size), cvSize(-1,-1),
00365                                        cvTermCriteria(CV_TERMCRIT_ITER, 50, 1e-2));
00366                     objpose.pose = FindTransformation(cb.corners, cb.grid3d, cb.tlocaltrans);
00367                 }
00368 
00369 #pragma omp critical
00370                 {
00371                     if( allfound ) {
00372                         vobjects.push_back(objpose);
00373                         vobjects.back().type = vstrtypes[i];
00374                     }
00375 
00376                     cvRectangle(pimggray, upperleft, lowerright, CV_RGB(0,0,0),CV_FILLED);
00377                 }
00378             }
00379 
00380             //cvSaveImage("temp.jpg", pimggray);
00381         }
00382 
00383         objdetmsg.objects = vobjects;
00384         objdetmsg.header.stamp = imagemsg.header.stamp;
00385         if( frame_id.size() > 0 )
00386             objdetmsg.header.frame_id = frame_id;
00387         else
00388             objdetmsg.header.frame_id = imagemsg.header.frame_id;
00389 
00390         if( verbose > 0 )
00391             ROS_INFO("checkerboard: image: %ux%u (size=%u), num: %u, total: %.3fs",imagemsg.width,imagemsg.height,
00392                      (unsigned int)imagemsg.data.size(), (unsigned int)objdetmsg.objects.size(),
00393                      (float)(ros::Time::now()-lasttime).toSec());
00394         lasttime = ros::Time::now();
00395 
00396         if( display ) {
00397             // draw each found checkerboard
00398             for(size_t i = 0; i < vobjects.size(); ++i) {
00399                 int itype = maptypes[vobjects[i].type];
00400                 CHECKERBOARD& cb = vcheckers[itype];
00401                 Transform tglobal;
00402                 tglobal.trans = Vector(vobjects[i].pose.position.x,vobjects[i].pose.position.y,vobjects[i].pose.position.z);
00403                 tglobal.rot = Vector(vobjects[i].pose.orientation.w,vobjects[i].pose.orientation.x,vobjects[i].pose.orientation.y, vobjects[i].pose.orientation.z);
00404                 Transform tlocal = tglobal * cb.tlocaltrans.inverse();
00405 
00406                 CvPoint X[4];
00407 
00408                 Vector vaxes[4];
00409                 vaxes[0] = Vector(0,0,0);
00410                 vaxes[1] = Vector(0.05f,0,0);
00411                 vaxes[2] = Vector(0,0.05f,0);
00412                 vaxes[3] = Vector(0,0,0.05f);
00413 
00414                 for(int i = 0; i < 4; ++i) {
00415                     Vector p = tglobal*vaxes[i];
00416                     dReal fx = p.x*camInfoMsg.P[0] + p.y*camInfoMsg.P[1] + p.z*camInfoMsg.P[2] + camInfoMsg.P[3];
00417                     dReal fy = p.x*camInfoMsg.P[4] + p.y*camInfoMsg.P[5] + p.z*camInfoMsg.P[6] + camInfoMsg.P[7];
00418                     dReal fz = p.x*camInfoMsg.P[8] + p.y*camInfoMsg.P[9] + p.z*camInfoMsg.P[10] + camInfoMsg.P[11];
00419                     X[i].x = (int)(fx/fz);
00420                     X[i].y = (int)(fy/fz);
00421                 }
00422 
00423                 // draw three lines
00424                 CvScalar col0 = CV_RGB(255,0,(64*itype)%256);
00425                 CvScalar col1 = CV_RGB(0,255,(64*itype)%256);
00426                 CvScalar col2 = CV_RGB((64*itype)%256,(64*itype)%256,255);
00427                 cvLine(frame, X[0], X[1], col0, 1);
00428                 cvLine(frame, X[0], X[2], col1, 1);
00429                 cvLine(frame, X[0], X[3], col2, 1);
00430 
00431                 // draw all the points
00432                 for(size_t i = 0; i < cb.grid3d.size(); ++i) {
00433                     Vector p = tlocal * cb.grid3d[i];
00434                     dReal fx = p.x*camInfoMsg.P[0] + p.y*camInfoMsg.P[1] + p.z*camInfoMsg.P[2] + camInfoMsg.P[3];
00435                     dReal fy = p.x*camInfoMsg.P[4] + p.y*camInfoMsg.P[5] + p.z*camInfoMsg.P[6] + camInfoMsg.P[7];
00436                     dReal fz = p.x*camInfoMsg.P[8] + p.y*camInfoMsg.P[9] + p.z*camInfoMsg.P[10] + camInfoMsg.P[11];
00437                     int x = (int)(fx/fz);
00438                     int y = (int)(fy/fz);
00439                     cvCircle(frame, cvPoint(x,y), 6, CV_RGB(0,0,0), 2);
00440                     cvCircle(frame, cvPoint(x,y), 2, CV_RGB(0,0,0), 2);
00441                     cvCircle(frame, cvPoint(x,y), 4, CV_RGB(128,128,64*itype), 3);
00442                 }
00443 
00444                 cvCircle(frame, X[0], 3, CV_RGB(255,255,128), 3);
00445             }
00446 
00447             cvShowImage("Checkerboard Detector",frame);
00448         }
00449 
00450         return true;
00451     }
00452 
00453 
00455     // FindTransformation
00456     geometry_msgs::Pose FindTransformation(const vector<CvPoint2D32f> &imgpts, const vector<Vector> &objpts, const Transform& tlocal)
00457     {
00458         CvMat *objpoints = cvCreateMat(3,objpts.size(),CV_32FC1);
00459         for(size_t i=0; i<objpts.size(); ++i) {
00460             cvSetReal2D(objpoints, 0,i, objpts[i].x);
00461             cvSetReal2D(objpoints, 1,i, objpts[i].y);
00462             cvSetReal2D(objpoints, 2,i, objpts[i].z);
00463         }
00464 
00465         geometry_msgs::Pose pose;
00466         Transform tchecker;
00467         assert(sizeof(tchecker.trans.x)==sizeof(float));
00468         float fR3[3];
00469         CvMat R3, T3;
00470         assert(sizeof(pose.position.x) == sizeof(double));
00471         cvInitMatHeader(&R3, 3, 1, CV_32FC1, fR3);
00472         cvInitMatHeader(&T3, 3, 1, CV_32FC1, &tchecker.trans.x);
00473 
00474         float kc[4] = {0};
00475         CvMat kcmat;
00476         cvInitMatHeader(&kcmat,1,4,CV_32FC1,kc);
00477 
00478         CvMat img_points;
00479         cvInitMatHeader(&img_points, 1,imgpts.size(), CV_32FC2, const_cast<CvPoint2D32f*>(&imgpts[0]));
00480 
00481         cvFindExtrinsicCameraParams2(objpoints, &img_points, this->intrinsic_matrix, &kcmat, &R3, &T3);
00482         cvReleaseMat(&objpoints);
00483 
00484         double fang = sqrt(fR3[0]*fR3[0] + fR3[1]*fR3[1] + fR3[2]*fR3[2]);
00485         if( fang >= 1e-6 ) {
00486             double fmult = sin(fang/2)/fang;
00487             tchecker.rot = Vector(cos(fang/2),fR3[0]*fmult, fR3[1]*fmult, fR3[2]*fmult);
00488         }
00489 
00490         Transform tglobal = tchecker*tlocal;
00491         pose.position.x = tglobal.trans.x;
00492         pose.position.y = tglobal.trans.y;
00493         pose.position.z = tglobal.trans.z;
00494         pose.orientation.x = tglobal.rot.y;
00495         pose.orientation.y = tglobal.rot.z;
00496         pose.orientation.z = tglobal.rot.w;
00497         pose.orientation.w = tglobal.rot.x;
00498         return pose;
00499     }
00500 };
00501 
00503 // MAIN
00504 int main(int argc, char **argv)
00505 {
00506     ros::init(argc,argv,"checkerboard_detector");
00507     if( !ros::master::check() )
00508         return 1;
00509   
00510     CheckerboardDetector cd;
00511     ros::spin();
00512 
00513     return 0;
00514 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


checkerboard_detector
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu)
autogenerated on Sat Mar 23 2013 18:37:21