tabletop_detector.cpp
Go to the documentation of this file.
00001 #include "hrl_table_detect/tabletop_detector.h"
00002 using namespace std;
00003 
00004 namespace hrl_table_detect {
00005 
00006     TabletopDetector::TabletopDetector() : img_trans(nh) {
00007     }
00008 
00009     
00010     void TabletopDetector::onInit() {
00012         nh_priv = ros::NodeHandle("~");
00013         bool run_service;
00014         nh_priv.param<bool>("run_service", run_service, false);
00015         nh_priv.param<double>("scan_width", maxy, 1.5); miny = -maxy;
00016         nh_priv.param<double>("min_scan_depth", minx, 0.3);
00017         nh_priv.param<double>("max_scan_depth", maxx, 3.0);
00018         nh_priv.param<double>("min_table_height", minz, 0.5);
00019         nh_priv.param<double>("max_table_height", maxz, 1.0);
00020         nh_priv.param<double>("height_image_res", resolution, 200);
00021         nh_priv.param<double>("inlier_magnitude", inlier_magnitude, 200);
00022         nh_priv.param<int32_t>("num_edge_dilate", num_edge_dilate, 1);
00023         nh_priv.param<int32_t>("num_closes", num_closes, 1);
00024         nh_priv.param<double>("degree_bins", degree_bins, 0.3);
00025         nh_priv.param<double>("hough_thresh", hough_thresh, 30); hough_thresh *= resolution;
00026         nh_priv.param<double>("theta_gran", theta_gran, 1); theta_gran *= CV_PI/180;
00027         nh_priv.param<double>("rho_gran", rho_gran, 0.1); rho_gran *= resolution;
00028         nh_priv.param<double>("xgran", xgran, 0.1); xgran *= resolution;
00029         nh_priv.param<double>("ygran", ygran, 0.1); ygran *= resolution;
00030         imgx = (maxx-minx)*resolution;
00031         imgy = (maxy-miny)*resolution;
00033 
00034         grasp_points_found = false;
00035         height_img_sum = cv::Mat::zeros(imgx, imgy, CV_32F);
00036         height_img_count = cv::Mat::zeros(imgx, imgy, CV_32F);
00037         height_img_max = cv::Mat::zeros(imgx, imgy, CV_8U);
00038 
00039         pc_pub = nh.advertise<pcl::PointCloud<pcl::PointXYZRGB> >("/table_detection_vis", 1);
00040         height_pub = img_trans.advertise("/height_image", 1);
00041         pose_arr_pub = nh.advertise<geometry_msgs::PoseArray>("/table_approach_poses", 1);
00042         nh_priv = ros::NodeHandle("~");
00043         if(run_service) {
00044             table_detect_start = nh.advertiseService("/table_detect_start", &TabletopDetector::startCallback, this);
00045             table_detect_stop = nh.advertiseService("/table_detect_stop", &TabletopDetector::stopCallback, this);
00046             table_detect_inst = nh.advertiseService("/table_detect_inst", &TabletopDetector::instCallback, this);
00047         }
00048         else
00049             pc_sub = nh.subscribe("/kinect_head/rgb/points", 1, &TabletopDetector::pcCallback, this);
00050         ros::Duration(1.0).sleep();
00051     }
00052 
00053     bool TabletopDetector::startCallback(hrl_table_detect::DetectTableStart::Request& req, 
00054                                        hrl_table_detect::DetectTableStart::Response& resp) {
00055         grasp_points_found = false;
00056         height_img_sum = cv::Mat::zeros(imgx, imgy, CV_32F);
00057         height_img_count = cv::Mat::zeros(imgx, imgy, CV_32F);
00058         height_img_max = cv::Mat::zeros(imgx, imgy, CV_8U);
00059         pc_sub = nh.subscribe("/kinect_head/rgb/points", 1, &TabletopDetector::pcCallback, this);
00060         return true;
00061     }
00062 
00063     bool TabletopDetector::stopCallback(hrl_table_detect::DetectTableStop::Request& req, 
00064                                        hrl_table_detect::DetectTableStop::Response& resp) {
00065         pc_sub.shutdown();
00066         resp.grasp_points = grasp_points;
00067         return true;
00068     }
00069 
00070     bool TabletopDetector::instCallback(hrl_table_detect::DetectTableInst::Request& req, 
00071                                        hrl_table_detect::DetectTableInst::Response& resp) {
00072         grasp_points_found = false;
00073         height_img_sum = cv::Mat::zeros(imgx, imgy, CV_32F);
00074         height_img_count = cv::Mat::zeros(imgx, imgy, CV_32F);
00075         height_img_max = cv::Mat::zeros(imgx, imgy, CV_8U);
00076         pc_sub = nh.subscribe("/kinect_head/rgb/points", 1, &TabletopDetector::pcCallback, this);
00077         double begin_time = ros::Time::now().toSec();
00078         double now = begin_time;
00079         ros::Rate r(100);
00080         while(ros::ok() && now - begin_time < req.block_time) {
00081             ros::spinOnce();
00082             now = ros::Time::now().toSec();
00083             r.sleep();
00084         }
00085         pc_sub.shutdown();
00086         resp.grasp_points = grasp_points;
00087         return true;
00088     }
00089 
00090     bool compind(uint32_t a, uint32_t b, vector<float> v) { return v[a] < v[b]; }
00091 
00092     void convCvBox2DPoly(CvBox2D& box, CvPoint**& pts, int*& npts) {
00093         pts = new CvPoint*[1]; pts[0] = new CvPoint[4];
00094         float x = box.center.x, y = box.center.y;
00095         float x1 = box.size.height*cos(box.angle-CV_PI/2), y1 = -box.size.height*sin(box.angle-CV_PI/2);
00096         float x2 = box.size.width*cos(box.angle), y2 = -box.size.width*sin(box.angle);
00097         pts[0][0].x = x+x1+x2; pts[0][0].y = y+y1+y2;
00098         pts[0][1].x = x-x1+x2; pts[0][1].y = y-y1+y2;
00099         pts[0][2].x = x-x1-x2; pts[0][2].y = y-y1-y2;
00100         pts[0][3].x = x+x1-x2; pts[0][3].y = y+y1-y2;
00101         pts[0][4].x = x+x1+x2; pts[0][4].y = y+y1+y2;
00102         npts = new int[1]; npts[0] = 5;
00103     }
00104 
00105     void drawCvBox2D(IplImage& img, CvBox2D& box, cv::Scalar color, int width=1) {
00106         CvPoint** rpts; int* npts;
00107         convCvBox2DPoly(box, rpts, npts);
00108         cvPolyLine(&img, rpts, npts, 1, 1, color, width);
00109         delete[] rpts[0]; delete[] rpts; delete[] npts;
00110     }
00111 
00112     void fillCvBox2D(IplImage& img, CvBox2D& box, cv::Scalar color) {
00113         CvPoint** rpts; int* npts;
00114         convCvBox2DPoly(box, rpts, npts);
00115         cvFillPoly(&img, rpts, npts, 1, color);
00116         delete[] rpts[0]; delete[] rpts; delete[] npts;
00117     }
00118 
00119     void TabletopDetector::pcCallback(sensor_msgs::PointCloud2::ConstPtr pc_msg) {
00120         if(!pc_lock.try_lock())
00121             return;
00122 
00123         pcl::PointCloud<pcl::PointXYZRGB> pc_full, pc_full_frame;
00124         pcl::fromROSMsg(*pc_msg, pc_full);
00125         string base_frame("/base_link");
00126         ros::Time now = ros::Time::now();
00127         tf_listener.waitForTransform(pc_msg->header.frame_id, base_frame, now, ros::Duration(3.0));
00128         pcl_ros::transformPointCloud(base_frame, pc_full, pc_full_frame, tf_listener);
00129         // pc_full_frame is in torso lift frame
00130 
00131         cv::Mat cur_height_img = cv::Mat::zeros(imgx, imgy, CV_8U);
00132         
00133         BOOST_FOREACH(const pcl::PointXYZRGB& pt, pc_full_frame.points) {
00134             if(pt.x != pt.x || pt.y != pt.y || pt.z != pt.z)
00135                 continue;
00136             int32_t x, y, z;
00137             x = (pt.x - minx)/(maxx-minx) * imgx;
00138             y = (pt.y - miny)/(maxy-miny) * imgy;
00139             z = (pt.z - minz)/(maxz-minz) * 256;
00140             if(x < 0 || y < 0) continue; 
00141             if(x >= imgx || y >= imgy) continue;
00142             if(z < 0 || z >= 256) continue;
00143             if(cur_height_img.at<uint8_t>(x, y) == 0 || cur_height_img.at<uint8_t>(x, y) < (uint8_t) z)
00144                 cur_height_img.at<uint8_t>(x, y) = (uint8_t) z;
00145         }
00146         cv::max(height_img_max, cur_height_img, height_img_max);
00147         cv::Mat cur_height_img_flt;
00148         cur_height_img.convertTo(cur_height_img_flt, CV_32F);
00149         height_img_sum += cur_height_img_flt;
00150         cv::Mat cur_count(imgx, imgy, CV_8U);
00151         cur_count = (cur_height_img > 0) / 255;
00152         cv::Mat cur_count_flt(imgx, imgy, CV_32F);
00153         cur_count.convertTo(cur_count_flt, CV_32F);
00154         height_img_count += cur_count_flt;
00155         cv::Mat height_img_avg_flt = height_img_sum / height_img_count;
00156         cv::Mat height_img_avg(imgx, imgy, CV_8U);
00157         height_img_avg_flt.convertTo(height_img_avg, CV_8U);
00158         height_img_avg = height_img_max;
00159 
00160         cv::Mat height_hist(256, 1, CV_32F, cv::Scalar(0));
00161         for(uint32_t x=0;x<imgx;x++)
00162             for(uint32_t y=0;y<imgy;y++) {
00163                 if(height_img_avg.at<uint8_t>(x,y) == 255)
00164                     height_img_avg.at<uint8_t>(x,y) = 0;
00165                 if(height_img_avg.at<uint8_t>(x,y) != 0) {
00166                     height_hist.at<float>(height_img_avg.at<uint8_t>(x,y), 0)++;
00167                 }
00168             }
00170         uint32_t gfiltlen = 25;
00171         float stddev = 256/(maxz-minz) * 0.015;
00172         cv::Mat gauss_filt(gfiltlen, 1, CV_32F, cv::Scalar(0));
00173         for(uint32_t i=0;i<gfiltlen;i++)
00174             gauss_filt.at<float>(i,0) = 0.39894 / stddev * std::exp(-(i-((float)gfiltlen)/2)*(i-((float)gfiltlen)/2)/(2*stddev*stddev));
00175         //cout << gauss_filt;
00176         uint32_t maxval = 0, maxidx = 0;
00177         for(uint32_t i=0;i<256-gfiltlen;i++) {
00178             uint32_t sum = 0;
00179             for(uint32_t j=0;j<gfiltlen;j++) 
00180                 sum += height_hist.at<float>(i+j,0) * gauss_filt.at<float>(j,0);
00181             if(sum > maxval && i != 0) {
00182                 maxval = sum;
00183                 maxidx = i+gfiltlen/2;
00184             }
00185         }
00186         int32_t table_height = ((int32_t)maxidx);
00187         //printf("%d %d, ", maxval, maxidx);
00189         cv::Mat height_img_thresh(imgx, imgy, CV_8U);
00190         height_img_thresh = height_img_avg.clone();
00191         for(uint32_t x=0;x<imgx;x++)
00192             for(uint32_t y=0;y<imgy;y++) {
00193                 if(std::fabs(table_height - ((int32_t)height_img_thresh.at<uint8_t>(x,y))) < stddev*2)
00194                     height_img_thresh.at<uint8_t>(x,y) = 255;
00195                 else
00196                     height_img_thresh.at<uint8_t>(x,y) = 0;
00197             }
00199         IplImage height_img_thresh_ipl = height_img_thresh;
00200         IplConvKernel* element = cvCreateStructuringElementEx(3, 3, 1, 1, CV_SHAPE_RECT);
00201         cvMorphologyEx(&height_img_thresh_ipl, &height_img_thresh_ipl, NULL, element, CV_MOP_CLOSE, num_closes);
00202         //cvMorphologyEx(&height_img_thresh, &height_img_thresh, NULL, element, CV_MOP_OPEN, 2);
00203 
00204         cv::Mat height_img_thresh_blob = height_img_thresh.clone();
00205         IplImage blob_img = height_img_thresh_blob;
00206         CBlobResult blobs = CBlobResult(&blob_img, NULL, 0);
00207         //blobs.Filter(blobs, B_EXCLUDE, CBlobGetArea(), B_LESS, 10);
00208         CBlob biggestblob;
00209         blobs.GetNthBlob(CBlobGetArea(), 0, biggestblob);
00210         cv::Mat table_blob(imgx, imgy, CV_8U, cv::Scalar(0)); IplImage table_blob_img = table_blob;
00211         biggestblob.FillBlob(&table_blob_img, cv::Scalar(150));
00212         //drawCvBox2D(blob_img, table_roi, cv::Scalar(50), 1);
00213         CvBox2D table_roi = biggestblob.GetEllipse(); table_roi.angle *= CV_PI/180;
00214         cv::Mat table_hull(imgx, imgy, CV_8U, cv::Scalar(0));
00215         IplImage hull_img = table_hull;
00216         fillCvBox2D(hull_img, table_roi, cv::Scalar(255));
00217         //printf("Cvbox: %f, %f, %f, %f, %f\n", table_roi.center.x, table_roi.center.y, table_roi.size.width, table_roi.size.height, table_roi.angle);
00218 
00219         //cv::Mat height_morph(imgx, imgy, CV_8U, cv::Scalar(0));
00220         //cv::Mat tmp_img(imgx, imgy, CV_8U, cv::Scalar(0));
00221         //IplImage t1 = height_img_thresh; IplImage  = height_morph;
00222 
00223         cv::Mat table_edge(imgx, imgy, CV_8U);
00224         cv::Sobel(table_blob, table_edge, CV_8U, 0, 1, 1);
00225 
00226         cv::Mat above_table(imgx, imgy, CV_8U);
00227         bitwise_and(height_img_max > table_height + stddev*2, table_hull, above_table);
00228         IplImage above_table_img = above_table;
00229 
00230         CBlobResult obj_blobs = CBlobResult(&above_table_img, NULL, 0);
00231         CBlob biggest_obj_blob;
00232         double objcentx = 0, objcenty = 0;
00233         if(obj_blobs.GetNumBlobs() > 0) {
00234             obj_blobs.GetNthBlob(CBlobGetArea(), 0, biggest_obj_blob);
00235             CvBox2D obj_box = biggest_obj_blob.GetEllipse();
00236             objcenty = obj_box.center.x, objcentx = obj_box.center.y;
00237         }
00238         //double objcentx = 0, objcenty = 0;
00239 
00240         //cv::Mat table_edge = height_morph.clone();
00241         //cvMorphologyEx(&height_img, &height_morph, NULL, element, CV_MOP_CLOSE);
00242 
00243         //cvFillPoly(&ipl_hull, rpts, npts, 1, cv::Scalar(255));
00244 
00245         //cv::Mat obj_img(imgx, imgy, CV_8U, cv::Scalar(0));
00246         //std::vector<int32_t> xfeats, yfeats, zfeats;
00247         //double sumobjx = 0, sumobjy = 0, sumobja = 0;
00248         //for(uint32_t y=0;y<imgx;y++) 
00249         //    for(uint32_t x=0;x<imgx;x++) 
00250         //        if(table_hull.at<uint8_t>(x,y) == 255 && height_morph.at<uint8_t>(x,y) == 0
00251         //                && height_img_avg.at<uint8_t>(x,y) > table_height + stddev*2) {
00252         //            obj_img.at<uint8_t>(x,y) = height_img_avg.at<uint8_t>(x,y);
00253         //            sumobjx += x; sumobjy += y; sumobja ++;
00254         //            //xfeats.push_back(x); yfeats.push_back(y); 
00255         //            //zfeats.push_back(height_img.at<uint8_t>(x,y));
00256         //        }
00257         //double objcentx = sumobjx/sumobja, objcenty = sumobjy/sumobja;
00258 
00259         CvMemStorage* storage = cvCreateMemStorage(0);
00260         CvSeq* lines = 0;
00261         cv::Mat lines_img = height_img_max.clone();
00262         IplImage lines_img_ipl = lines_img;
00263         IplImage table_edge_ipl = table_edge;
00264         cvMorphologyEx(&table_edge_ipl, &table_edge_ipl, NULL, element, CV_MOP_DILATE, num_edge_dilate);
00265         lines = cvHoughLines2(&table_edge_ipl, storage, CV_HOUGH_STANDARD, 1, degree_bins*CV_PI/180, hough_thresh, 0, 0);
00266         vector<float> theta_bins, rho_bins;
00267         vector<uint32_t> count_bins;
00268         for(uint32_t i=0; i < (uint32_t) lines->total; i++) {
00269             float* line = (float*)cvGetSeqElem(lines, i);
00270             float rho = line[0];
00271             float theta = line[1];
00272             bool found_same = false;
00273             for(int32_t j=theta_bins.size()-1; j >= 0; j--) {
00274                 if(fabs(theta_bins[j]/count_bins[j] - theta) < theta_gran &&
00275                    fabs(rho_bins[j]/count_bins[j] - rho) < rho_gran) {
00276                     theta_bins[j] += theta;
00277                     rho_bins[j] += rho;
00278                     count_bins[j]++;
00279                     found_same = true;
00280                     break;
00281                 }
00282             }
00283             if(!found_same) {
00284                 theta_bins.push_back(theta);
00285                 rho_bins.push_back(rho);
00286                 count_bins.push_back(1);
00287             }
00288 
00289             double a = cos(theta), b = sin(theta);
00290             double x0 = a*rho, y0 = b*rho;
00291             CvPoint pt1, pt2;
00292             a = cos(theta); b = sin(theta);
00293             //a = cos(theta+CV_PI/2); b = sin(theta+CV_PI/2);
00294             //x0 = objcenty; y0 = objcentx;
00295             pt1.x = cvRound(x0 + 1000*(-b));
00296             pt1.y = cvRound(y0 + 1000*(a));
00297             pt2.x = cvRound(x0 - 1000*(-b));
00298             pt2.y = cvRound(y0 - 1000*(a));
00299             cvLine(&lines_img_ipl, pt1, pt2, cv::Scalar(100), 2, 8 );
00300         }
00301         //delete[] lines;
00302         for(uint32_t i=0;i<theta_bins.size();i++) {
00303             theta_bins[i] /= count_bins[i];
00304             rho_bins[i] /= count_bins[i];
00305         }
00306         vector<float> posesx, posesy, poses_theta, dists_obj;
00307         vector<uint32_t> pose_inds;
00308         for(uint32_t i=0;i<theta_bins.size();i++) {
00309             double theta = theta_bins[i];
00310             double rho = rho_bins[i];
00311             double a1 = cos(theta-CV_PI/2), b1 = sin(theta-CV_PI/2);
00312             double a2 = cos(theta-CV_PI), b2 = sin(theta-CV_PI);
00313             double vvcl = a2*b1-b2*a1, deltpx = cos(theta)*rho-objcenty, deltpy = sin(theta)*rho-objcentx;
00314             double pvcr = deltpx*b1 - deltpy*a1;
00315             double t = pvcr/vvcl;
00316             double posey = objcenty + t*a2, posex = objcentx + t*b2;
00317             printf("\naPose %d: (t: %f, %f, %f)[%f, %f](%f, %f)[%f, %f](1 %f, %f)(2 %f, %f)[theta %f, %f]\n", i, t, posex, posey, t*a2, t*b2, a1*rho, b1*rho, objcentx, objcenty, a1, b1, a2, b2, theta, rho);
00318             if(posex == posex && posey == posey &&
00319                 posex >= 0 && posey >= 0 &&
00320                 posex < imgx && posey < imgy) {
00321                 posesx.push_back(posex); posesy.push_back(posey); poses_theta.push_back(theta);
00322                 pose_inds.push_back(posesx.size()-1);
00323                 float dist = (posex-objcentx)*(posex-objcentx)+(posey-objcenty)*(posey-objcenty);
00324                 dists_obj.push_back(dist);
00325             }
00326             //lines_img.at<uint8_t>(posex, posey)
00327         }
00328         boost::function<bool(uint32_t, uint32_t)> sortind = boost::bind(&compind, _1, _2, dists_obj);
00329         sort(pose_inds.begin(), pose_inds.end(), sortind);
00330 
00331         vector<float> retposesx, retposesy, retposesr;
00332         grasp_points.poses.clear();
00333         for(uint32_t i=0;i<pose_inds.size();i++) {
00334             float posex = posesx[pose_inds[i]], posey = posesy[pose_inds[i]];
00335             float poser = -poses_theta[pose_inds[i]] + 3*CV_PI/2;
00336             bool same_found = false;
00337             for(int32_t j=((int)retposesx.size())-1;j>=0;j--) {
00338                 if(fabs(posex - retposesx[j]) < xgran && 
00339                    fabs(posey - retposesy[j]) < ygran) {
00340                     same_found = true;
00341                 } 
00342             }
00343             if(!same_found) {
00344                 retposesx.push_back(posex);
00345                 retposesy.push_back(posey);
00346                 retposesr.push_back(poser);
00347                 geometry_msgs::Pose cpose;
00348                 cpose.position.x = posex/imgx*(maxx-minx) + minx;
00349                 cpose.position.y = posey/imgy*(maxy-miny) + miny;
00350                 cpose.position.z = table_height/256.0*(maxz-minz) + minz;
00351                 btMatrix3x3 quatmat; btQuaternion quat;
00352                 quatmat.setEulerZYX(poser, 0 , 0);
00353                 quatmat.getRotation(quat);
00354                 cpose.orientation.x = quat.x(); cpose.orientation.y = quat.y();
00355                 cpose.orientation.z = quat.z(); cpose.orientation.w = quat.w();
00356                 grasp_points.poses.push_back(cpose);
00357             }
00358         }
00359         grasp_points.header.stamp = ros::Time::now();
00360         grasp_points.header.frame_id = base_frame;
00361         pose_arr_pub.publish(grasp_points);
00362         
00363 
00364         printf("\nCenter (%f, %f)\n", objcentx, objcenty);
00365         for(uint32_t i=0;i<retposesx.size();i++) {
00366         //for(uint32_t i=0;i<1;i++) {
00367             printf("\nPose %d: (%f, %f, r: %f)\n", i, retposesx[i], retposesy[i], retposesr[i]);
00368             //CvPoint centerpt; centerpt.x = objcenty; centerpt.y = objcentx;
00369             CvPoint centerpt; centerpt.x = retposesy[i]; centerpt.y = retposesx[i];
00370             cvCircle(&lines_img_ipl, centerpt, 3, cv::Scalar(200), 2);
00371         }
00372 
00373 
00374         
00375         //cv::Mat obj_feats(xfeats.size(), 1, CV_32S, cv::Scalar(0));
00376         //for(uint32_t i=0;i<xfeats.size();i++) {
00377         //    obj_feats.at<uint32_t>(i,0) = xfeats[i]; obj_feats.at<uint32_t>(i,1) = yfeats[i]; obj_feats.at<uint32_t>(i,2) = zfeats[i]; 
00378         //}
00379         //cvflann::KMeansIndexParams kmips;
00380         //kmips.branching = 32;
00381         //kmips.iterations = 11;
00382         //kmips.centers_init = cvflann::CENTERS_RANDOM;
00383         //kmips.cb_index = 0.2;
00384         //cv::Mat obj_centers;
00385         //CvMat obj_feats_mat = obj_feats;
00388         //int num_clust = cvflann::hierarchicalClustering<CV_32S,CV_32S>(obj_feats_mat, obj_centers, kmips);
00389         //printf("\nNum clust: %d \n", num_clust);
00390         
00391 
00392 
00393         cv::Mat table_edge2 = table_edge.clone();
00394         IplImage table_edge_ipl2 = table_edge2;
00395         cvMorphologyEx(&table_edge_ipl2, &table_edge_ipl2, NULL, element, CV_MOP_DILATE, 3);
00396 
00397         BOOST_FOREACH(const pcl::PointXYZRGB& pt, pc_full_frame.points) {
00398             if(pt.x != pt.x || pt.y != pt.y || pt.z != pt.z)
00399                 continue;
00400             int32_t x, y, z;
00401             x = (pt.x - minx)/(maxx-minx) * imgx;
00402             y = (pt.y - miny)/(maxy-miny) * imgy;
00403             z = (pt.z - minz)/(maxz-minz) * 256;
00404             if(x < 0 || y < 0) continue; 
00405             if(x >= imgx || y >= imgy) continue;
00406             if(z < 0 || z >= 256) continue;
00407             if(table_blob.at<uint8_t>(x,y) == 255 && 
00408                     std::fabs(table_height - z) < stddev*2) {
00409                 uint32_t red = 0xFFFF0000;
00410                 ((uint32_t*) &pt.rgb)[0] = red;
00411             }
00412             if(table_edge2.at<uint8_t>(x,y) == 255 && 
00413                     std::fabs(table_height - z) < stddev*4) {
00414                 uint32_t blue = 0xFF0000FF;
00415                 ((uint32_t*) &pt.rgb)[0] = blue;
00416             }
00417         }
00418 
00419         cv_bridge::CvImage cvb_height_img;
00420         //cvb_height_img.image = height_img_avg;
00421         //cvb_height_img.image = height_img_max;
00422         //cvb_height_img.image = height_morph;
00423         //cvb_height_img.image = obj_img;
00424         cvb_height_img.image = lines_img;
00425         //cvb_height_img.image = height_img_thresh_blob;
00426         //cvb_height_img.image = table_blob;
00427         //cvb_height_img.image = height_img_thresh;
00428         //cvb_height_img.image = above_table;
00429         //cvb_height_img.image = table_edge;
00430         cvb_height_img.header.stamp = ros::Time::now();
00431         cvb_height_img.header.frame_id = base_frame;
00432         cvb_height_img.encoding = enc::MONO8;
00433         height_pub.publish(cvb_height_img.toImageMsg());
00434         pc_full_frame.header.stamp = ros::Time::now();
00435         pc_full_frame.header.frame_id = base_frame;
00436         pc_pub.publish(pc_full_frame);
00437 
00438         if(grasp_points.poses.size() > 0)
00439             grasp_points_found = true;
00440 
00441         //delete element;
00442         pc_lock.unlock();
00443     }
00444 
00445 };
00446 
00447 using namespace hrl_table_detect;
00448 
00449 int main(int argc, char **argv)
00450 {
00451     ros::init(argc, argv, "tabletop_approach");
00452     TabletopDetector ta;
00453     ta.onInit();
00454     ros::spin();
00455     return 0;
00456 }


hrl_table_detect
Author(s): kelsey
autogenerated on Wed Nov 27 2013 12:15:26