47 srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::RadiusOutlierRemovalConfig> > (nh);
49 srv_->setCallback (f);
58 boost::mutex::scoped_lock lock (
mutex_);
60 if (
impl_.getMinNeighborsInRadius () != config.min_neighbors)
62 impl_.setMinNeighborsInRadius (config.min_neighbors);
63 NODELET_DEBUG (
"[%s::config_callback] Setting the number of neighbors in radius: %d.",
getName ().c_str (), config.min_neighbors);
66 if (
impl_.getRadiusSearch () != config.radius_search)
68 impl_.setRadiusSearch (config.radius_search);
69 NODELET_DEBUG (
"[%s::config_callback] Setting the radius to search neighbors: %f.",
getName ().c_str (), config.radius_search);
pcl::RadiusOutlierRemoval< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
PLUGINLIB_EXPORT_CLASS(RadiusOutlierRemoval, nodelet::Nodelet)
const std::string & getName() const
virtual bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
pcl_ros::RadiusOutlierRemoval RadiusOutlierRemoval
RadiusOutlierRemoval is a simple filter that removes outliers if the number of neighbors in a certain...
boost::mutex mutex_
Internal mutex.
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::RadiusOutlierRemovalConfig > > srv_
Pointer to a dynamic reconfigure service.
#define NODELET_DEBUG(...)
void config_callback(pcl_ros::RadiusOutlierRemovalConfig &config, uint32_t level)
Dynamic reconfigure callback.