@@ -242,7 +242,6 @@ void AEB::onPointCloud(const PointCloud2::ConstSharedPtr input_msg)
242
242
filter.filter (*no_height_filtered_pointcloud_ptr);
243
243
244
244
obstacle_ros_pointcloud_ptr_ = std::make_shared<PointCloud2>();
245
- cropped_ros_pointcloud_ptr_ = std::make_shared<PointCloud2>();
246
245
247
246
pcl::toROSMsg (*no_height_filtered_pointcloud_ptr, *obstacle_ros_pointcloud_ptr_);
248
247
obstacle_ros_pointcloud_ptr_->header = input_msg->header ;
@@ -386,8 +385,8 @@ bool AEB::checkCollision(MarkerArray & debug_markers)
386
385
}
387
386
}
388
387
389
- if (cropped_ros_pointcloud_ptr_ ) {
390
- pub_obstacle_pointcloud_->publish (*cropped_ros_pointcloud_ptr_ );
388
+ if (obstacle_ros_pointcloud_ptr_ ) {
389
+ pub_obstacle_pointcloud_->publish (*obstacle_ros_pointcloud_ptr_ );
391
390
}
392
391
393
392
return has_collision_ego || has_collision_predicted;
@@ -577,7 +576,7 @@ void AEB::cropPointCloudWithEgoFootprintPath(const std::vector<Polygon2d> & ego_
577
576
578
577
// Store the results
579
578
if (!objects->empty ()) {
580
- pcl::toROSMsg (*objects, *cropped_ros_pointcloud_ptr_ );
579
+ pcl::toROSMsg (*objects, *obstacle_ros_pointcloud_ptr_ );
581
580
}
582
581
}
583
582
@@ -586,12 +585,12 @@ void AEB::createObjectDataUsingPointCloudClusters(
586
585
std::vector<ObjectData> & objects)
587
586
{
588
587
// check if the predicted path has valid number of points
589
- if (ego_path.size () < 2 || ego_polys.empty () || cropped_ros_pointcloud_ptr_ ->data .empty ()) {
588
+ if (ego_path.size () < 2 || ego_polys.empty () || obstacle_ros_pointcloud_ptr_ ->data .empty ()) {
590
589
return ;
591
590
}
592
591
593
592
PointCloud::Ptr obstacle_points_ptr (new PointCloud);
594
- pcl::fromROSMsg (*cropped_ros_pointcloud_ptr_ , *obstacle_points_ptr);
593
+ pcl::fromROSMsg (*obstacle_ros_pointcloud_ptr_ , *obstacle_points_ptr);
595
594
if (obstacle_points_ptr->empty ()) return ;
596
595
597
596
std::vector<pcl::PointIndices> cluster_indices;
0 commit comments