mirror of
https://github.com/hku-mars/FAST_LIO.git
synced 2023-04-06 16:28:55 +08:00
Crashes when fed empty pointcloud pt. II
This commit is contained in:
@@ -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 ***/
|
||||
|
||||
Reference in New Issue
Block a user