diff --git a/cfg/IntensityFilter.cfg b/cfg/IntensityFilter.cfg index b0811b07..190e3359 100755 --- a/cfg/IntensityFilter.cfg +++ b/cfg/IntensityFilter.cfg @@ -41,9 +41,9 @@ PACKAGE = "laser_filters" gen = ParameterGenerator() gen.add("lower_threshold", double_t, 0, - "Intensity values lower than this value will be filtered", 8000.0, 0, 100000.0) + "Intensity values lower equal than this value will be filtered. Use negative values for no lower bound filtering.", 8000.0, -1.0, 100000.0) gen.add("upper_threshold", double_t, 0, - "Intensity values greater than this value will be filtered", 100000.0, 0, 100000.0) + "Intensity values greater equal than this value will be filtered", 100000.0, 0, 100000.0) gen.add("invert", bool_t, 0, "A Boolean to invert the filter", False) gen.add("filter_override_range", bool_t, 0, diff --git a/src/intensity_filter.cpp b/src/intensity_filter.cpp index b35f1fe7..9ccb0ced 100644 --- a/src/intensity_filter.cpp +++ b/src/intensity_filter.cpp @@ -73,8 +73,8 @@ bool LaserScanIntensityFilter::update(const sensor_msgs::LaserScan& input_scan, float& range = filtered_scan.ranges[i]; float& intensity = filtered_scan.intensities[i]; - // Is this reading below our lower threshold? - // Is this reading above our upper threshold? + // Is this reading below or equal to our lower threshold? + // Is this reading above or equal to our upper threshold? bool filter = intensity <= config_.lower_threshold || intensity >= config_.upper_threshold; if (config_.invert) {