47 srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::FilterConfig> > (nh);
49 srv_->setCallback (f);
58 boost::mutex::scoped_lock lock (
mutex_);
60 double filter_min, filter_max;
61 impl_.getFilterLimits (filter_min, filter_max);
64 if (filter_min != config.filter_limit_min)
66 filter_min = config.filter_limit_min;
67 NODELET_DEBUG (
"[%s::config_callback] Setting the minimum filtering value a point will be considered from to: %f.",
getName ().c_str (), filter_min);
69 impl_.setFilterLimits (filter_min, filter_max);
72 if (filter_max != config.filter_limit_max)
74 filter_max = config.filter_limit_max;
75 NODELET_DEBUG (
"[%s::config_callback] Setting the maximum filtering value a point will be considered from to: %f.",
getName ().c_str (), filter_max);
77 impl_.setFilterLimits (filter_min, filter_max);
82 if (
impl_.getFilterFieldName () != config.filter_field_name)
85 impl_.setFilterFieldName (config.filter_field_name);
86 NODELET_DEBUG (
"[%s::config_callback] Setting the filter field name to: %s.",
getName ().c_str (), config.filter_field_name.c_str ());
90 if (
impl_.getKeepOrganized () != config.keep_organized)
92 NODELET_DEBUG (
"[%s::config_callback] Setting the filter keep_organized value to: %s.",
getName ().c_str (), config.keep_organized ?
"true" :
"false");
94 impl_.setKeepOrganized (config.keep_organized);
98 #if PCL_VERSION_COMPARE(<, 1, 10, 0) 99 if (
impl_.getFilterLimitsNegative () != config.filter_limit_negative)
101 if (
impl_.getNegative () != config.filter_limit_negative)
104 NODELET_DEBUG (
"[%s::config_callback] Setting the filter negative flag to: %s.",
getName ().c_str (), config.filter_limit_negative ?
"true" :
"false");
106 #if PCL_VERSION_COMPARE(<, 1, 10, 0) 107 impl_.setFilterLimitsNegative (config.filter_limit_negative);
109 impl_.setNegative (config.filter_limit_negative);
pcl_ros::PassThrough PassThrough
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::FilterConfig > > srv_
Pointer to a dynamic reconfigure service.
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
const std::string & getName() const
pcl::PassThrough< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
boost::mutex mutex_
Internal mutex.
PassThrough uses the base Filter class methods to pass through all data that satisfies the user given...
void config_callback(pcl_ros::FilterConfig &config, uint32_t level)
Dynamic reconfigure service callback.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define NODELET_DEBUG(...)