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
00027
00028
00029
00030
00031 #include <door_handle_detector/handle_detector.h>
00032 #include <pr2_doors_common/door_functions.h>
00033
00034
00035 using namespace std;
00036 using namespace ros;
00037 using namespace mapping_msgs;
00038 using namespace door_msgs;
00039 using namespace door_handle_detector;
00040 using namespace pr2_doors_common;
00041
00043 HandleDetector::HandleDetector ()
00044 : node_tilde_("~")
00045 {
00046
00047 {
00048 node_tilde_.param ("parameter_frame", parameter_frame_, string ("base_footprint"));
00049 node_tilde_.param ("fixed_frame", fixed_frame_, string ("odom_combined"));
00050
00051 node_tilde_.param ("handle_distance_door_max_threshold", handle_distance_door_max_threshold_, 0.3);
00052
00053 node_tilde_.param ("handle_min_height", handle_min_height_, 0.5);
00054 node_tilde_.param ("handle_max_height", handle_max_height_, 1.22);
00055 ROS_DEBUG ("Using the following thresholds for handle detection [min height / max height]: %f / %f.", handle_min_height_, handle_max_height_);
00056 }
00057
00058 z_axis_.x = 0; z_axis_.y = 0; z_axis_.z = 1;
00059 k_search_ = 10;
00060
00061 distance_from_door_margin_ = 0.02 * 0.02;
00062 min_plane_pts_ = 1000;
00063 sac_distance_threshold_ = 0.015;
00064
00065
00066 euclidean_cluster_angle_tolerance_ = angles::from_degrees (15.0);
00067 euclidean_cluster_min_pts_ = 4;
00068 euclidean_cluster_distance_tolerance_ = 0.04;
00069
00070 node_tilde_.param ("input_cloud_topic", input_cloud_topic_, string ("/full_cloud"));
00071 detect_srv_ = node_.advertiseService ("handle_detector", &HandleDetector::detectHandleSrv, this);
00072 detect_cloud_srv_ = node_.advertiseService ("handle_detector_cloud",
00073 &HandleDetector::detectHandleCloudSrv, this);
00074 vis_marker_pub_ = node_tilde_.advertise<visualization_msgs::Marker> ("visualization_marker", 100);
00075 handle_pol_pub_ = node_tilde_.advertise<PolygonalMap> ("handle_polygon", 1);
00076 handle_reg_pub_ = node_tilde_.advertise<sensor_msgs::PointCloud> ("handle_regions", 1);
00077 door_outliers_pub_ = node_tilde_.advertise<sensor_msgs::PointCloud> ("door_outliers", 1);
00078
00079 global_marker_id_ = 1;
00080 }
00081
00082
00083
00084
00086 bool HandleDetector::detectHandle (const door_msgs::Door& door, sensor_msgs::PointCloud pointcloud,
00087 std::vector<door_msgs::Door>& result) const
00088 {
00089 ROS_INFO ("HandleDetector: Start detecting handle in a point cloud of size %i", (int)pointcloud.points.size ());
00090
00091 Time ts = Time::now();
00092 Duration duration;
00093 Duration timeout = Duration().fromSec(2.0);
00094
00095
00096 if (!tf_.waitForTransform(parameter_frame_, pointcloud.header.frame_id, pointcloud.header.stamp, timeout)){
00097 ROS_ERROR ("HandleDetector: Could not transform point cloud from frame '%s' to frame '%s' at time %f.",
00098 pointcloud.header.frame_id.c_str (), parameter_frame_.c_str (), pointcloud.header.stamp.toSec());
00099 return false;
00100 }
00101 tf_.transformPointCloud (parameter_frame_, pointcloud, pointcloud);
00102 ROS_INFO("HandleDetector: Pointcloud transformed to '%s'", parameter_frame_.c_str());
00103
00104
00105
00106 Door door_tr;
00107 if (!transformTo(tf_, parameter_frame_, door, door_tr, fixed_frame_)){
00108 ROS_ERROR ("HandleDetector: Could not transform door message from frame '%s' to frame '%s'.",
00109 door.header.frame_id.c_str (), parameter_frame_.c_str ());
00110 return false;
00111 }
00112 ROS_INFO("HandleDetector: Door message transformed to '%s'", parameter_frame_.c_str());
00113
00114
00115 vector<int> tmp_indices;
00116 geometry_msgs::Point32 tmp_p;
00117
00118
00119 geometry_msgs::PointStamped viewpoint_cloud;
00120 getCloudViewPoint (parameter_frame_, viewpoint_cloud, &tf_);
00121
00122
00123 geometry_msgs::Point32 pt;
00124 pt.x = (door_tr.door_p2.x + door_tr.door_p1.x) / 2.0;
00125 pt.y = (door_tr.door_p2.y + door_tr.door_p1.y) / 2.0;
00126 pt.z = (door_tr.door_p2.z + door_tr.door_p1.z) / 2.0 + door_tr.height / 2.0;
00127 vector<double> coeff (4);
00128 KDL::Vector door_normal = getDoorNormal(door_tr);
00129 geometry_msgs::Point32 door_normal_pnt;
00130 door_normal_pnt.x = door_normal(0);
00131 door_normal_pnt.y = door_normal(1);
00132 door_normal_pnt.z = door_normal(2);
00133 coeff[0] = door_normal(0);
00134 coeff[1] = door_normal(1);
00135 coeff[2] = door_normal(2);
00136 coeff[3] = - cloud_geometry::dot (door_normal_pnt, pt);
00137
00138
00139
00140 int nr_p = 0;
00141 vector<int> indices_in_bounds (pointcloud.points.size ());
00142 double dist_p1p2 = cloud_geometry::distances::pointToPointXYDistanceSqr (door_tr.door_p1, door_tr.door_p2);
00143 for (int i = pointcloud.points.size () - 1; i >= 0; --i)
00144 {
00145 if (pointcloud.points[i].z > handle_min_height_ && pointcloud.points[i].z < handle_max_height_ &&
00146 cloud_geometry::distances::pointToPlaneDistance (pointcloud.points[i], coeff) < handle_distance_door_max_threshold_)
00147 {
00148 double dist_p1 = cloud_geometry::distances::pointToPointXYDistanceSqr (pointcloud.points[i], door_tr.door_p1);
00149 double dist_p2 = cloud_geometry::distances::pointToPointXYDistanceSqr (pointcloud.points[i], door_tr.door_p2);
00150 if (dist_p1 < dist_p1p2 && dist_p1 > distance_from_door_margin_ && dist_p2 < dist_p1p2 && dist_p2 > distance_from_door_margin_)
00151 {
00152 indices_in_bounds[nr_p] = i;
00153 nr_p++;
00154 }
00155 }
00156 }
00157 indices_in_bounds.resize (nr_p);
00158 sort (indices_in_bounds.begin (), indices_in_bounds.end ());
00159
00160 vector<int> inliers, outliers;
00161
00162 if (!fitSACPlane (pointcloud, indices_in_bounds, inliers, coeff, viewpoint_cloud, sac_distance_threshold_, min_plane_pts_) || inliers.size () == 0)
00163 {
00164 ROS_ERROR ("Could not find a door planar model in the input data (%d points)! Exiting...", nr_p);
00165 return (false);
00166 }
00167
00168 geometry_msgs::Polygon polygon, polygon_tr;
00169 cloud_geometry::areas::convexHull2D (pointcloud, inliers, coeff, polygon);
00170
00171
00172 Eigen::Matrix4d transformation;
00173 cloud_geometry::transforms::getPlaneToPlaneTransformation (coeff, z_axis_, 0, 0, 0, transformation);
00174 cloud_geometry::transforms::transformPoints (polygon.points, polygon_tr.points, transformation);
00175
00176
00177 getDoorOutliers (indices_in_bounds, inliers, coeff, polygon, polygon_tr, transformation, outliers, pointcloud);
00178
00179
00180 vector<int> handle_indices;
00181 getHandleCandidates (indices_in_bounds, coeff, polygon, polygon_tr, transformation,
00182 handle_indices, pointcloud, viewpoint_cloud);
00183
00184
00185 estimatePointNormals (pointcloud, handle_indices, k_search_, viewpoint_cloud);
00186
00187
00188
00189 int curvature_idx = cloud_geometry::getChannelIndex (pointcloud, "curvatures");
00190 int intensity_idx = cloud_geometry::getChannelIndex (pointcloud, "intensities");
00191 if (intensity_idx == -1 || curvature_idx == -1)
00192 {
00193 ROS_ERROR ("Intensity (and/or curvature) channels not present in the point cloud! Exiting...");
00194 return (false);
00195 }
00196 selectBestDualDistributionStatistics (pointcloud, handle_indices, curvature_idx, intensity_idx, tmp_indices);
00197
00198 if (tmp_indices.size () == 0)
00199 {
00200 ROS_WARN ("No handle indices found !");
00201 return (false);
00202 }
00203 handle_indices = tmp_indices;
00204 ROS_DEBUG ("Number of candidate points for clustering in the dual intensity-curvature space: %d.", (int)handle_indices.size ());
00205
00206
00207 ROS_DEBUG (" -- handle indices before refinement: %d.", (int)handle_indices.size ());
00208 geometry_msgs::Point32 door_axis = cloud_geometry::cross (coeff, z_axis_);
00209 refineHandleCandidatesWithDoorOutliers (handle_indices, outliers, polygon, coeff, door_axis, door_tr, pointcloud);
00210 ROS_DEBUG (" -- handle indices after refinement: %d.", (int)handle_indices.size ());
00211
00212 duration = ros::Time::now () - ts;
00213
00214
00215 geometry_msgs::Point32 min_h, max_h, handle_center;
00216 cloud_geometry::statistics::getLargestDiagonalPoints (pointcloud, handle_indices, min_h, max_h);
00217 handle_center.x = (min_h.x + max_h.x) / 2.0;
00218 handle_center.y = (min_h.y + max_h.y) / 2.0;
00219 handle_center.z = (min_h.z + max_h.z) / 2.0;
00220
00221
00222 cout << "min_h = " << min_h.x << " " << min_h.y << " "<< min_h.z << endl;
00223 cout << "max_h = " << max_h.x << " " << max_h.y << " "<< max_h.z << endl;
00224 cout << "handle_center = " << handle_center.x << " " << handle_center.y << " "<< handle_center.z << endl;
00225
00226
00227 double distance_to_plane = coeff[0] * handle_center.x + coeff[1] * handle_center.y + coeff[2] * handle_center.z + coeff[3] * 1;
00228 cout << "distance to plane = " << distance_to_plane << endl;
00229
00230
00231
00232
00233
00234 sensor_msgs::PointCloud cloud_regions;
00235 cloud_regions.channels.resize (1); cloud_regions.channels[0].name = "intensities";
00236
00237 cloud_regions.header = pointcloud.header;
00238 cloud_regions.points.resize (0);
00239 cloud_regions.channels[0].values.resize (0);
00240
00241 bool show_cluster = true;
00242 if (show_cluster)
00243 {
00244 for (unsigned int i = 0; i < handle_indices.size (); i++)
00245 {
00246 cloud_regions.points.push_back ( pointcloud.points[handle_indices[i]] );
00247 cloud_regions.channels[0].values.push_back ( pointcloud.channels[curvature_idx].values[handle_indices[i]] );
00248 }
00249 }
00250 else
00251 {
00252 cloud_regions.points.push_back (handle_center);
00253 cloud_regions.channels[0].values.push_back (9999);
00254 }
00255
00256
00257
00258
00259
00260
00261 handle_reg_pub_.publish (cloud_regions);
00262
00263
00264 handle_indices = outliers;
00265 cloud_regions.points.resize (0);
00266 cloud_regions.channels[0].values.resize (0);
00267 for (unsigned int i = 0; i < handle_indices.size (); i++)
00268 {
00269 cloud_regions.points.push_back ( pointcloud.points[handle_indices[i]] );
00270 cloud_regions.channels[0].values.push_back ( pointcloud.channels[curvature_idx].values[handle_indices[i]] );
00271 }
00272 door_outliers_pub_.publish (cloud_regions);
00273
00274 PolygonalMap pmap;
00275 pmap.header = pointcloud.header;
00276 pmap.polygons.resize (1);
00277 pmap.polygons[0] = polygon;
00278 handle_pol_pub_.publish (pmap);
00279
00280
00281 result.resize(1);
00282 result[0] = door_tr;
00283 result[0].handle = handle_center;
00284 if (!transformTo(tf_, fixed_frame_, result[0], result[0], fixed_frame_)){
00285 ROS_ERROR ("HandleDetector: Could not transform door message from frame '%s' to frame '%s'.",
00286 result[0].header.frame_id.c_str (), fixed_frame_.c_str ());
00287 return false;
00288 }
00289 ROS_INFO("HandleDetector: Door message transformed to '%s'", fixed_frame_.c_str());
00290
00291 ROS_INFO ("Handle detected. Result in frame %s \n Handle = [%f, %f, %f]. \n Total time: %f.",
00292 result[0].header.frame_id.c_str (),
00293 result[0].handle.x, result[0].handle.y, result[0].handle.z,
00294 duration.toSec ());
00295 return (true);
00296 }
00297
00298
00299
00300
00301
00302
00304 void HandleDetector::refineHandleCandidatesWithDoorOutliers (vector<int> &handle_indices, vector<int> &outliers,
00305 const geometry_msgs::Polygon &polygon,
00306 const vector<double> &coeff, const geometry_msgs::Point32 &door_axis,
00307 const Door& door_prior,
00308 sensor_msgs::PointCloud& pointcloud) const
00309 {
00310
00311 vector<vector<int> > clusters;
00312 findClusters (pointcloud, handle_indices, euclidean_cluster_distance_tolerance_, clusters, -1, -1, -1, 0, euclidean_cluster_min_pts_);
00313 ROS_DEBUG ("Number of clusters for the handle candidate points: %d.", (int)clusters.size ());
00314
00315
00316 handle_indices.resize (0);
00317 for (unsigned int i = 0; i < clusters.size (); i++)
00318 {
00319 int old_size = handle_indices.size ();
00320 handle_indices.resize (old_size + clusters[i].size ());
00321 for (unsigned int j = 0; j < clusters[i].size (); j++)
00322 handle_indices.at (old_size + j) = clusters[i][j];
00323 }
00324
00325
00326
00327 vector<vector<int> > line_inliers (clusters.size ());
00328 vector<vector<int> > inliers (clusters.size ());
00329 for (int i = 0; i < (int)clusters.size (); i++)
00330 {
00331
00332 #if 0
00333
00334
00335
00336 #endif
00337
00338 growCurrentCluster (pointcloud, outliers, clusters[i], inliers[i], 2 * euclidean_cluster_distance_tolerance_);
00339
00340 sensor_msgs::PointCloud tmp_cloud;
00341 cloud_geometry::projections::pointsToPlane (pointcloud, inliers[i], tmp_cloud, coeff);
00342
00343 fitSACOrientedLine (tmp_cloud, sac_distance_threshold_ * 2, door_axis, euclidean_cluster_angle_tolerance_, line_inliers[i]);
00344 for (unsigned int j = 0; j < line_inliers[i].size (); j++)
00345 line_inliers[i][j] = inliers[i][line_inliers[i][j]];
00346 }
00347
00348 double best_score = -FLT_MAX;
00349 int best_i = -1;
00350
00351 for (unsigned int i = 0; i < line_inliers.size (); i++)
00352 {
00353 if (line_inliers[i].size () == 0)
00354 continue;
00355
00356 geometry_msgs::Point32 min_h, max_h, mid;
00357 cloud_geometry::statistics::getLargestXYPoints (pointcloud, line_inliers[i], min_h, max_h);
00358 mid.x = (min_h.x + max_h.x)/2.0; mid.y = (min_h.y + max_h.y)/2.0;
00359
00360
00361 double length = sqrt ( (min_h.x - max_h.x) * (min_h.x - max_h.x) + (min_h.y - max_h.y) * (min_h.y - max_h.y) );
00362 double fit = ((double)(line_inliers[i].size())) / ((double)(inliers[i].size()));
00363 double score = fit - 3.0 * fabs (length - 0.15);
00364 ROS_INFO (" Handle line cluster %d with %d inliers, has fit %g and length %g --> %g.", i, (int)line_inliers[i].size (), fit, length, score);
00365
00366
00367 double dist_to_side = 0;
00368 if (door_prior.hinge == Door::HINGE_P1)
00369 dist_to_side = cloud_geometry::distances::pointToPointXYDistance(door_prior.door_p2, mid);
00370 else if (door_prior.hinge == Door::HINGE_P2)
00371 dist_to_side = cloud_geometry::distances::pointToPointXYDistance(door_prior.door_p1, mid);
00372 else
00373 ROS_ERROR("HandleDetector: Door hinge side not defined");
00374 if (dist_to_side > 0.3)
00375 score = 0;
00376 else
00377 score /= fmin(0.0001, dist_to_side);
00378 ROS_INFO (" Handle is found at %f [m] from the door side", dist_to_side);
00379
00380 if (score > best_score)
00381 {
00382 best_score = score;
00383 best_i = i;
00384 }
00385 }
00386
00387 if (best_i == -1)
00388 {
00389 ROS_ERROR ("All clusters rejected!");
00390
00391 for (unsigned int i = 0; i < inliers.size (); i++)
00392 {
00393 if (inliers[i].size () == 0)
00394 continue;
00395 int old_size = handle_indices.size ();
00396 handle_indices.resize (old_size + inliers[i].size ());
00397 for (unsigned int j = 0; j < inliers[i].size (); j++)
00398 handle_indices.at (old_size + j) = inliers[i][j];
00399 }
00400 }
00401 else
00402 {
00403 ROS_INFO ("Selecting cluster %d.", best_i);
00404
00405
00406 handle_indices.resize (clusters[best_i].size ());
00407 for (unsigned int j = 0; j < clusters[best_i].size (); j++)
00408 handle_indices[j] = clusters[best_i][j];
00409
00410
00411 int old_size = handle_indices.size ();
00412 handle_indices.resize (old_size + line_inliers[best_i].size ());
00413 for (unsigned int j = 0; j < line_inliers[best_i].size (); j++)
00414 handle_indices[old_size + j] = line_inliers[best_i][j];
00415 }
00416 sort (handle_indices.begin (), handle_indices.end ());
00417 handle_indices.erase (unique (handle_indices.begin (), handle_indices.end ()), handle_indices.end ());
00418
00419 }
00420
00421
00422
00424 void HandleDetector::getHandleCandidates (const vector<int> &indices, const vector<double> &coeff,
00425 const geometry_msgs::Polygon &polygon, const geometry_msgs::Polygon &polygon_tr,
00426 Eigen::Matrix4d transformation, vector<int> &handle_indices,
00427 sensor_msgs::PointCloud& pointcloud, geometry_msgs::PointStamped& viewpoint_cloud) const
00428 {
00429
00430 handle_indices.resize (indices.size ());
00431
00432
00433 vector<double> viewpoint_pt_line (6);
00434 viewpoint_pt_line[0] = viewpoint_cloud.point.x;
00435 viewpoint_pt_line[1] = viewpoint_cloud.point.y;
00436 viewpoint_pt_line[2] = viewpoint_cloud.point.z;
00437
00438
00439 geometry_msgs::Point32 tmp_p;
00440 int nr_p = 0;
00441 geometry_msgs::Point32 pt;
00442 for (unsigned int i = 0; i < indices.size (); i++)
00443 {
00444
00445 double distance_to_plane;
00446 cloud_geometry::projections::pointToPlane (pointcloud.points.at (indices.at (i)), pt, coeff, distance_to_plane);
00447 if (distance_to_plane < 0)
00448 continue;
00449 cloud_geometry::transforms::transformPoint (pt, tmp_p, transformation);
00450 if (!cloud_geometry::areas::isPointIn2DPolygon (tmp_p, polygon_tr))
00451 continue;
00452
00453
00454 if (cloud_geometry::distances::pointToPolygonDistanceSqr (tmp_p, polygon_tr) < distance_from_door_margin_)
00455 continue;
00456
00457
00458 viewpoint_pt_line[3] = pointcloud.points.at (indices.at (i)).x - viewpoint_cloud.point.x;
00459 viewpoint_pt_line[4] = pointcloud.points.at (indices.at (i)).y - viewpoint_cloud.point.y;
00460 viewpoint_pt_line[5] = pointcloud.points.at (indices.at (i)).z - viewpoint_cloud.point.z;
00461
00462 double n_norm = sqrt (viewpoint_pt_line[3] * viewpoint_pt_line[3] +
00463 viewpoint_pt_line[4] * viewpoint_pt_line[4] +
00464 viewpoint_pt_line[5] * viewpoint_pt_line[5]);
00465 viewpoint_pt_line[3] /= n_norm;
00466 viewpoint_pt_line[4] /= n_norm;
00467 viewpoint_pt_line[5] /= n_norm;
00468
00469
00470 geometry_msgs::Point32 viewpoint_door_intersection;
00471 if (!cloud_geometry::intersections::lineWithPlaneIntersection (coeff, viewpoint_pt_line, viewpoint_door_intersection))
00472 {
00473 ROS_WARN ("Line and plane are parallel (no intersections found between the line and the plane).");
00474 continue;
00475 }
00476
00477 cloud_geometry::projections::pointToPlane (viewpoint_door_intersection, pt, coeff);
00478 cloud_geometry::transforms::transformPoint (pt, tmp_p, transformation);
00479 if (!cloud_geometry::areas::isPointIn2DPolygon (tmp_p, polygon_tr))
00480 continue;
00481
00482
00483 handle_indices[nr_p++] = indices.at (i);
00484 }
00485 handle_indices.resize (nr_p);
00486 }
00487
00488
00489
00491 void HandleDetector::getDoorOutliers (const vector<int> &indices, const vector<int> &inliers,
00492 const vector<double> &coeff, const geometry_msgs::Polygon &polygon,
00493 const geometry_msgs::Polygon &polygon_tr, Eigen::Matrix4d transformation,
00494 vector<int> &outliers, sensor_msgs::PointCloud& pointcloud) const
00495 {
00496 vector<int> tmp_indices;
00497 geometry_msgs::Point32 tmp_p;
00498 set_difference (indices.begin (), indices.end (), inliers.begin (), inliers.end (),
00499 inserter (outliers, outliers.begin ()));
00500
00501 #if 0
00502
00503 vector<double> viewpoint_pt_line (6);
00504 viewpoint_pt_line[0] = viewpoint_cloud.point.x;
00505 viewpoint_pt_line[1] = viewpoint_cloud.point.y;
00506 viewpoint_pt_line[2] = viewpoint_cloud.point.z;
00507 #endif
00508 geometry_msgs::Point32 pt;
00509 tmp_indices.resize (outliers.size ());
00510 int nr_p = 0;
00511 for (unsigned int i = 0; i < outliers.size (); i++)
00512 {
00513
00514 double distance_to_plane;
00515 cloud_geometry::projections::pointToPlane (pointcloud.points.at (outliers[i]), pt, coeff, distance_to_plane);
00516 if (distance_to_plane < 0)
00517 continue;
00518 cloud_geometry::transforms::transformPoint (pt, tmp_p, transformation);
00519 if (!cloud_geometry::areas::isPointIn2DPolygon (tmp_p, polygon_tr))
00520 continue;
00521
00522
00523 if (cloud_geometry::distances::pointToPolygonDistanceSqr (tmp_p, polygon_tr) < distance_from_door_margin_)
00524 continue;
00525
00526 tmp_indices[nr_p] = outliers[i];
00527 nr_p++;
00528 }
00529 tmp_indices.resize (nr_p);
00530 outliers = tmp_indices;
00531
00532
00533 vector<vector<int> > clusters;
00534 if (outliers.size () > 0)
00535 {
00536 findClusters (pointcloud, outliers, euclidean_cluster_distance_tolerance_, clusters, -1, -1, -1, 0, euclidean_cluster_min_pts_);
00537 outliers.resize (0);
00538 for (unsigned int i = 0; i < clusters.size (); i++)
00539 {
00540 int old_size = outliers.size ();
00541 outliers.resize (old_size + clusters[i].size ());
00542 for (unsigned int j = 0; j < clusters[i].size (); j++)
00543 outliers[old_size + j] = clusters[i][j];
00544 }
00545 }
00546 else
00547 ROS_DEBUG ("[getDoorOutliers] No door plane outliers found.");
00548 }
00549
00550
00551
00552
00554 bool HandleDetector::detectHandleSrv (door_handle_detector::DoorsDetector::Request &req,
00555 door_handle_detector::DoorsDetector::Response &resp)
00556 {
00557
00558 num_clouds_received_ = 0;
00559
00560 ros::Subscriber cloud_sub = node_.subscribe(input_cloud_topic_, 1, &HandleDetector::cloud_cb, this);
00561 ros::Duration tictoc = ros::Duration ().fromSec (0.1);
00562 while ((int)num_clouds_received_ < 1)
00563 tictoc.sleep ();
00564 cloud_sub.shutdown();
00565
00566 return detectHandle(req.door, pointcloud_, resp.doors);
00567 }
00568
00569
00571 bool HandleDetector::detectHandleCloudSrv (door_handle_detector::DoorsDetectorCloud::Request &req,
00572 door_handle_detector::DoorsDetectorCloud::Response &resp)
00573 {
00574 return detectHandle(req.door, req.cloud, resp.doors);
00575 }
00576
00577
00578
00580 void HandleDetector::cloud_cb (const sensor_msgs::PointCloudConstPtr& cloud)
00581 {
00582 pointcloud_ = *cloud;
00583 ROS_INFO ("Received %d data points in frame %s with %d channels (%s).", (int)pointcloud_.points.size (), pointcloud_.header.frame_id.c_str (),
00584 (int)pointcloud_.channels.size (), cloud_geometry::getAvailableChannels (pointcloud_).c_str ());
00585 num_clouds_received_++;
00586 }
00587
00588
00589
00590
00591 int
00592 main (int argc, char** argv)
00593 {
00594 ros::init (argc, argv, "handle_detector_node");
00595
00596 HandleDetector p;
00597
00598 ros::MultiThreadedSpinner s(2);
00599 s.spin();
00600
00601 return (0);
00602 }
00603
00604