Skip to content

Commit

Permalink
Push NAN into point array for measurement outside range limit
Browse files Browse the repository at this point in the history
According to the comment in sensor_msgs/LaserScan, values
< range_min or > range_max should be discarded.
Without this, scan matching will fail for lidars publishing
0 for invalid measurements.
  • Loading branch information
981213 committed Apr 4, 2023
1 parent fed596e commit 695125b
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions include/slam_toolbox/laser_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,18 +37,20 @@ inline std::vector<double> scanToReadings(
const bool & inverted)
{
std::vector<double> readings;
float range_min = scan.range_min;
float range_max = scan.range_max;

if (inverted) {
for (std::vector<float>::const_reverse_iterator it = scan.ranges.rbegin();
it != scan.ranges.rend(); ++it)
{
readings.push_back(*it);
readings.push_back(karto::math::InRange(*it, range_min, range_max) ? *it : NAN);
}
} else {
for (std::vector<float>::const_iterator it = scan.ranges.begin(); it != scan.ranges.end();
++it)
{
readings.push_back(*it);
readings.push_back(karto::math::InRange(*it, range_min, range_max) ? *it : NAN);
}
}

Expand Down

0 comments on commit 695125b

Please sign in to comment.