Skip to content

Commit

Permalink
setting zero range values to infinity now (so they are ignored, inste…
Browse files Browse the repository at this point in the history
…ad of creating false measurements as before)
  • Loading branch information
Max Wittal committed Feb 4, 2020
1 parent ff0dc3b commit 4de3b95
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion gmapping/src/slam_gmapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -567,7 +567,7 @@ SlamGMapping::addScan(const sensor_msgs::LaserScan& scan, GMapping::OrientedPoin
{
// Must filter out short readings, because the mapper won't
if(scan.ranges[num_ranges - i - 1] < scan.range_min)
ranges_double[i] = (double)scan.range_max;
ranges_double[i] = std::numeric_limits<double>::infinity();
else
ranges_double[i] = (double)scan.ranges[num_ranges - i - 1];
}
Expand Down

0 comments on commit 4de3b95

Please sign in to comment.