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");