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 3, 2023
1 parent fed596e commit 6ecd6ac
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion lib/karto_sdk/include/karto_sdk/Karto.h
Original file line number Diff line number Diff line change
Expand Up @@ -5659,7 +5659,11 @@ class LocalizedRangeScan : public LaserRangeScan
kt_int32u beamNum = 0;
for (kt_int32u i = 0; i < pLaserRangeFinder->GetNumberOfRangeReadings(); i++, beamNum++) {
kt_double rangeReading = GetRangeReadings()[i];
if (!math::InRange(rangeReading, pLaserRangeFinder->GetMinimumRange(), rangeThreshold)) {
if (!math::InRange(rangeReading,
pLaserRangeFinder->GetMinimumRange(), pLaserRangeFinder->GetMaximumRange())) {
m_UnfilteredPointReadings.push_back(Vector2<kt_double>(NAN, NAN));
continue;
} else if (rangeReading > rangeThreshold) {
kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;

Vector2<kt_double> point;
Expand Down

0 comments on commit 6ecd6ac

Please sign in to comment.