From 232eefb6c982319bf56e3d8dd3a668e538719002 Mon Sep 17 00:00:00 2001 From: Andreu Huguet Date: Mon, 13 Dec 2021 02:18:20 +0800 Subject: [PATCH] Crashes when fed empty pointcloud pt. II --- src/preprocess.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/preprocess.cpp b/src/preprocess.cpp index 3f0cb62..61cb94a 100644 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -267,6 +267,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg) pcl::PointCloud pl_orig; pcl::fromROSMsg(*msg, pl_orig); int plsize = pl_orig.points.size(); + if (plsize == 0) return; pl_surf.reserve(plsize); /*** These variables only works when no point timestamps given ***/