36 num_ranges_(1), xmlrpc_value_(), range_filter_(NULL), intensity_filter_(NULL)
38 ROS_WARN(
"LaserMedianFilter has been deprecated. Please use LaserArrayFilter instead.\n");
46 ROS_ERROR(
"Cannot Configure LaserMedianFilter: Didn't find \"internal_filter\" tag within LaserMedianFilter params. Filter definitions needed inside for processing range and intensity");
70 ROS_ERROR(
"LaserMedianFilter not configured");
73 boost::mutex::scoped_lock lock(
data_lock);
79 ROS_INFO(
"Laser filter clearning and reallocating due to larger scan size");
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)
bool getParam(const std::string &name, std::string &value)
bool configure(unsigned int size, std::string param_name, ros::NodeHandle node=ros::NodeHandle())