36 num_ranges_(1), range_filter_(NULL), intensity_filter_(NULL)
47 if (!found_range_config && !found_intensity_config)
49 ROS_ERROR(
"Cannot Configure LaserArrayFilter: Didn't find \"range_filter\" or \"intensity _filter\" tag within LaserArrayFilter params. Filter definitions needed inside for processing range and intensity");
59 if (found_range_config)
66 if (found_intensity_config)
89 ROS_ERROR(
"LaserArrayFilter not configured");
93 boost::mutex::scoped_lock lock(
data_lock);
100 ROS_INFO(
"LaserArrayFilter cleaning and reallocating due to larger scan size");
filters::MultiChannelFilterChain< float > * intensity_filter_
LaserScanMaskFilter removes points on directions defined in a mask from a laser scan.
bool update(const std::vector< T > &data_in, std::vector< T > &data_out)
LaserArrayFilter()
Constructor.
XmlRpc::XmlRpcValue range_config_
How many data point are in each row.
bool update(const sensor_msgs::LaserScan &scan_in, sensor_msgs::LaserScan &scan_out)
Update the filter and get the response.
unsigned int num_ranges_
How many scans to average over.
XmlRpc::XmlRpcValue intensity_config_
bool getParam(const std::string &name, std::string &value) const
filters::MultiChannelFilterChain< float > * range_filter_
bool configure(unsigned int size, std::string param_name, ros::NodeHandle node=ros::NodeHandle())