Crashes when fed empty pointcloud pt. II

main
Andreu Huguet 2021-12-13 02:18:20 +08:00 committed by Cris.Wei
parent 2a70778fd6
commit 232eefb6c9
1 changed files with 1 additions and 0 deletions

View File

@ -267,6 +267,7 @@ void Preprocess::velodyne_handler(const sensor_msgs::PointCloud2::ConstPtr &msg)
pcl::PointCloud<velodyne_ros::Point> 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 ***/