Skip to content

Commit

Permalink
ignore measurements outside lidar range
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 Oct 25, 2022
1 parent 67c1127 commit 52acc42
Showing 1 changed file with 6 additions and 12 deletions.
18 changes: 6 additions & 12 deletions lib/karto_sdk/include/karto_sdk/Karto.h
Original file line number Diff line number Diff line change
Expand Up @@ -5658,27 +5658,21 @@ 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)) {
kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;

Vector2<kt_double> point;
point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));

m_UnfilteredPointReadings.push_back(point);
if (rangeReading < pLaserRangeFinder->GetMinimumRange() ||
rangeReading > pLaserRangeFinder->GetMaximumRange())
continue;
}

kt_double angle = scanPose.GetHeading() + minimumAngle + beamNum * angularResolution;

Vector2<kt_double> point;
point.SetX(scanPose.GetX() + (rangeReading * cos(angle)));
point.SetY(scanPose.GetY() + (rangeReading * sin(angle)));

m_PointReadings.push_back(point);
if (rangeReading < rangeThreshold) {
m_PointReadings.push_back(point);
rangePointsSum += point;
}
m_UnfilteredPointReadings.push_back(point);

rangePointsSum += point;
}

// compute barycenter
Expand Down

0 comments on commit 52acc42

Please sign in to comment.