52 dynamic_reconfigure::Server<IntensityFilterConfig>::CallbackType
f;
53 f = [
this](
auto& config,
auto level){
reconfigureCB(config, level); };
61 getParam(
"filter_override_intensity",
config_.filter_override_intensity);
68 filtered_scan = input_scan;
71 for (
unsigned int i=0; i < input_scan.ranges.size() && i < input_scan.intensities.size(); i++)
73 float& range = filtered_scan.ranges[i];
74 float& intensity = filtered_scan.intensities[i];
78 bool filter = intensity <=
config_.lower_threshold || intensity >=
config_.upper_threshold;
86 if (
config_.filter_override_range)
89 range = std::numeric_limits<float>::quiet_NaN();
91 if (
config_.filter_override_intensity)
98 if (
config_.filter_override_intensity)