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 #include <cstdio>
00027 #include <vector>
00028 #include <sstream>
00029 #include <ros/ros.h>
00030
00031 #include <boost/thread/mutex.hpp>
00032 #include <boost/format.hpp>
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 "geometry_msgs/PoseStamped.h"
00039 #include "geometry_msgs/PoseArray.h"
00040 #include "checkerboard_detector2/ObjectDetection.h"
00041 #include "checkerboard_detector2/Detect.h"
00042 #include "math.h"
00043 #include <image_transport/image_transport.h>
00044
00045 #include <sys/timeb.h>
00046 #include <sys/time.h>
00047
00048 #define sqr(a) ((a)*(a))
00049
00050 using namespace std;
00051 using namespace ros;
00052 using namespace boost;
00053
00054 class CheckerboardDetector
00055 {
00056 template <typename T>
00057 static vector<T> tokenizevector(const string& s)
00058 {
00059 stringstream ss(s);
00060 return vector<T>((istream_iterator<T>(ss)), istream_iterator<T>());
00061 }
00062
00063 public:
00064 struct CHECKERBOARD
00065 {
00066 CvSize griddims;
00067 vector<Vector> grid3d;
00068 vector<CvPoint2D32f> corners;
00069 TransformMatrix tlocaltrans;
00070 TransformMatrix previous_pose;
00071 double cellwidth;
00072 double cellheight;
00073 };
00074
00075 checkerboard_detector2::ObjectDetection _objdetmsg;
00076 sensor_msgs::CvBridge _cvbridge;
00077 sensor_msgs::CameraInfo _camInfoMsg;
00078
00079 ros::Subscriber camInfoSubscriber;
00080 image_transport::Subscriber imageSubscriber;
00081
00082 ros::Publisher _pubPoseArray;
00083 std::vector<ros::Publisher> _pubPose;
00084
00085 string frame_id;
00086
00087 int display, verbose;
00088 vector<CHECKERBOARD> vcheckers;
00089 vector< string > vstrtypes;
00090 map<string,int> maptypes;
00091 ros::Time lasttime;
00092 CvMat *intrinsic_matrix;
00093 boost::mutex mutexcalib;
00094 IplImage* frame;
00095
00096 ros::NodeHandle _node_private;
00097 ros::NodeHandle _node_pub;
00098
00100
00101 CheckerboardDetector() : intrinsic_matrix(NULL), frame(NULL), _node_private("~")
00102 {
00103 _node_private.param("display", display, 0);
00104 _node_private.param("verbose", verbose, 1);
00105
00106 char str[32];
00107 int index = 0;
00108
00109 while(1) {
00110 int dimx, dimy;
00111 double fRectSize[2];
00112 string type;
00113
00114 sprintf(str,"grid%d_size_x",index);
00115 if( !_node_private.getParam(str,dimx) )
00116 break;
00117 if (dimx < 3) {
00118 ROS_ERROR("Param: %s must be greater than 2",str);
00119 return;
00120 }
00121
00122 sprintf(str,"grid%d_size_y",index);
00123 if( !_node_private.getParam(str,dimy) )
00124 break;
00125 if (dimy < 3) {
00126 ROS_ERROR("Param: %s must be greater than 2",str);
00127 return;
00128 }
00129
00130 sprintf(str,"rect%d_size_x",index);
00131 if( !_node_private.getParam(str,fRectSize[0]) )
00132 break;
00133
00134 sprintf(str,"rect%d_size_y",index);
00135 if( !_node_private.getParam(str,fRectSize[1]) )
00136 break;
00137
00138 sprintf(str,"type%d",index);
00139 if( !_node_private.getParam(str,type) ) {
00140 sprintf(str,"checker%dx%d", dimx, dimy);
00141 type = str;
00142 }
00143
00144 string strtranslation,strrotation;
00145 sprintf(str,"translation%d",index);
00146 _node_private.param(str,strtranslation,string());
00147
00148 vector<float> vtranslation = tokenizevector<float>(strtranslation);
00149 sprintf(str,"rotation%d",index);
00150 _node_private.param(str,strrotation,string());
00151
00152 vector<float> vrotation = tokenizevector<float>(strrotation);
00153
00154 CHECKERBOARD cb;
00155 cb.griddims = cvSize(dimx,dimy);
00156 cb.cellwidth = fRectSize[0];
00157 cb.cellheight = fRectSize[0];
00158
00159 cb.grid3d.resize(dimx*dimy);
00160 int j=0;
00161 for(int y=0; y<dimy; ++y)
00162 for(int x=0; x<dimx; ++x)
00163 cb.grid3d[j++] = Vector(x*fRectSize[0], y*fRectSize[1], 0);
00164
00165 if( vtranslation.size() == 3 )
00166 cb.tlocaltrans.trans =
00167 Vector(vtranslation[0],vtranslation[1],vtranslation[2]);
00168
00169 if( vrotation.size() == 9 ) {
00170 for(int k = 0; k < 3; ++k) {
00171 cb.tlocaltrans.m[4*k+0] = vrotation[3*k+0];
00172 cb.tlocaltrans.m[4*k+1] = vrotation[3*k+1];
00173 cb.tlocaltrans.m[4*k+2] = vrotation[3*k+2];
00174 }
00175 }
00176
00177 vcheckers.push_back(cb);
00178 vstrtypes.push_back(type);
00179 maptypes[vstrtypes.back()] = index;
00180 index++;
00181 }
00182
00183 _node_private.param("frame_id", frame_id,string(""));
00184
00185 if( maptypes.size() == 0 ) {
00186 ROS_ERROR("no checkerboards to detect");
00187 return;
00188 }
00189
00190 if( display ) {
00191 cvNamedWindow("Checkerboard Detector", CV_WINDOW_AUTOSIZE);
00192 cvStartWindowThread();
00193 }
00194
00195 lasttime = ros::Time::now();
00196
00197 _pubPoseArray = _node_pub.advertise<geometry_msgs::PoseArray>("pose_array",1);
00198
00199 cout <<"vcheckers.size()=="<<vcheckers.size()<<endl;
00200 for(size_t i=0;i<vcheckers.size();i++) {
00201 _pubPose.push_back( _node_pub.advertise<geometry_msgs::PoseStamped>( boost::str(format("pose%d")%i),1) );
00202 }
00203
00204 this->camInfoSubscriber = _node_pub.subscribe("camera_info", 1, &CheckerboardDetector::caminfo_cb, this);
00205 image_transport::ImageTransport it(_node_pub);
00206 this->imageSubscriber = it.subscribe("image_rect", 1, &CheckerboardDetector::image_cb,this);
00207 }
00208
00210
00211 virtual ~CheckerboardDetector()
00212 {
00213 if( frame )
00214 cvReleaseImage(&frame);
00215 if( this->intrinsic_matrix )
00216 cvReleaseMat(&this->intrinsic_matrix);
00217 this->camInfoSubscriber.shutdown();
00218 this->imageSubscriber.shutdown();
00219 }
00220
00222
00223 void caminfo_cb(const sensor_msgs::CameraInfoConstPtr &msg)
00224 {
00225 boost::mutex::scoped_lock lock(this->mutexcalib);
00226
00227 this->_camInfoMsg = *msg;
00228
00229
00230
00231
00232 }
00233
00234
00236
00237 void image_cb(const sensor_msgs::ImageConstPtr &msg)
00238 {
00239 boost::mutex::scoped_lock lock(this->mutexcalib);
00240 if( Detect(_objdetmsg,*msg,this->_camInfoMsg) ) {
00241 _objdetmsg.header = msg->header;
00242
00243 geometry_msgs::PoseArray array;
00244 array.header = _objdetmsg.header;
00245 array.poses.resize(vcheckers.size());
00246 for(size_t i=0;i<_objdetmsg.objects.size();i++) {
00247 array.poses[_objdetmsg.objects[i].id] = _objdetmsg.objects[i].pose;
00248 }
00249 _pubPoseArray.publish(array);
00250
00251 for(size_t i=0;i<_objdetmsg.objects.size();i++) {
00252 geometry_msgs::PoseStamped pose;
00253 pose.header = _objdetmsg.header;
00254 pose.pose = _objdetmsg.objects[i].pose;
00255 _pubPose[_objdetmsg.objects[i].id].publish( pose );
00256 }
00257 }
00258 }
00259
00260 bool detect_cb(checkerboard_detector2::Detect::Request& req, checkerboard_detector2::Detect::Response& res)
00261 {
00262 return Detect(res.object_detection,req.image,req.camera_info);
00263 }
00264
00265 bool Detect(checkerboard_detector2::ObjectDetection& objdetmsg, const sensor_msgs::Image& imagemsg, const sensor_msgs::CameraInfo& camInfoMsg)
00266 {
00267 if( this->intrinsic_matrix == NULL )
00268 this->intrinsic_matrix = cvCreateMat(3,3,CV_32FC1);
00269
00270 for(int i = 0; i < 3; ++i)
00271 for(int j = 0; j < 3; ++j)
00272 this->intrinsic_matrix->data.fl[3*i+j] = camInfoMsg.P[4*i+j];
00273
00274 if( !_cvbridge.fromImage(imagemsg, "mono8") ) {
00275 ROS_ERROR("failed to get image");
00276 return false;
00277 }
00278
00279 IplImage *pimggray = _cvbridge.toIpl();
00280 if( display ) {
00281
00282 if( frame != NULL && (frame->width != (int)imagemsg.width || frame->height != (int)imagemsg.height) ) {
00283 cvReleaseImage(&frame);
00284 frame = NULL;
00285 }
00286
00287 if( frame == NULL )
00288 frame = cvCreateImage(cvSize(imagemsg.width,imagemsg.height),IPL_DEPTH_8U, 3);
00289
00290 cvCvtColor(pimggray,frame,CV_GRAY2RGB);
00291 }
00292
00293 vector<checkerboard_detector2::Object6DPose> vobjects;
00294
00295
00296 for(int i = 0; i < (int)vcheckers.size(); ++i) {
00297 CHECKERBOARD& cb = vcheckers[i];
00298 int ncorners;
00299 checkerboard_detector2::Object6DPose objpose;
00300
00301
00302 while(1) {
00303 cb.corners.resize(200);
00304 int allfound = cvFindChessboardCorners( pimggray, cb.griddims, &cb.corners[0], &ncorners,
00305 CV_CALIB_CB_ADAPTIVE_THRESH );
00306 cb.corners.resize(ncorners);
00307
00308
00309
00310
00311 if(!allfound || ncorners != (int)cb.grid3d.size())
00312 break;
00313
00314
00315 const int borderthresh = 30;
00316
00317 for(int j = 0; j < ncorners; ++j) {
00318 int x = cb.corners[j].x;
00319 int y = cb.corners[j].y;
00320 if( x < borderthresh || x > pimggray->width-borderthresh ||
00321 y < borderthresh || y > pimggray->height-borderthresh )
00322 {
00323 allfound = 0;
00324 break;
00325 }
00326 }
00327
00328
00329 CvPoint upperleft, lowerright;
00330 upperleft.x = lowerright.x = cb.corners[0].x;
00331 upperleft.y = lowerright.y = cb.corners[0].y;
00332 for(int j = 1; j < (int)cb.corners.size(); ++j) {
00333 if( upperleft.x > cb.corners[j].x ) upperleft.x = cb.corners[j].x;
00334 if( upperleft.y > cb.corners[j].y ) upperleft.y = cb.corners[j].y;
00335 if( lowerright.x < cb.corners[j].x ) lowerright.x = cb.corners[j].x;
00336 if( lowerright.y < cb.corners[j].y ) lowerright.y = cb.corners[j].y;
00337 }
00338
00339 if( allfound ) {
00340 cvFindCornerSubPix(pimggray, &cb.corners[0], cb.corners.size(), cvSize(5,5),cvSize(-1,-1),
00341 cvTermCriteria(CV_TERMCRIT_ITER,20,1e-2));
00342 CHECKERBOARD cb_copy = cb;
00343 objpose.pose = FindTransformation(cb.corners, cb.grid3d, cb.tlocaltrans,cb_copy);
00344
00345
00346 double mindist2 = sqr(cb.cellwidth*cb.griddims.width) + sqr(cb.cellheight*cb.griddims.height);
00347 for(int j = 0; j < (int)vcheckers.size(); ++j) {
00348 if(j != i) {
00349 double dist2 = sqr(objpose.pose.position.x - vcheckers[j].previous_pose.trans.x) +
00350 sqr(objpose.pose.position.y - vcheckers[j].previous_pose.trans.y) +
00351 sqr(objpose.pose.position.z - vcheckers[j].previous_pose.trans.z);
00352 if(dist2 < mindist2) {
00353 cout << "skipping marker, because "<<dist2<<" < "<<mindist2<<endl;
00354 allfound = false;
00355 }
00356 }
00357 }
00358 if(allfound) {
00359 cb = cb_copy;
00360 }
00361 }
00362
00363
00364 {
00365 if( allfound ) {
00366 vobjects.push_back(objpose);
00367 vobjects.back().type = vstrtypes[i];
00368 vobjects.back().id = i;
00369 }
00370
00371 cvRectangle(pimggray, upperleft, lowerright, CV_RGB(0,0,0),CV_FILLED);
00372 }
00373 }
00374
00375
00376 }
00377
00378 objdetmsg.objects = vobjects;
00379 objdetmsg.header.stamp = imagemsg.header.stamp;
00380 if( frame_id.size() > 0 )
00381 objdetmsg.header.frame_id = frame_id;
00382 else
00383 objdetmsg.header.frame_id = imagemsg.header.frame_id;
00384
00385 if( verbose > 0 )
00386 ROS_INFO("checkerboard: image: %ux%u (size=%u), num: %u, total: %.3fs",imagemsg.width,imagemsg.height,
00387 (unsigned int)imagemsg.data.size(), (unsigned int)objdetmsg.objects.size(),
00388 (float)(ros::Time::now()-lasttime).toSec());
00389 lasttime = ros::Time::now();
00390
00391 if( display ) {
00392
00393 for(size_t i = 0; i < vobjects.size(); ++i) {
00394 int itype = maptypes[vobjects[i].type];
00395 CHECKERBOARD& cb = vcheckers[itype];
00396 Transform tglobal;
00397 tglobal.trans = Vector(vobjects[i].pose.position.x,vobjects[i].pose.position.y,vobjects[i].pose.position.z);
00398 tglobal.rot = Vector(vobjects[i].pose.orientation.w,vobjects[i].pose.orientation.x,vobjects[i].pose.orientation.y, vobjects[i].pose.orientation.z);
00399 Transform tlocal = tglobal * cb.tlocaltrans.inverse();
00400
00401 CvPoint X[4];
00402
00403 Vector vaxes[4];
00404 vaxes[0] = Vector(0,0,0);
00405 vaxes[1] = Vector(0.05f,0,0);
00406 vaxes[2] = Vector(0,0.05f,0);
00407 vaxes[3] = Vector(0,0,0.05f);
00408
00409 for(int i = 0; i < 4; ++i) {
00410 Vector p = tglobal*vaxes[i];
00411 dReal fx = p.x*camInfoMsg.P[0] + p.y*camInfoMsg.P[1] + p.z*camInfoMsg.P[2] + camInfoMsg.P[3];
00412 dReal fy = p.x*camInfoMsg.P[4] + p.y*camInfoMsg.P[5] + p.z*camInfoMsg.P[6] + camInfoMsg.P[7];
00413 dReal fz = p.x*camInfoMsg.P[8] + p.y*camInfoMsg.P[9] + p.z*camInfoMsg.P[10] + camInfoMsg.P[11];
00414 X[i].x = (int)(fx/fz);
00415 X[i].y = (int)(fy/fz);
00416 }
00417
00418
00419 CvScalar col0 = CV_RGB(255,0,(64*itype)%256);
00420 CvScalar col1 = CV_RGB(0,255,(64*itype)%256);
00421 CvScalar col2 = CV_RGB((64*itype)%256,(64*itype)%256,255);
00422 cvLine(frame, X[0], X[1], col0, 1);
00423 cvLine(frame, X[0], X[2], col1, 1);
00424 cvLine(frame, X[0], X[3], col2, 1);
00425
00426
00427 for(size_t i = 0; i < cb.grid3d.size(); ++i) {
00428 Vector p = tlocal * cb.grid3d[i];
00429 dReal fx = p.x*camInfoMsg.P[0] + p.y*camInfoMsg.P[1] + p.z*camInfoMsg.P[2] + camInfoMsg.P[3];
00430 dReal fy = p.x*camInfoMsg.P[4] + p.y*camInfoMsg.P[5] + p.z*camInfoMsg.P[6] + camInfoMsg.P[7];
00431 dReal fz = p.x*camInfoMsg.P[8] + p.y*camInfoMsg.P[9] + p.z*camInfoMsg.P[10] + camInfoMsg.P[11];
00432 int x = (int)(fx/fz);
00433 int y = (int)(fy/fz);
00434 cvCircle(frame, cvPoint(x,y), 6, CV_RGB(0,0,0), 2);
00435 cvCircle(frame, cvPoint(x,y), 2, CV_RGB(0,0,0), 2);
00436 cvCircle(frame, cvPoint(x,y), 4, CV_RGB(128,128,64*itype), 3);
00437 }
00438
00439 cvCircle(frame, X[0], 3, CV_RGB(255,255,128), 3);
00440 }
00441
00442 cvShowImage("Checkerboard Detector",frame);
00443 }
00444
00445 return true;
00446 }
00447
00448
00450
00451 geometry_msgs::Pose FindTransformation(const vector<CvPoint2D32f> &imgpts, const vector<Vector> &objpts, const Transform& tlocal, CHECKERBOARD &cb)
00452 {
00453 CvMat *objpoints = cvCreateMat(3,objpts.size(),CV_32FC1);
00454 for(size_t i=0; i<objpts.size(); ++i) {
00455 cvSetReal2D(objpoints, 0,i, objpts[i].x);
00456 cvSetReal2D(objpoints, 1,i, objpts[i].y);
00457 cvSetReal2D(objpoints, 2,i, objpts[i].z);
00458 }
00459
00460 geometry_msgs::Pose pose;
00461 Transform tchecker;
00462 assert(sizeof(tchecker.trans.x)==sizeof(float));
00463 float fR3[3];
00464 CvMat R3, T3;
00465 assert(sizeof(pose.position.x) == sizeof(double));
00466 cvInitMatHeader(&R3, 3, 1, CV_32FC1, fR3);
00467 cvInitMatHeader(&T3, 3, 1, CV_32FC1, &tchecker.trans.x);
00468
00469 float kc[4] = {0};
00470 CvMat kcmat;
00471 cvInitMatHeader(&kcmat,1,4,CV_32FC1,kc);
00472
00473 CvMat img_points;
00474 cvInitMatHeader(&img_points, 1,imgpts.size(), CV_32FC2, const_cast<CvPoint2D32f*>(&imgpts[0]));
00475
00476 cvFindExtrinsicCameraParams2(objpoints, &img_points, this->intrinsic_matrix, &kcmat, &R3, &T3);
00477 cvReleaseMat(&objpoints);
00478
00479 double fang = sqrt(fR3[0]*fR3[0] + fR3[1]*fR3[1] + fR3[2]*fR3[2]);
00480 if( fang >= 1e-6 ) {
00481 double fmult = sin(fang/2)/fang;
00482 tchecker.rot = Vector(cos(fang/2),fR3[0]*fmult, fR3[1]*fmult, fR3[2]*fmult);
00483 }
00484
00485
00486 Transform center(Vector(1,0,0,0),Vector(
00487 cb.cellwidth*(cb.griddims.width-1)/2.0,
00488 cb.cellheight*(cb.griddims.height-1)/2.0,
00489 0));
00490
00491
00492 Transform rot180(Vector(1,0,0,0),Vector(0,0,0));
00493 rot180.rotfromaxisangle(Vector(0,0,1),(float)M_PI);
00494
00495 Transform tglobal1 = tchecker*center*tlocal;
00496 Transform tglobal2 = tchecker*center*rot180*tlocal;
00497 TransformMatrix diff1(cb.previous_pose.inverse() * tglobal1);
00498 TransformMatrix diff2(cb.previous_pose.inverse() * tglobal2);
00499
00500 Transform tglobal;
00501 if(diff1.m[0]>=0)
00502 tglobal = tglobal1;
00503 else
00504 tglobal = tglobal2;
00505
00506 cb.previous_pose = tglobal;
00507
00508 pose.position.x = tglobal.trans.x;
00509 pose.position.y = tglobal.trans.y;
00510 pose.position.z = tglobal.trans.z;
00511 pose.orientation.x = tglobal.rot.y;
00512 pose.orientation.y = tglobal.rot.z;
00513 pose.orientation.z = tglobal.rot.w;
00514 pose.orientation.w = tglobal.rot.x;
00515 return pose;
00516 }
00517 };
00518
00520
00521 int main(int argc, char **argv)
00522 {
00523 ros::init(argc,argv,"checkerboard_detector");
00524 if( !ros::master::check() )
00525 return 1;
00526
00527 CheckerboardDetector cd;
00528 ros::spin();
00529
00530 return 0;
00531 }