55   srv_ = boost::make_shared <dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > (*pnh_);
 
   57   srv_->setCallback (
f);
 
   69   sub_hull_filter_.subscribe (*pnh_, 
"planar_hull", max_queue_size_);
 
   70   sub_input_filter_.subscribe (*pnh_, 
"input", max_queue_size_);
 
   73   if (approximate_sync_)
 
   74     sync_input_hull_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
 
   76     sync_input_hull_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
 
   80     sub_indices_filter_.subscribe (*pnh_, 
"indices", max_queue_size_);
 
   81     if (approximate_sync_)
 
   82       sync_input_hull_indices_a_->connectInput (sub_input_filter_, sub_hull_filter_, sub_indices_filter_);
 
   84       sync_input_hull_indices_e_->connectInput (sub_input_filter_, sub_hull_filter_, sub_indices_filter_);
 
   90     if (approximate_sync_)
 
   91       sync_input_hull_indices_a_->connectInput (sub_input_filter_, sub_hull_filter_, nf_);
 
   93       sync_input_hull_indices_e_->connectInput (sub_input_filter_, sub_hull_filter_, nf_);
 
   96   if (approximate_sync_)
 
  106   sub_hull_filter_.unsubscribe ();
 
  107   sub_input_filter_.unsubscribe ();
 
  110     sub_indices_filter_.unsubscribe ();
 
  117   double height_min, height_max;
 
  118   impl_.getHeightLimits (height_min, height_max);
 
  119   if (height_min != config.height_min)
 
  121     height_min = config.height_min;
 
  122     NODELET_DEBUG (
"[%s::config_callback] Setting new minimum height to the planar model to: %f.", 
getName ().c_str (), height_min);
 
  123     impl_.setHeightLimits (height_min, height_max);
 
  125   if (height_max != config.height_max)
 
  127     height_max = config.height_max;
 
  128     NODELET_DEBUG (
"[%s::config_callback] Setting new maximum height to the planar model to: %f.", 
getName ().c_str (), height_max);
 
  129     impl_.setHeightLimits (height_min, height_max);
 
  141   if (pub_output_.getNumSubscribers () <= 0)
 
  145   pcl_msgs::PointIndices inliers;
 
  146   inliers.header = 
fromPCL(cloud->header);
 
  149   if (!isValid (cloud) || !isValid (hull, 
"planar_hull"))
 
  152     pub_output_.publish (inliers);
 
  156   if (indices && !isValid (indices))
 
  159     pub_output_.publish (inliers);
 
  166                    "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  167                    "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  168                    "                                 - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
 
  170                    cloud->width * cloud->height, 
pcl::getFieldsList (*cloud).c_str (), 
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
 
  171                    hull->width * hull->height, 
pcl::getFieldsList (*hull).c_str (), 
fromPCL(hull->header).stamp.toSec (), hull->header.frame_id.c_str (), pnh_->resolveName (
"planar_hull").c_str (),
 
  172                    indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
 
  175                    "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  176                    "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
 
  178                    cloud->width * cloud->height, 
pcl::getFieldsList (*cloud).c_str (), 
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
 
  179                    hull->width * hull->height, 
pcl::getFieldsList (*hull).c_str (), 
fromPCL(hull->header).stamp.toSec (), hull->header.frame_id.c_str (), pnh_->resolveName (
"planar_hull").c_str ());
 
  182   if (cloud->header.frame_id != hull->header.frame_id)
 
  184     NODELET_DEBUG (
"[%s::input_hull_callback] Planar hull has a different TF frame (%s) than the input point cloud (%s)! Using TF to transform.", 
getName ().c_str (), hull->header.frame_id.c_str (), cloud->header.frame_id.c_str ());
 
  189       pub_output_.publish (inliers);
 
  192     impl_.setInputPlanarHull (
pcl_ptr(planar_hull.makeShared ()));
 
  195     impl_.setInputPlanarHull (
pcl_ptr(hull));
 
  198   if (indices && !indices->header.frame_id.empty ())
 
  199     indices_ptr.reset (
new std::vector<int> (indices->indices));
 
  201   impl_.setInputCloud (
pcl_ptr(cloud));
 
  202   impl_.setIndices (indices_ptr);
 
  205   if (!cloud->points.empty ()) {
 
  206     pcl::PointIndices pcl_inliers;
 
  208     impl_.segment (pcl_inliers);
 
  212   inliers.header = 
fromPCL(cloud->header);
 
  213   pub_output_.publish (inliers);
 
  214   NODELET_DEBUG (
"[%s::input_hull_callback] Publishing %zu indices.", 
getName ().c_str (), inliers.indices.size ());