Commit 98d4b0b 1 parent bd48d6d commit 98d4b0b Copy full SHA for 98d4b0b
File tree 1 file changed +7
-1
lines changed
control/autoware_autonomous_emergency_braking/src
1 file changed +7
-1
lines changed Original file line number Diff line number Diff line change @@ -631,6 +631,9 @@ std::optional<Path> AEB::generateEgoPath(const Trajectory & predicted_traj)
631
631
std::vector<Polygon2d> AEB::generatePathFootprint (
632
632
const Path & path, const double extra_width_margin)
633
633
{
634
+ if (path.empty ()) {
635
+ return {};
636
+ }
634
637
std::vector<Polygon2d> polygons;
635
638
for (size_t i = 0 ; i < path.size () - 1 ; ++i) {
636
639
polygons.push_back (
@@ -643,7 +646,7 @@ void AEB::createObjectDataUsingPredictedObjects(
643
646
const Path & ego_path, const std::vector<Polygon2d> & ego_polys,
644
647
std::vector<ObjectData> & object_data_vector)
645
648
{
646
- if (predicted_objects_ptr_->objects .empty ()) return ;
649
+ if (predicted_objects_ptr_->objects .empty () || ego_polys. empty () ) return ;
647
650
648
651
const double current_ego_speed = current_velocity_ptr_->longitudinal_velocity ;
649
652
const auto & objects = predicted_objects_ptr_->objects ;
@@ -814,6 +817,9 @@ void AEB::createObjectDataUsingPointCloudClusters(
814
817
void AEB::cropPointCloudWithEgoFootprintPath (
815
818
const std::vector<Polygon2d> & ego_polys, pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_objects)
816
819
{
820
+ if (ego_polys.empty ()) {
821
+ return ;
822
+ }
817
823
PointCloud::Ptr full_points_ptr (new PointCloud);
818
824
pcl::fromROSMsg (*obstacle_ros_pointcloud_ptr_, *full_points_ptr);
819
825
// Create a Point cloud with the points of the ego footprint
You can’t perform that action at this time.
0 commit comments