Skip to content

Commit 69525aa

Browse files
author
KhalilSelyan
committed
chore: add check for empty pointcloud before calling setInputCloud
Signed-off-by: KhalilSelyan <khalil@leodrive.ai>
1 parent 84db8c5 commit 69525aa

File tree

1 file changed

+6
-0
lines changed

1 file changed

+6
-0
lines changed

common/autoware_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp

+6
Original file line numberDiff line numberDiff line change
@@ -361,6 +361,12 @@ void PredictedObjectsDisplay::processPointCloud(
361361
// Create Kd-tree to search neighbor pointcloud to reduce cost.
362362
pcl::search::Search<pcl::PointXYZRGB>::Ptr kdtree =
363363
pcl::make_shared<pcl::search::KdTree<pcl::PointXYZRGB>>(false);
364+
365+
// check if the pointcloud is empty to not call setInputCloud with an empty pointcloud
366+
if (colored_cloud->empty()) {
367+
return;
368+
}
369+
364370
kdtree->setInputCloud(colored_cloud);
365371

366372
pcl::PointCloud<pcl::PointXYZRGB>::Ptr out_cloud(new pcl::PointCloud<pcl::PointXYZRGB>());

0 commit comments

Comments
 (0)