$search
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; 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 00095 char str[32]; 00096 int index = 0; 00097 00098 while(1) { 00099 int dimx, dimy; 00100 double fRectSize[2]; 00101 string type; 00102 00103 sprintf(str,"grid%d_size_x",index); 00104 if( !_node.getParam(str,dimx) ) 00105 break; 00106 if (dimx < 3) { 00107 ROS_ERROR("Param: %s must be greater than 2",str); 00108 return; 00109 } 00110 00111 sprintf(str,"grid%d_size_y",index); 00112 if( !_node.getParam(str,dimy) ) 00113 break; 00114 if (dimy < 3) { 00115 ROS_ERROR("Param: %s must be greater than 2",str); 00116 return; 00117 } 00118 00119 sprintf(str,"rect%d_size_x",index); 00120 if( !_node.getParam(str,fRectSize[0]) ) 00121 break; 00122 00123 sprintf(str,"rect%d_size_y",index); 00124 if( !_node.getParam(str,fRectSize[1]) ) 00125 break; 00126 00127 sprintf(str,"type%d",index); 00128 if( !_node.getParam(str,type) ) { 00129 sprintf(str,"checker%dx%d", dimx, dimy); 00130 type = str; 00131 } 00132 00133 string strtranslation,strrotation; 00134 sprintf(str,"translation%d",index); 00135 _node.param(str,strtranslation,string()); 00136 00137 vector<float> vtranslation = tokenizevector<float>(strtranslation); 00138 sprintf(str,"rotation%d",index); 00139 _node.param(str,strrotation,string()); 00140 00141 vector<float> vrotation = tokenizevector<float>(strrotation); 00142 00143 CHECKERBOARD cb; 00144 cb.griddims = cvSize(dimx,dimy); 00145 00146 cb.grid3d.resize(dimx*dimy); 00147 int j=0; 00148 for(int y=0; y<dimy; ++y) 00149 for(int x=0; x<dimx; ++x) 00150 cb.grid3d[j++] = Vector(x*fRectSize[0], y*fRectSize[1], 0); 00151 00152 if( vtranslation.size() == 3 ) 00153 cb.tlocaltrans.trans = 00154 Vector(vtranslation[0],vtranslation[1],vtranslation[2]); 00155 00156 if( vrotation.size() == 9 ) { 00157 for(int k = 0; k < 3; ++k) { 00158 cb.tlocaltrans.m[4*k+0] = vrotation[3*k+0]; 00159 cb.tlocaltrans.m[4*k+1] = vrotation[3*k+1]; 00160 cb.tlocaltrans.m[4*k+2] = vrotation[3*k+2]; 00161 } 00162 } 00163 00164 vcheckers.push_back(cb); 00165 vstrtypes.push_back(type); 00166 maptypes[vstrtypes.back()] = index; 00167 index++; 00168 } 00169 00170 _node.param("frame_id", frame_id,string("")); 00171 00172 if( maptypes.size() == 0 ) { 00173 ROS_ERROR("no checkerboards to detect"); 00174 return; 00175 } 00176 00177 if( display ) { 00178 cvNamedWindow("Checkerboard Detector", CV_WINDOW_AUTOSIZE); 00179 cvStartWindowThread(); 00180 } 00181 00182 lasttime = ros::Time::now(); 00183 _pubDetection = _node.advertise<posedetection_msgs::ObjectDetection>("ObjectDetection",1); 00184 00185 this->camInfoSubscriber = _node.subscribe("camera_info", 1, &CheckerboardDetector::caminfo_cb, this); 00186 this->imageSubscriber = _node.subscribe("image",1, &CheckerboardDetector::image_cb, this); 00187 this->camInfoSubscriber2 = _node.subscribe("CameraInfo", 1, &CheckerboardDetector::caminfo_cb2, this); 00188 this->imageSubscriber2 = _node.subscribe("Image",1, &CheckerboardDetector::image_cb2, this); 00189 _srvDetect = _node.advertiseService("Detect",&CheckerboardDetector::detect_cb,this); 00190 } 00191 00193 // Destructor 00194 virtual ~CheckerboardDetector() 00195 { 00196 if( frame ) 00197 cvReleaseImage(&frame); 00198 if( this->intrinsic_matrix ) 00199 cvReleaseMat(&this->intrinsic_matrix); 00200 _srvDetect.shutdown(); 00201 this->camInfoSubscriber.shutdown(); 00202 this->imageSubscriber.shutdown(); 00203 this->camInfoSubscriber2.shutdown(); 00204 this->imageSubscriber2.shutdown(); 00205 } 00206 00208 // Camera info callback 00209 void caminfo_cb(const sensor_msgs::CameraInfoConstPtr &msg) 00210 { 00211 boost::mutex::scoped_lock lock(this->mutexcalib); 00212 00213 this->_camInfoMsg = *msg; 00214 00215 // only get the camera info once <- this is dumb 00216 //this->camInfoSubscriber.shutdown(); 00217 //this->camInfoSubscriber2.shutdown(); 00218 } 00219 void caminfo_cb2(const sensor_msgs::CameraInfoConstPtr &msg) 00220 { 00221 ROS_WARN("The topic CameraInfo has been deprecated. Please change your launch file to use camera_info instead."); 00222 caminfo_cb(msg); 00223 } 00224 00225 void image_cb2(const sensor_msgs::ImageConstPtr &msg) 00226 { 00227 ROS_WARN("The topic Image has been deprecated. Please change your launch file to use image instead."); 00228 boost::mutex::scoped_lock lock(this->mutexcalib); 00229 if( Detect(_objdetmsg,*msg,this->_camInfoMsg) ) 00230 _pubDetection.publish(_objdetmsg); 00231 } 00232 00234 // Image data callback 00235 void image_cb(const sensor_msgs::ImageConstPtr &msg) 00236 { 00237 boost::mutex::scoped_lock lock(this->mutexcalib); 00238 if( Detect(_objdetmsg,*msg,this->_camInfoMsg) ) 00239 _pubDetection.publish(_objdetmsg); 00240 } 00241 00242 bool detect_cb(posedetection_msgs::Detect::Request& req, posedetection_msgs::Detect::Response& res) 00243 { 00244 return Detect(res.object_detection,req.image,req.camera_info); 00245 } 00246 00247 bool Detect(posedetection_msgs::ObjectDetection& objdetmsg, const sensor_msgs::Image& imagemsg, const sensor_msgs::CameraInfo& camInfoMsg) 00248 { 00249 if( this->intrinsic_matrix == NULL ) 00250 this->intrinsic_matrix = cvCreateMat(3,3,CV_32FC1); 00251 00252 for(int i = 0; i < 3; ++i) 00253 for(int j = 0; j < 3; ++j) 00254 this->intrinsic_matrix->data.fl[3*i+j] = camInfoMsg.P[4*i+j]; 00255 00256 if( !_cvbridge.fromImage(imagemsg, "mono8") ) { 00257 ROS_ERROR("failed to get image"); 00258 return false; 00259 } 00260 00261 IplImage *pimggray = _cvbridge.toIpl(); 00262 if( display ) { 00263 // copy the raw image 00264 if( frame != NULL && (frame->width != (int)imagemsg.width || frame->height != (int)imagemsg.height) ) { 00265 cvReleaseImage(&frame); 00266 frame = NULL; 00267 } 00268 00269 if( frame == NULL ) 00270 frame = cvCreateImage(cvSize(imagemsg.width,imagemsg.height),IPL_DEPTH_8U, 3); 00271 00272 cvCvtColor(pimggray,frame,CV_GRAY2RGB); 00273 } 00274 00275 vector<posedetection_msgs::Object6DPose> vobjects; 00276 00277 //#pragma omp parallel for schedule(dynamic,1) 00278 for(int i = 0; i < (int)vcheckers.size(); ++i) { 00279 CHECKERBOARD& cb = vcheckers[i]; 00280 int ncorners; 00281 posedetection_msgs::Object6DPose objpose; 00282 00283 // do until no more checkerboards detected 00284 while(1) { 00285 cb.corners.resize(200); 00286 int allfound = cvFindChessboardCorners( pimggray, cb.griddims, &cb.corners[0], &ncorners, 00287 CV_CALIB_CB_ADAPTIVE_THRESH ); 00288 cb.corners.resize(ncorners); 00289 00290 //cvDrawChessboardCorners(pimgGray, itbox->second.griddims, &corners[0], ncorners, allfound); 00291 //cvSaveImage("temp.jpg", pimgGray); 00292 00293 if(!allfound || ncorners != (int)cb.grid3d.size()) 00294 break; 00295 00296 // remove any corners that are close to the border 00297 const int borderthresh = 30; 00298 00299 for(int j = 0; j < ncorners; ++j) { 00300 int x = cb.corners[j].x; 00301 int y = cb.corners[j].y; 00302 if( x < borderthresh || x > pimggray->width-borderthresh || 00303 y < borderthresh || y > pimggray->height-borderthresh ) 00304 { 00305 allfound = 0; 00306 break; 00307 } 00308 } 00309 00310 // mark out the image 00311 CvPoint upperleft, lowerright; 00312 upperleft.x = lowerright.x = cb.corners[0].x; 00313 upperleft.y = lowerright.y = cb.corners[0].y; 00314 for(int j = 1; j < (int)cb.corners.size(); ++j) { 00315 if( upperleft.x > cb.corners[j].x ) upperleft.x = cb.corners[j].x; 00316 if( upperleft.y > cb.corners[j].y ) upperleft.y = cb.corners[j].y; 00317 if( lowerright.x < cb.corners[j].x ) lowerright.x = cb.corners[j].x; 00318 if( lowerright.y < cb.corners[j].y ) lowerright.y = cb.corners[j].y; 00319 } 00320 00321 cout <<"here"<< endl; 00322 if( allfound ) { 00323 cvFindCornerSubPix(pimggray, &cb.corners[0], cb.corners.size(), cvSize(5,5),cvSize(-1,-1), 00324 cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2)); 00325 objpose.pose = FindTransformation(cb.corners, cb.grid3d, cb.tlocaltrans); 00326 cout <<"pose="<<objpose.pose.position.x << endl; 00327 } 00328 00329 //#pragma omp critical 00330 { 00331 if( allfound ) { 00332 cout <<"there"<< endl; 00333 vobjects.push_back(objpose); 00334 vobjects.back().type = vstrtypes[i]; 00335 } 00336 00337 cvRectangle(pimggray, upperleft, lowerright, CV_RGB(0,0,0),CV_FILLED); 00338 } 00339 } 00340 00341 //cvSaveImage("temp.jpg", pimggray); 00342 } 00343 00344 objdetmsg.objects = vobjects; 00345 objdetmsg.header.stamp = imagemsg.header.stamp; 00346 if( frame_id.size() > 0 ) 00347 objdetmsg.header.frame_id = frame_id; 00348 else 00349 objdetmsg.header.frame_id = imagemsg.header.frame_id; 00350 00351 if( verbose > 0 ) 00352 ROS_INFO("checkerboard: image: %ux%u (size=%u), num: %u, total: %.3fs",imagemsg.width,imagemsg.height, 00353 (unsigned int)imagemsg.data.size(), (unsigned int)objdetmsg.get_objects_size(), 00354 (float)(ros::Time::now()-lasttime).toSec()); 00355 lasttime = ros::Time::now(); 00356 00357 if( display ) { 00358 // draw each found checkerboard 00359 for(size_t i = 0; i < vobjects.size(); ++i) { 00360 int itype = maptypes[vobjects[i].type]; 00361 CHECKERBOARD& cb = vcheckers[itype]; 00362 Transform tglobal; 00363 tglobal.trans = Vector(vobjects[i].pose.position.x,vobjects[i].pose.position.y,vobjects[i].pose.position.z); 00364 tglobal.rot = Vector(vobjects[i].pose.orientation.w,vobjects[i].pose.orientation.x,vobjects[i].pose.orientation.y, vobjects[i].pose.orientation.z); 00365 Transform tlocal = tglobal * cb.tlocaltrans.inverse(); 00366 00367 CvPoint X[4]; 00368 00369 Vector vaxes[4]; 00370 vaxes[0] = Vector(0,0,0); 00371 vaxes[1] = Vector(0.05f,0,0); 00372 vaxes[2] = Vector(0,0.05f,0); 00373 vaxes[3] = Vector(0,0,0.05f); 00374 00375 for(int i = 0; i < 4; ++i) { 00376 Vector p = tglobal*vaxes[i]; 00377 dReal fx = p.x*camInfoMsg.P[0] + p.y*camInfoMsg.P[1] + p.z*camInfoMsg.P[2] + camInfoMsg.P[3]; 00378 dReal fy = p.x*camInfoMsg.P[4] + p.y*camInfoMsg.P[5] + p.z*camInfoMsg.P[6] + camInfoMsg.P[7]; 00379 dReal fz = p.x*camInfoMsg.P[8] + p.y*camInfoMsg.P[9] + p.z*camInfoMsg.P[10] + camInfoMsg.P[11]; 00380 X[i].x = (int)(fx/fz); 00381 X[i].y = (int)(fy/fz); 00382 } 00383 00384 // draw three lines 00385 CvScalar col0 = CV_RGB(255,0,(64*itype)%256); 00386 CvScalar col1 = CV_RGB(0,255,(64*itype)%256); 00387 CvScalar col2 = CV_RGB((64*itype)%256,(64*itype)%256,255); 00388 cvLine(frame, X[0], X[1], col0, 1); 00389 cvLine(frame, X[0], X[2], col1, 1); 00390 cvLine(frame, X[0], X[3], col2, 1); 00391 00392 // draw all the points 00393 for(size_t i = 0; i < cb.grid3d.size(); ++i) { 00394 Vector p = tlocal * cb.grid3d[i]; 00395 dReal fx = p.x*camInfoMsg.P[0] + p.y*camInfoMsg.P[1] + p.z*camInfoMsg.P[2] + camInfoMsg.P[3]; 00396 dReal fy = p.x*camInfoMsg.P[4] + p.y*camInfoMsg.P[5] + p.z*camInfoMsg.P[6] + camInfoMsg.P[7]; 00397 dReal fz = p.x*camInfoMsg.P[8] + p.y*camInfoMsg.P[9] + p.z*camInfoMsg.P[10] + camInfoMsg.P[11]; 00398 int x = (int)(fx/fz); 00399 int y = (int)(fy/fz); 00400 cvCircle(frame, cvPoint(x,y), 6, CV_RGB(0,0,0), 2); 00401 cvCircle(frame, cvPoint(x,y), 2, CV_RGB(0,0,0), 2); 00402 cvCircle(frame, cvPoint(x,y), 4, CV_RGB(128,128,64*itype), 3); 00403 } 00404 00405 cvCircle(frame, X[0], 3, CV_RGB(255,255,128), 3); 00406 } 00407 00408 cvShowImage("Checkerboard Detector",frame); 00409 } 00410 00411 return true; 00412 } 00413 00414 00416 // FindTransformation 00417 geometry_msgs::Pose FindTransformation(const vector<CvPoint2D32f> &imgpts, const vector<Vector> &objpts, const Transform& tlocal) 00418 { 00419 CvMat *objpoints = cvCreateMat(3,objpts.size(),CV_32FC1); 00420 for(size_t i=0; i<objpts.size(); ++i) { 00421 cvSetReal2D(objpoints, 0,i, objpts[i].x); 00422 cvSetReal2D(objpoints, 1,i, objpts[i].y); 00423 cvSetReal2D(objpoints, 2,i, objpts[i].z); 00424 } 00425 00426 geometry_msgs::Pose pose; 00427 Transform tchecker; 00428 assert(sizeof(tchecker.trans.x)==sizeof(float)); 00429 float fR3[3]; 00430 CvMat R3, T3; 00431 assert(sizeof(pose.position.x) == sizeof(double)); 00432 cvInitMatHeader(&R3, 3, 1, CV_32FC1, fR3); 00433 cvInitMatHeader(&T3, 3, 1, CV_32FC1, &tchecker.trans.x); 00434 00435 float kc[4] = {0}; 00436 CvMat kcmat; 00437 cvInitMatHeader(&kcmat,1,4,CV_32FC1,kc); 00438 00439 CvMat img_points; 00440 cvInitMatHeader(&img_points, 1,imgpts.size(), CV_32FC2, const_cast<CvPoint2D32f*>(&imgpts[0])); 00441 00442 cvFindExtrinsicCameraParams2(objpoints, &img_points, this->intrinsic_matrix, &kcmat, &R3, &T3); 00443 cvReleaseMat(&objpoints); 00444 00445 double fang = sqrt(fR3[0]*fR3[0] + fR3[1]*fR3[1] + fR3[2]*fR3[2]); 00446 if( fang >= 1e-6 ) { 00447 double fmult = sin(fang/2)/fang; 00448 tchecker.rot = Vector(cos(fang/2),fR3[0]*fmult, fR3[1]*fmult, fR3[2]*fmult); 00449 } 00450 00451 Transform tglobal = tchecker*tlocal; 00452 pose.position.x = tglobal.trans.x; 00453 pose.position.y = tglobal.trans.y; 00454 pose.position.z = tglobal.trans.z; 00455 pose.orientation.x = tglobal.rot.y; 00456 pose.orientation.y = tglobal.rot.z; 00457 pose.orientation.z = tglobal.rot.w; 00458 pose.orientation.w = tglobal.rot.x; 00459 return pose; 00460 } 00461 }; 00462 00464 // MAIN 00465 int main(int argc, char **argv) 00466 { 00467 ros::init(argc,argv,"checkerboard_detector"); 00468 if( !ros::master::check() ) 00469 return 1; 00470 00471 CheckerboardDetector cd; 00472 ros::spin(); 00473 00474 return 0; 00475 }