From 881fa761507c86e697ef5eb379062ca19fa025ae Mon Sep 17 00:00:00 2001 From: gaschler Date: Mon, 26 Mar 2018 14:58:21 +0200 Subject: [PATCH] Ignore empty laser scan message. (#767) FIXES=#766 --- cartographer_ros/cartographer_ros/sensor_bridge.cc | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cartographer_ros/cartographer_ros/sensor_bridge.cc b/cartographer_ros/cartographer_ros/sensor_bridge.cc index 181453b..8e3d28e 100644 --- a/cartographer_ros/cartographer_ros/sensor_bridge.cc +++ b/cartographer_ros/cartographer_ros/sensor_bridge.cc @@ -181,6 +181,9 @@ void SensorBridge::HandleLaserScan( const std::string& sensor_id, const carto::common::Time time, const std::string& frame_id, const carto::sensor::PointCloudWithIntensities& points) { + if (points.points.empty()) { + return; + } CHECK_LE(points.points.back()[3], 0); // TODO(gaschler): Use per-point time instead of subdivisions. for (int i = 0; i != num_subdivisions_per_laser_scan_; ++i) {