47   srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig> > (nh);
 
   49   srv_->setCallback (
f);
 
   60   boost::mutex::scoped_lock lock (mutex_);
 
   61   pcl::PCLPointCloud2::Ptr pcl_input(
new pcl::PCLPointCloud2);
 
   63   impl_.setInputCloud (pcl_input);
 
   64   impl_.setIndices (indices);
 
   65   pcl::PCLPointCloud2 pcl_output;
 
   66   impl_.filter (pcl_output);
 
   74   boost::mutex::scoped_lock lock (mutex_);
 
   76   Eigen::Vector3f leaf_size = impl_.getLeafSize ();
 
   77   Eigen::Vector3f config_leaf_size;
 
   79   config_leaf_size[0] = (config.leaf_size_x >= 0.0 ? config.leaf_size_x : config.leaf_size);
 
   80   config_leaf_size[1] = (config.leaf_size_y >= 0.0 ? config.leaf_size_y : config.leaf_size);
 
   81   config_leaf_size[2] = (config.leaf_size_z >= 0.0 ? config.leaf_size_z : config.leaf_size);
 
   83   if (leaf_size != config_leaf_size) {
 
   84     NODELET_DEBUG(
"[config_callback] Setting the downsampling leaf size to: (%f, %f, %f).",
 
   85       config_leaf_size[0], config_leaf_size[1], config_leaf_size[2]);
 
   86     impl_.setLeafSize(config_leaf_size[0], config_leaf_size[1], config_leaf_size[2]);
 
   88   unsigned int minPointsPerVoxel = impl_.getMinimumPointsNumberPerVoxel ();
 
   89   if (minPointsPerVoxel != ((
unsigned int) config.min_points_per_voxel))
 
   91     minPointsPerVoxel = config.min_points_per_voxel;
 
   92     NODELET_DEBUG (
"[config_callback] Setting the minimum points per voxel to: %u.", minPointsPerVoxel);
 
   93     impl_.setMinimumPointsNumberPerVoxel (minPointsPerVoxel);
 
   96   double filter_min, filter_max;
 
   97   impl_.getFilterLimits (filter_min, filter_max);
 
   98   if (filter_min != config.filter_limit_min)
 
  100     filter_min = config.filter_limit_min;
 
  101     NODELET_DEBUG (
"[config_callback] Setting the minimum filtering value a point will be considered from to: %f.", filter_min);
 
  103   if (filter_max != config.filter_limit_max)
 
  105     filter_max = config.filter_limit_max;
 
  106     NODELET_DEBUG (
"[config_callback] Setting the maximum filtering value a point will be considered from to: %f.", filter_max);
 
  108   impl_.setFilterLimits (filter_min, filter_max);
 
  110   if (impl_.getFilterLimitsNegative () != config.filter_limit_negative)
 
  112     impl_.setFilterLimitsNegative (config.filter_limit_negative);
 
  113     NODELET_DEBUG (
"[%s::config_callback] Setting the filter negative flag to: %s.", 
getName ().c_str (), config.filter_limit_negative ? 
"true" : 
"false");
 
  116   if (impl_.getFilterFieldName () != config.filter_field_name)
 
  118     impl_.setFilterFieldName (config.filter_field_name);
 
  119     NODELET_DEBUG (
"[config_callback] Setting the filter field name to: %s.", config.filter_field_name.c_str ());
 
  123   if (tf_input_frame_ != config.input_frame)
 
  125     tf_input_frame_ = config.input_frame;
 
  126     NODELET_DEBUG (
"[config_callback] Setting the input TF frame to: %s.", tf_input_frame_.c_str ());
 
  128   if (tf_output_frame_ != config.output_frame)
 
  130     tf_output_frame_ = config.output_frame;
 
  131     NODELET_DEBUG (
"[config_callback] Setting the output TF frame to: %s.", tf_output_frame_.c_str ());