Skip to content

Commit 98d4b0b

Browse files
fix(autonomous_emergency_braking): add sanity checks (autowarefoundation#8998) (#1573)
feat(autonomous_emergency_braking): add sanity chackes (autowarefoundation#8998) add sanity chackes Signed-off-by: Daniel Sanchez <danielsanchezaran@gmail.com>
1 parent bd48d6d commit 98d4b0b

File tree

1 file changed

+7
-1
lines changed
  • control/autoware_autonomous_emergency_braking/src

1 file changed

+7
-1
lines changed

control/autoware_autonomous_emergency_braking/src/node.cpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -631,6 +631,9 @@ std::optional<Path> AEB::generateEgoPath(const Trajectory & predicted_traj)
631631
std::vector<Polygon2d> AEB::generatePathFootprint(
632632
const Path & path, const double extra_width_margin)
633633
{
634+
if (path.empty()) {
635+
return {};
636+
}
634637
std::vector<Polygon2d> polygons;
635638
for (size_t i = 0; i < path.size() - 1; ++i) {
636639
polygons.push_back(
@@ -643,7 +646,7 @@ void AEB::createObjectDataUsingPredictedObjects(
643646
const Path & ego_path, const std::vector<Polygon2d> & ego_polys,
644647
std::vector<ObjectData> & object_data_vector)
645648
{
646-
if (predicted_objects_ptr_->objects.empty()) return;
649+
if (predicted_objects_ptr_->objects.empty() || ego_polys.empty()) return;
647650

648651
const double current_ego_speed = current_velocity_ptr_->longitudinal_velocity;
649652
const auto & objects = predicted_objects_ptr_->objects;
@@ -814,6 +817,9 @@ void AEB::createObjectDataUsingPointCloudClusters(
814817
void AEB::cropPointCloudWithEgoFootprintPath(
815818
const std::vector<Polygon2d> & ego_polys, pcl::PointCloud<pcl::PointXYZ>::Ptr filtered_objects)
816819
{
820+
if (ego_polys.empty()) {
821+
return;
822+
}
817823
PointCloud::Ptr full_points_ptr(new PointCloud);
818824
pcl::fromROSMsg(*obstacle_ros_pointcloud_ptr_, *full_points_ptr);
819825
// Create a Point cloud with the points of the ego footprint

0 commit comments

Comments
 (0)