47 srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::StatisticalOutlierRemovalConfig> > (nh);
49 srv_->setCallback (f);
58 boost::mutex::scoped_lock lock (
mutex_);
60 if (
impl_.getMeanK () != config.mean_k)
62 impl_.setMeanK (config.mean_k);
63 NODELET_DEBUG (
"[%s::config_callback] Setting the number of points (k) to use for mean distance estimation to: %d.",
getName ().c_str (), config.mean_k);
66 if (
impl_.getStddevMulThresh () != config.stddev)
68 impl_.setStddevMulThresh (config.stddev);
69 NODELET_DEBUG (
"[%s::config_callback] Setting the standard deviation multiplier threshold to: %f.",
getName ().c_str (), config.stddev);
72 if (
impl_.getNegative () != config.negative)
74 impl_.setNegative (config.negative);
75 NODELET_DEBUG (
"[%s::config_callback] Returning only inliers: %s.",
getName ().c_str (), config.negative ?
"false" :
"true");
pcl_ros::StatisticalOutlierRemoval StatisticalOutlierRemoval
pcl::StatisticalOutlierRemoval< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
void config_callback(pcl_ros::StatisticalOutlierRemovalConfig &config, uint32_t level)
Dynamic reconfigure callback.
const std::string & getName() const
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
boost::mutex mutex_
Internal mutex.
StatisticalOutlierRemoval uses point neighborhood statistics to filter outlier data. For more information check:
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::StatisticalOutlierRemovalConfig > > srv_
Pointer to a dynamic reconfigure service.
PLUGINLIB_EXPORT_CLASS(StatisticalOutlierRemoval, nodelet::Nodelet)
#define NODELET_DEBUG(...)