Skip to content

Commit

Permalink
using NaN instead of range_max+1 to remove scans
Browse files Browse the repository at this point in the history
  • Loading branch information
bely2803 committed Aug 21, 2024
1 parent 913a342 commit 0f33136
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion include/laser_filters/angular_bounds_filter_in_place.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ namespace laser_filters
//loop through the scan and remove ranges at angles between lower_angle_ and upper_angle_
for(unsigned int i = 0; i < input_scan.ranges.size(); ++i){
if((current_angle > lower_angle_) && (current_angle < upper_angle_)){
filtered_scan.ranges[i] = input_scan.range_max + 1.0;
filtered_scan.ranges[i] = std::numeric_limits<float>::quiet_NaN();
if(i < filtered_scan.intensities.size()){
filtered_scan.intensities[i] = 0.0;
}
Expand Down

0 comments on commit 0f33136

Please sign in to comment.