50   NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 
   51                  " - max_queue_size    : %d",
 
   63   sub_input_filter_.subscribe (*pnh_, 
"input", max_queue_size_);
 
   64   sub_target_filter_.subscribe (*pnh_, 
"target", max_queue_size_);
 
   67   srv_ = boost::make_shared <dynamic_reconfigure::Server<SegmentDifferencesConfig> > (*pnh_);
 
   69   srv_->setCallback (
f);
 
   71   if (approximate_sync_)
 
   73     sync_input_target_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud> > > (max_queue_size_);
 
   74     sync_input_target_a_->connectInput (sub_input_filter_, sub_target_filter_);
 
   79     sync_input_target_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud> > > (max_queue_size_);
 
   80     sync_input_target_e_->connectInput (sub_input_filter_, sub_target_filter_);
 
   89   sub_input_filter_.unsubscribe ();
 
   90   sub_target_filter_.unsubscribe ();
 
   97   if (impl_.getDistanceThreshold () != config.distance_threshold)
 
   99     impl_.setDistanceThreshold (config.distance_threshold);
 
  100     NODELET_DEBUG (
"[%s::config_callback] Setting new distance threshold to: %f.", 
getName ().c_str (), config.distance_threshold);
 
  110   if (pub_output_.getNumSubscribers () <= 0)
 
  113   if (!isValid (cloud) || !isValid (cloud_target, 
"target")) 
 
  117     output.header = cloud->header;
 
  118     pub_output_.publish (
ros_ptr(output.makeShared ()));
 
  123                  "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 
  124                  "                                 - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
 
  126                  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 (),
 
  127                  cloud_target->width * cloud_target->height, 
pcl::getFieldsList (*cloud_target).c_str (), 
fromPCL(cloud_target->header).stamp.toSec (), cloud_target->header.frame_id.c_str (), pnh_->resolveName (
"target").c_str ());
 
  129   impl_.setInputCloud (
pcl_ptr(cloud));
 
  130   impl_.setTargetCloud (
pcl_ptr(cloud_target));
 
  133   impl_.segment (output);
 
  135   pub_output_.publish (
ros_ptr(output.makeShared ()));
 
  136   NODELET_DEBUG (
"[%s::segmentAndPublish] Published PointCloud2 with %zu points and stamp %f on topic %s", 
getName ().c_str (),
 
  137                      output.points.size (), 
fromPCL(output.header).stamp.toSec (), pnh_->resolveName (
"output").c_str ());