00001
00002
00003
00004
00005
00006
00007
00008 #include <ros/ros.h>
00009 #include <sensor_msgs/CameraInfo.h>
00010 #include <sensor_msgs/Image.h>
00011 #include <cv_bridge/cv_bridge.h>
00012 #include <sensor_msgs/image_encodings.h>
00013 #include <opencv2/imgproc/imgproc.hpp>
00014 #include <opencv2/highgui/highgui.hpp>
00015 #include <tf/transform_datatypes.h>
00016 #include <articulation_msgs/TrackMsg.h>
00017
00018 using namespace std;
00019
00020 const int MAX_PLANES = 10;
00021
00022 int PLANES = 1;
00023 bool SHOW_IMAGES = true;
00024
00025 int RANSAC_ITERATIONS = 200;
00026 double RANSAC_DISTANCE = 0.01;
00027 int RANSAC_DOWNSAMPLE = 15;
00028 int RANSAC_FITTING_ITERATIONS = 200;
00029
00030 double FILTER_Z = 2;
00031
00032 int COST_INPLANE = 0;
00033 int COST_FREE = 255;
00034 int COST_OCCLUDED = 20;
00035 int COST_UNKNOWN = 20;
00036
00037 double PRIOR_WIDTH = 0.1;
00038 double PRIOR_HEIGHT = 0.1;
00039
00040 double STEP_TRANS = 0.005;
00041 double STEP_ROT = M_PI/180*0.5;
00042 int STEP_FACTOR[] = {8,4,2,1};
00043
00044 double THRESHOLD_PRECISION = 0.7;
00045 double THRESHOLD_RECALL = 0.7;
00046
00047 int CLIP_LEFT = 16;
00048 int CLIP_RIGHT = 16;
00049 int CLIP_TOP = 40;
00050 int CLIP_BOTTOM = 16;
00051
00052 double MAX_DIFF_TRANS = 0.10;
00053 double MAX_DIFF_ROT = M_PI/180*20;
00054 double MAX_DIFF_SIZE = 0.05;
00055
00056 struct Observation {
00057 geometry_msgs::Transform transform;
00058 float w;
00059 float h;
00060 float precision;
00061 float recall;
00062 };
00063
00064 struct Track {
00065 std::vector<Observation> track;
00066 bool modified;
00067 };
00068
00069 sensor_msgs::CameraInfo::ConstPtr cameraInfo_;
00070 cv_bridge::CvImagePtr cv_ptr;
00071 cv::Mat debugImage_;
00072 cv::Mat tmpImage_;
00073 cv::Mat planeImage[MAX_PLANES];
00074 int planeSize[MAX_PLANES];
00075 cv::Vec3f planeCenter[MAX_PLANES];
00076 cv::Vec3f planeNormal[MAX_PLANES];
00077
00078 ros::Publisher visualization_pub_;
00079 ros::Publisher visualization_array_pub_;
00080 ros::Publisher track_pub_;
00081
00082 std::vector<Track > tracks;
00083
00084 void CountConvexPoly( cv::Mat& img, const cv::Point* v, int npts,int &pixel_value,int &pixel_size,int &pixel_occ)
00085 {
00086 pixel_value = 0;
00087 pixel_size = 0;
00088 pixel_occ = 0;
00089 int line_type=9;
00090 int shift=0;
00091 enum { XY_SHIFT = 16, XY_ONE = 1 << XY_SHIFT, DRAWING_STORAGE_BLOCK = (1<<12) - 256 };
00092 struct
00093 {
00094 int idx, di;
00095 int x, dx, ye;
00096 }
00097 edge[2];
00098
00099 int delta = shift ? 1 << (shift - 1) : 0;
00100 int i, y, imin = 0, left = 0, right = 1, x1, x2;
00101 int edges = npts;
00102 int xmin, xmax, ymin, ymax;
00103 uchar* ptr = img.data;
00104 cv::Size size = img.size();
00105 cv::Point p0;
00106 int delta1, delta2;
00107
00108 if( line_type < CV_AA )
00109 delta1 = delta2 = XY_ONE >> 1;
00110 else
00111 delta1 = XY_ONE - 1, delta2 = 0;
00112
00113 p0 = v[npts - 1];
00114 p0.x <<= XY_SHIFT - shift;
00115 p0.y <<= XY_SHIFT - shift;
00116
00117 assert( 0 <= shift && shift <= XY_SHIFT );
00118 xmin = xmax = v[0].x;
00119 ymin = ymax = v[0].y;
00120
00121 for( i = 0; i < npts; i++ )
00122 {
00123 cv::Point p = v[i];
00124 if( p.y < ymin )
00125 {
00126 ymin = p.y;
00127 imin = i;
00128 }
00129
00130 ymax = std::max( ymax, p.y );
00131 xmax = std::max( xmax, p.x );
00132 xmin = MIN( xmin, p.x );
00133
00134 p.x <<= XY_SHIFT - shift;
00135 p.y <<= XY_SHIFT - shift;
00136
00137 cv::Point pt0, pt1;
00138 pt0.x = p0.x >> XY_SHIFT;
00139 pt0.y = p0.y >> XY_SHIFT;
00140 pt1.x = p.x >> XY_SHIFT;
00141 pt1.y = p.y >> XY_SHIFT;
00142 p0 = p;
00143 }
00144
00145 xmin = (xmin + delta) >> shift;
00146 xmax = (xmax + delta) >> shift;
00147 ymin = (ymin + delta) >> shift;
00148 ymax = (ymax + delta) >> shift;
00149
00150 if( npts < 3 || xmax < 0 || ymax < 0 || xmin >= size.width || ymin >= size.height )
00151 return;
00152
00153 ymax = MIN( ymax, size.height - 1 );
00154 edge[0].idx = edge[1].idx = imin;
00155
00156 edge[0].ye = edge[1].ye = y = ymin;
00157 edge[0].di = 1;
00158 edge[1].di = npts - 1;
00159
00160 ptr += img.step*y;
00161
00162 do
00163 {
00164 if( line_type < CV_AA || y < ymax || y == ymin )
00165 {
00166 for( i = 0; i < 2; i++ )
00167 {
00168 if( y >= edge[i].ye )
00169 {
00170 int idx = edge[i].idx, di = edge[i].di;
00171 int xs = 0, xe, ye, ty = 0;
00172
00173 for(;;)
00174 {
00175 ty = (v[idx].y + delta) >> shift;
00176 if( ty > y || edges == 0 )
00177 break;
00178 xs = v[idx].x;
00179 idx += di;
00180 idx -= ((idx < npts) - 1) & npts;
00181 edges--;
00182 }
00183
00184 ye = ty;
00185 xs <<= XY_SHIFT - shift;
00186 xe = v[idx].x << (XY_SHIFT - shift);
00187
00188
00189 if( y >= ye )
00190 return;
00191
00192 edge[i].ye = ye;
00193 edge[i].dx = ((xe - xs)*2 + (ye - y)) / (2 * (ye - y));
00194 edge[i].x = xs;
00195 edge[i].idx = idx;
00196 }
00197 }
00198 }
00199
00200 if( edge[left].x > edge[right].x )
00201 {
00202 left ^= 1;
00203 right ^= 1;
00204 }
00205
00206 x1 = edge[left].x;
00207 x2 = edge[right].x;
00208
00209 if( y >= 0 )
00210 {
00211 int xx1 = (x1 + delta1) >> XY_SHIFT;
00212 int xx2 = (x2 + delta2) >> XY_SHIFT;
00213
00214 if( xx2 >= 0 && xx1 < size.width )
00215 {
00216 if( xx1 < 0 )
00217 xx1 = 0;
00218 if( xx2 >= size.width )
00219 xx2 = size.width - 1;
00220 for(int i=xx1;i<xx2;i++) {
00221
00222 pixel_size += 1;
00223 pixel_value += ptr[i];
00224 if(ptr[i]==0) pixel_occ += 1;
00225 }
00226
00227 }
00228 }
00229
00230 x1 += edge[left].dx;
00231 x2 += edge[right].dx;
00232
00233 edge[left].x = x1;
00234 edge[right].x = x2;
00235 ptr += img.step;
00236 }
00237 while( ++y <= ymax );
00238 }
00239
00240 cv::Point samplePoint(int step) {
00241 cv::Point p(0, 0);
00242 int iter = 0;
00243 do {
00244 p = cv::Point(rand() % (tmpImage_.cols/step), rand() % (tmpImage_.rows/step)) * step;
00245 } while (!isfinite(tmpImage_.at<float> (p)) && iter++ < 10 );
00246 return (p);
00247 }
00248
00249 inline cv::Point3f to3D(cv::Point a) {
00250 cv::Point3f pt;
00251 float constant = 1.00 / cameraInfo_->K[0];
00252 pt.x = (a.x - (cv_ptr->image.cols >> 1)) * cv_ptr->image.at<float> (a)
00253 * constant;
00254 pt.y = (a.y - (cv_ptr->image.rows >> 1)) * cv_ptr->image.at<float> (a)
00255 * constant;
00256
00257 pt.z = cv_ptr->image.at<float> (a);
00258 return pt;
00259 }
00260
00261 inline cv::Point to2D(cv::Point3f pt) {
00262 cv::Point a;
00263 a.x = pt.x/ pt.z * cameraInfo_->K[0] + (cv_ptr->image.cols >> 1);
00264 a.y = pt.y/ pt.z * cameraInfo_->K[0] + (cv_ptr->image.rows >> 1);
00265 return a;
00266 }
00267
00268 bool extractPlanes() {
00269 ros::Time begin = ros::Time::now();
00270
00271
00272 tmpImage_ = cv_ptr->image.clone();
00273 const float bad_point = std::numeric_limits<float>::quiet_NaN ();
00274
00275 for (int plane=0;plane<PLANES;plane++) {
00276 int best_count = 0;
00277 cv::Point3f best_plane_normal(0,0,0);
00278 float best_plane_d = 0;
00279 for (int iter = 0; iter < RANSAC_ITERATIONS; iter++) {
00280
00281 cv::Point p1 = samplePoint(RANSAC_DOWNSAMPLE);
00282 cv::Point p2 = samplePoint(RANSAC_DOWNSAMPLE);
00283 cv::Point p3 = samplePoint(RANSAC_DOWNSAMPLE);
00284
00285 cv::Point3f P1 = to3D(p1);
00286 cv::Point3f P2 = to3D(p2);
00287 cv::Point3f P3 = to3D(p3);
00288
00289 cv::Point3f plane_normal = (P2 - P1).cross(P3 - P1);
00290 plane_normal *= 1/sqrt((plane_normal.dot(plane_normal)));
00291 float plane_d = plane_normal.dot(P1);
00292
00293 if(!isfinite(plane_d)) continue;
00294 int count = 0;
00295
00296 for (int y = 0; y < tmpImage_.rows; y+=RANSAC_DOWNSAMPLE) {
00297 for (int x = 0; x < tmpImage_.cols; x+=RANSAC_DOWNSAMPLE) {
00298 if (isfinite(tmpImage_.at<float>(cv::Point(x,y))) &&
00299 (fabs(plane_normal.dot(to3D(cv::Point(x, y))) - plane_d) < RANSAC_DISTANCE)) {
00300 count++;
00301 }
00302 }
00303 }
00304 if(count > best_count) {
00305 best_count = count;
00306 best_plane_normal = plane_normal;
00307 best_plane_d = plane_d;
00308 }
00309 }
00310 if(!isfinite(best_plane_d)) return false;
00311
00312
00313 cv::Mat points(tmpImage_.rows/RANSAC_DOWNSAMPLE * tmpImage_.cols/RANSAC_DOWNSAMPLE,3,CV_32FC1);
00314 cv::Vec3f center;
00315 int n=0;
00316 for (int y = 0; y < tmpImage_.rows; y+=RANSAC_DOWNSAMPLE) {
00317 for (int x = 0; x < tmpImage_.cols; x+=RANSAC_DOWNSAMPLE) {
00318 if (fabs(best_plane_normal.dot(to3D(cv::Point(x, y))) - best_plane_d)
00319 < RANSAC_DISTANCE) {
00320 tmpImage_.at<float>(cv::Point(x,y)) = bad_point;
00321 cv::Point3f P = to3D(cv::Point(x, y));
00322 points.at<float>(n,0) =P.x;
00323 points.at<float>(n,1) =P.y;
00324 points.at<float>(n,2) =P.z;
00325 center += cv::Vec3f(P);
00326 n++;
00327 }
00328 }
00329 }
00330 points = points.rowRange(0,n);
00331 center *= 1.0/n;
00332 planeCenter[plane] = center;
00333 for(int i=0;i<n;i++) {
00334 cv::Vec3f d = points.at<cv::Vec3f>(i,0) - center;
00335 points.at<float>(i,0) = d[0];
00336 points.at<float>(i,1) = d[1];
00337 points.at<float>(i,2) = d[2];
00338 }
00339
00340 cv::SVD svd(points);
00344
00345
00346
00347
00348 best_plane_normal.x = svd.vt.at<float>(2,0);
00349 best_plane_normal.y = svd.vt.at<float>(2,1);
00350 best_plane_normal.z = svd.vt.at<float>(2,2);
00351 if(best_plane_normal.dot(cv::Point3f(0,0,1))<0)
00352 best_plane_normal = -best_plane_normal;
00353 best_plane_d = best_plane_normal.dot( center );
00354
00355
00356
00357
00358
00359
00360
00361 planeNormal[plane] = best_plane_normal;
00362
00363
00364 planeImage[plane] = cv::Mat::zeros(cv_ptr->image.size(),CV_8UC1);
00365 planeSize[plane]=0;
00366
00367 for (int y = 0; y < cv_ptr->image.rows; y++) {
00368 for (int x = 0; x < cv_ptr->image.cols; x++) {
00369 float dist = best_plane_normal.dot(to3D(cv::Point(x, y))) - best_plane_d;
00370 if (fabs(dist) < RANSAC_DISTANCE) {
00371 debugImage_.at<cv::Vec3f>(cv::Point(x,y))[plane%3] = 1.0 / (1+plane/3);
00372 planeSize[plane]++;
00373 }
00374
00375
00376
00377 if(!isfinite(dist)) {
00378
00379
00380 planeImage[plane].at<char>(cv::Point(x,y)) = COST_UNKNOWN;
00381 } else
00382 if (dist > RANSAC_DISTANCE) {
00383
00384
00385 planeImage[plane].at<char>(cv::Point(x,y)) = COST_FREE;
00386 } else
00387 if (dist < -RANSAC_DISTANCE) {
00388
00389
00390 planeImage[plane].at<char>(cv::Point(x,y)) = COST_OCCLUDED;
00391 } else {
00392
00393
00394 planeImage[plane].at<char>(cv::Point(x,y)) = COST_INPLANE;
00395 }
00396
00397 }
00398 }
00399 cout <<"inliers="<<best_count<<endl;
00400 }
00401
00402 return true;
00403 }
00404
00405 float evalPercept(Observation& percept,int plane,bool draw=false) {
00406 float score = 0;
00407 int pixel_value = 0;
00408 int pixel_occ = 0;
00409 int pixel_size = 0;
00410
00411
00412 btTransform bulletPose;
00413 tf::transformMsgToTF(percept.transform,bulletPose);
00414
00415
00416
00417
00418
00419
00420
00421
00422 btVector3 points3[4];
00423 points3[0] = bulletPose * btVector3(0,0,0);
00424 points3[1] = bulletPose * btVector3(percept.w,0,0);
00425 points3[2] = bulletPose * btVector3(percept.w,percept.h,0);
00426 points3[3] = bulletPose * btVector3(0,percept.h,0);
00427
00428
00429 cv::Point points[4];
00430 for(int i=0;i<4;i++) {
00431 points[i] = to2D( cv::Point3f(points3[i][0],points3[i][1],points3[i][2]) );
00432 if(points[i].x < 0 || points[i].y < 0 || points[i].x >= planeImage[plane].cols || points[i].y >= planeImage[plane].rows) {
00433 percept.precision = 0;
00434 percept.recall = 0;
00435 return 0;
00436 }
00437 }
00438
00439 if(draw) {
00440 for(int i=0;i<4;i++) {
00441 cv::line(debugImage_,points[i%4],points[(i+1)%4],cv::Scalar(1,1,1),3);
00442 }
00443 cv::circle(debugImage_,points[0],5,cv::Scalar(0,0,1));
00444 }
00445 CountConvexPoly(planeImage[plane],points,4,pixel_value,pixel_size,pixel_occ);
00446
00447 score = 1.0 / pow(pixel_size,0.95) * (pixel_size*255 - pixel_value);
00448 percept.precision = (pixel_size - pixel_value/255) /(double) pixel_size;
00449 percept.recall= pixel_occ / (double)planeSize[plane];
00450 if(draw) {
00451 cout <<" score = "<<score<<" pixel_size="<<pixel_size<<" pixel_value="<<(pixel_value/255)<<" planesize="<<planeSize[plane]
00452 <<" precision="<<percept.precision<<" recall="<<percept.recall<<endl;
00453 }
00454
00455 return score;
00456 }
00457
00458 bool checkPercept(Observation& percept,int plane) {
00459 btTransform bulletPose;
00460 tf::transformMsgToTF(percept.transform,bulletPose);
00461 btVector3 points3[4];
00462 points3[0] = bulletPose * btVector3(0,0,0);
00463 points3[1] = bulletPose * btVector3(percept.w,0,0);
00464 points3[2] = bulletPose * btVector3(percept.w,percept.h,0);
00465 points3[3] = bulletPose * btVector3(0,percept.h,0);
00466
00467
00468 cv::Point points[4];
00469 for(int i=0;i<4;i++) {
00470
00471
00472 points[i] = to2D( cv::Point3f(points3[i][0],points3[i][1],points3[i][2]) );
00473 if(points[i].x < CLIP_LEFT || points[i].y < CLIP_TOP || points[i].x >= planeImage[plane].cols-CLIP_RIGHT || points[i].y >= planeImage[plane].rows-CLIP_TOP) {
00474 return false;
00475 }
00476 }
00477 return true;
00478 }
00479
00480 float optimizePercept(Observation& percept,int plane) {
00481 float best_score = evalPercept(percept,plane);
00482 float score;
00483 Observation best_percept = percept;
00484 Observation current_percept = percept;
00485 btTransform pose,poseInc;
00486 for(int iter=0;iter<RANSAC_FITTING_ITERATIONS;iter++) {
00487 bool change = false;
00488 Observation previous_best_percept = best_percept;
00489 for(int step_size=0;step_size<4;step_size++) {
00490 for(int step=0;step<10;step++) {
00491 current_percept = previous_best_percept;
00492 tf::transformMsgToTF(current_percept.transform,pose);
00493 float step_trans = STEP_TRANS*STEP_FACTOR[step_size];
00494 float step_rot = STEP_ROT*STEP_FACTOR[step_size];
00495 switch(step) {
00496 case 0:
00497 pose = pose * btTransform(btQuaternion(0,0,0,1),btVector3(+step_trans,0,0));
00498 current_percept.w -= step_trans;
00499 break;
00500 case 1:
00501 pose = pose * btTransform(btQuaternion(0,0,0,1),btVector3(-step_trans,0,0));
00502 current_percept.w += step_trans;
00503 break;
00504 case 2:
00505 pose = pose * btTransform(btQuaternion(0,0,0,1),btVector3(0,+step_trans,0));
00506 current_percept.h -= step_trans;
00507 break;
00508 case 3:
00509 pose = pose * btTransform(btQuaternion(0,0,0,1),btVector3(0,-step_trans,0));
00510 current_percept.h += step_trans;
00511 break;
00512 case 4:
00513 current_percept.w -= step_trans;
00514 break;
00515 case 5:
00516 current_percept.w += step_trans;
00517 break;
00518 case 6:
00519 current_percept.h -= step_trans;
00520 break;
00521 case 7:
00522 current_percept.h += step_trans;
00523 break;
00524 case 8:
00525 pose = pose * btTransform(btQuaternion(btVector3(0,0,1),+step_rot),btVector3(0,0,0));
00526 break;
00527 case 9:
00528 pose = pose * btTransform(btQuaternion(btVector3(0,0,1),-step_rot),btVector3(0,0,0));
00529 break;
00530 }
00531 tf::transformTFToMsg(pose,current_percept.transform);
00532 score = evalPercept(current_percept,plane);
00533 if(score>best_score) {
00534 best_score = score;
00535 best_percept = current_percept;
00536 change = true;
00537 }
00538 }
00539 if(change)
00540 break;
00541 }
00542
00543
00544 if(!change) break;
00545 }
00546 percept = best_percept;
00547 if(percept.precision>THRESHOLD_PRECISION && percept.recall>THRESHOLD_RECALL && checkPercept(best_percept,plane)) {
00548 score = evalPercept(best_percept,plane,true);
00549 cout << "plane="<<plane<<" precision="<<percept.precision<<" recall="<<percept.recall<<endl;
00550 return best_score;
00551 } else {
00552 return 0;
00553 }
00554 }
00555
00556 bool sameObject(Observation& a,Observation& b) {
00557 if(fabs(a.w - b.w)> MAX_DIFF_SIZE) return false;
00558 if(fabs(a.h - b.h)> MAX_DIFF_SIZE) return false;
00559 btTransform pa,pb;
00560 tf::transformMsgToTF(a.transform,pa);
00561 tf::transformMsgToTF(b.transform,pb);
00562 btTransform diff = pa.inverseTimes(pb);
00563 if(diff.getOrigin().length() > MAX_DIFF_TRANS) return false;
00564 if(diff.getRotation().getAngle() > MAX_DIFF_ROT) return false;
00565 return true;
00566 }
00567
00568 void addToTrack(Observation& percept) {
00569 bool found = false;
00570 for(size_t i=0;i<tracks.size();i++) {
00571 for(size_t j=0;j<tracks[i].track.size();j++) {
00572 if( sameObject( percept, tracks[i].track[j] ) ) {
00573 tracks[i].track.push_back(percept);
00574 tracks[i].modified = true;
00575 cout <<"add pose observation of object id="<<i<<" (total: "<<tracks[i].track.size()<<" observations)"<<endl;
00576 found = true;
00577 break;
00578 }
00579 }
00580 if(found)
00581 break;
00582 }
00583 if(!found) {
00584 cout <<"new object detected (id="<<tracks.size()<<" w="<<percept.w<<" h="<<percept.h<<endl;
00585 Track t;
00586 t.modified = true;
00587 t.track.push_back(percept);
00588 tracks.push_back(t);
00589 }
00590 }
00591
00592 int openChannel(articulation_msgs::TrackMsg &track,std::string name,bool autocreate) {
00593
00594 size_t i = 0;
00595 for(; i < track.channels.size(); i++) {
00596 if(track.channels[i].name == name)
00597 break;
00598 }
00599
00600 if( i == track.channels.size() ) {
00601 if(!autocreate) return -1;
00602
00603 sensor_msgs::ChannelFloat32 ch;
00604 ch.name = name;
00605 track.channels.push_back(ch);
00606 }
00607
00608 track.channels[i].values.resize( track.pose.size() );
00609
00610 return i;
00611 }
00612
00613 void sendTracks(std_msgs::Header header) {
00614 for(size_t i=0;i<tracks.size();i++) {
00615 if(!tracks[i].modified)
00616 continue;
00617 if(tracks[i].track.size()<5)
00618 continue;
00619 articulation_msgs::TrackMsg msg;
00620 msg.header = header;
00621 int ch_width = openChannel(msg,"width",true);
00622 int ch_height = openChannel(msg,"height",true);
00623 for(size_t j=0;j<tracks[i].track.size();j++) {
00624 geometry_msgs::Pose pose;
00625 pose.position.x = tracks[i].track[j].transform.translation.x;
00626 pose.position.y = tracks[i].track[j].transform.translation.y;
00627 pose.position.z = tracks[i].track[j].transform.translation.z;
00628 pose.orientation.x = tracks[i].track[j].transform.rotation.x;
00629 pose.orientation.y = tracks[i].track[j].transform.rotation.y;
00630 pose.orientation.z = tracks[i].track[j].transform.rotation.z;
00631 pose.orientation.w = tracks[i].track[j].transform.rotation.w;
00632 msg.pose.push_back(pose);
00633 msg.channels[ch_width].values.push_back(tracks[i].track[j].w);
00634 msg.channels[ch_height].values.push_back(tracks[i].track[j].h);
00635 }
00636 msg.id = i;
00637 track_pub_.publish(msg);
00638 tracks[i].modified=false;
00639 }
00640 }
00641
00642 void infoCallback(const sensor_msgs::CameraInfo::ConstPtr& msg) {
00643 cameraInfo_ = msg;
00644 cout << "received info" << endl;
00645 }
00646
00647 void imageCallback(const sensor_msgs::Image::ConstPtr& msg) {
00648 cout << "received image" << endl;
00649 ros::Time begin = ros::Time::now();
00650 if (!cameraInfo_)
00651 return;
00652 try {
00653 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::MONO16);
00654 } catch (cv_bridge::Exception& e) {
00655 ROS_ERROR("cv_bridge exception: %s", e.what());
00656 return;
00657 }
00658
00659
00660 cvtColor(cv_ptr->image * 0.2, debugImage_, CV_GRAY2BGR);
00661 debugImage_.step.p[2]=4;
00662
00663
00664
00665
00666
00667
00668
00669
00670 if(!extractPlanes()) {
00671 return;
00672 }
00673
00674 for(int plane=0;plane<PLANES;plane++) {
00675 Observation percept;
00676
00677 btVector3 center(planeCenter[plane][0],planeCenter[plane][1],planeCenter[plane][2]);
00678 btVector3 z(planeNormal[plane][0],planeNormal[plane][1],planeNormal[plane][2]);
00679 btVector3 x(1,0,0);
00680 x = x - x.dot(z)*z;
00681 btVector3 y = z.cross(x);
00682 btTransform transform;
00683 transform.setOrigin(center);
00684 btMatrix3x3 basis;
00685 basis.setValue( x[0],y[0],z[0],x[1],y[1],z[1],x[2],y[2],z[2] );
00686 btQuaternion q;
00687 basis.getRotation(q);
00688 transform.setRotation(q);
00689 transform = transform * btTransform(btQuaternion(0,0,0,1),btVector3(-PRIOR_WIDTH/2,-PRIOR_HEIGHT/2,0));
00690
00691 tf::transformTFToMsg(transform,percept.transform);
00692 percept.w = PRIOR_WIDTH;
00693 percept.h = PRIOR_HEIGHT;
00694
00695 float score = optimizePercept(percept,plane);
00696 if(score>0) {
00697 addToTrack(percept);
00698 }
00699
00700
00701
00702
00703 }
00704
00705 cout <<"duration= "<< (ros::Time::now() - begin).toSec()<<endl;
00706
00707 if(SHOW_IMAGES) {
00708 cv::imshow("depth", debugImage_);
00709 cv::waitKey(3);
00710 }
00711
00712 sendTracks(msg->header);
00713 }
00714
00715
00716 int main(int argc, char** argv) {
00717 ros::init(argc, argv, "detector");
00718 ros::NodeHandle nh("~");
00719
00720 nh.getParam("planes",PLANES);
00721 nh.getParam("show_images",SHOW_IMAGES);
00722
00723
00724 nh.getParam("ransac_iterations",RANSAC_ITERATIONS);
00725 nh.getParam("ransac_distance",RANSAC_DISTANCE);
00726 nh.getParam("ransac_downsample",RANSAC_DOWNSAMPLE);
00727 nh.getParam("ransac_fitting_iterations",RANSAC_FITTING_ITERATIONS);
00728 nh.getParam("filter_z",FILTER_Z);
00729
00730 nh.getParam("cost_inplane",COST_INPLANE);
00731 nh.getParam("cost_free",COST_FREE);
00732 nh.getParam("cost_occluded",COST_OCCLUDED);
00733 nh.getParam("cost_unknown",COST_UNKNOWN);
00734
00735 nh.getParam("prior_width",PRIOR_WIDTH);
00736 nh.getParam("prior_height",PRIOR_HEIGHT);
00737
00738 nh.getParam("step_trans",STEP_TRANS);
00739 nh.getParam("step_rot",STEP_ROT);
00740
00741 nh.getParam("threshold_precision",THRESHOLD_PRECISION);
00742 nh.getParam("threshold_recall",THRESHOLD_RECALL);
00743
00744 nh.getParam("clip_left",CLIP_LEFT);
00745 nh.getParam("clip_right",CLIP_RIGHT);
00746 nh.getParam("clip_top",CLIP_TOP);
00747 nh.getParam("clip_bottom",CLIP_BOTTOM);
00748
00749 nh.getParam("MAX_DIFF_TRANS",MAX_DIFF_TRANS);
00750 nh.getParam("MAX_DIFF_ROT",MAX_DIFF_ROT);
00751 nh.getParam("MAX_DIFF_SIZE",MAX_DIFF_SIZE);
00752
00753 ros::NodeHandle n;
00754
00755 ros::Subscriber sub = n.subscribe("camera/depth/image", 1, imageCallback);
00756 ros::Subscriber sub2 = n.subscribe("camera/depth/camera_info", 1,
00757 infoCallback);
00758 track_pub_ = n.advertise<articulation_msgs::TrackMsg> ("track", 100);
00759
00760 if(SHOW_IMAGES)
00761 cv::namedWindow("depth");
00762
00763 ros::spin();
00764 }