39 #include <pcl/PointIndices.h> 
   56   double cluster_tolerance;
 
   57   if (!
pnh_->getParam (
"cluster_tolerance", cluster_tolerance))
 
   59     NODELET_ERROR (
"[%s::onInit] Need a 'cluster_tolerance' parameter to be set before continuing!", 
getName ().c_str ()); 
 
   63   if (!
pnh_->getParam (
"spatial_locator", spatial_locator))
 
   65     NODELET_ERROR (
"[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!", 
getName ().c_str ());
 
   78   srv_ = boost::make_shared <dynamic_reconfigure::Server<EuclideanClusterExtractionConfig> > (*pnh_);
 
   80   srv_->setCallback (
f);
 
   82   NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 
   83                  " - max_queue_size    : %d\n" 
   84                  " - use_indices       : %s\n" 
   85                  " - cluster_tolerance : %f\n",
 
   91   impl_.setClusterTolerance (cluster_tolerance);
 
  104     sub_input_filter_.subscribe (*pnh_, 
"input", max_queue_size_);
 
  105     sub_indices_filter_.subscribe (*pnh_, 
"indices", max_queue_size_);
 
  107     if (approximate_sync_)
 
  109       sync_input_indices_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<PointCloud, PointIndices> > > (max_queue_size_);
 
  110       sync_input_indices_a_->connectInput (sub_input_filter_, sub_indices_filter_);
 
  115       sync_input_indices_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<PointCloud, PointIndices> > > (max_queue_size_);
 
  116       sync_input_indices_e_->connectInput (sub_input_filter_, sub_indices_filter_);
 
  131     sub_input_filter_.unsubscribe ();
 
  132     sub_indices_filter_.unsubscribe ();
 
  135     sub_input_.shutdown ();
 
  142   if (impl_.getClusterTolerance () != config.cluster_tolerance)
 
  144     impl_.setClusterTolerance (config.cluster_tolerance);
 
  145     NODELET_DEBUG (
"[%s::config_callback] Setting new clustering tolerance to: %f.", 
getName ().c_str (), config.cluster_tolerance);
 
  147   if (impl_.getMinClusterSize () != config.cluster_min_size)
 
  149     impl_.setMinClusterSize (config.cluster_min_size);
 
  150     NODELET_DEBUG (
"[%s::config_callback] Setting the minimum cluster size to: %d.", 
getName ().c_str (), config.cluster_min_size);
 
  152   if (impl_.getMaxClusterSize () != config.cluster_max_size)
 
  154     impl_.setMaxClusterSize (config.cluster_max_size);
 
  155     NODELET_DEBUG (
"[%s::config_callback] Setting the maximum cluster size to: %d.", 
getName ().c_str (), config.cluster_max_size);
 
  157   if (max_clusters_ != config.max_clusters)
 
  159     max_clusters_ = config.max_clusters;
 
  160     NODELET_DEBUG (
"[%s::config_callback] Setting the maximum number of clusters to extract to: %d.", 
getName ().c_str (), config.max_clusters);
 
  170   if (pub_output_.getNumSubscribers () <= 0)
 
  174   if (!isValid (cloud))
 
  180   if (indices && !isValid (indices))
 
  188     std_msgs::Header cloud_header = 
fromPCL(cloud->header);
 
  189     std_msgs::Header indices_header = indices->header;
 
  191                    "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  192                    "                                 - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
 
  194                    cloud->width * cloud->height, 
pcl::getFieldsList (*cloud).c_str (), cloud_header.stamp.toSec (), cloud_header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
 
  195                    indices->indices.size (), indices_header.stamp.toSec (), indices_header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
 
  197     NODELET_DEBUG (
"[%s::input_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", 
getName ().c_str (), cloud->width * cloud->height, 
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str ());
 
  203     indices_ptr.reset (
new std::vector<int> (indices->indices));
 
  205   impl_.setInputCloud (
pcl_ptr(cloud));
 
  206   impl_.setIndices (indices_ptr);
 
  208   std::vector<pcl::PointIndices> clusters;
 
  209   impl_.extract (clusters);
 
  211   if (publish_indices_)
 
  213     for (
size_t i = 0; i < clusters.size (); ++i)
 
  215       if ((
int)i >= max_clusters_)
 
  218       pcl_msgs::PointIndices ros_pi;
 
  221       pub_output_.publish (ros_pi);
 
  224     NODELET_DEBUG (
"[segmentAndPublish] Published %zu clusters (PointIndices) on topic %s", clusters.size (), pnh_->resolveName (
"output").c_str ());
 
  228     for (
size_t i = 0; i < clusters.size (); ++i)
 
  230       if ((
int)i >= max_clusters_)
 
  233       copyPointCloud (*cloud, clusters[i].indices, output);
 
  242       pub_output_.publish (
ros_ptr(output.makeShared ()));
 
  243       NODELET_DEBUG (
"[segmentAndPublish] Published cluster %zu (with %zu values and stamp %f) on topic %s",
 
  244                      i, clusters[i].indices.size (), 
header.stamp.toSec (), pnh_->resolveName (
"output").c_str ());