From 74c52f3922d9e5bb6ce6ffbecd5b33c4d8b5fdac Mon Sep 17 00:00:00 2001 From: ralwing <58466562+ralwing@users.noreply.github.com> Date: Fri, 17 May 2024 10:16:14 +0200 Subject: [PATCH] fix(shape_estimation): segfault when the classification was empty (#7039) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit fix(shape_estimation): fix segfault when the classification is empty Signed-off-by: Grzegorz GÅ‚owacki --- perception/shape_estimation/src/node.cpp | 22 ++++++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/perception/shape_estimation/src/node.cpp b/perception/shape_estimation/src/node.cpp index 9d7e8b4d4729d..04a96391ca165 100644 --- a/perception/shape_estimation/src/node.cpp +++ b/perception/shape_estimation/src/node.cpp @@ -61,6 +61,22 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option published_time_publisher_ = std::make_unique(this); } +static autoware_auto_perception_msgs::msg::ObjectClassification::_label_type get_label( + const autoware_auto_perception_msgs::msg::DetectedObject::_classification_type & classification) +{ + if (classification.empty()) { + return Label::UNKNOWN; + } + return classification.front().label; +} + +static bool label_is_vehicle( + const autoware_auto_perception_msgs::msg::ObjectClassification::_label_type & label) +{ + return Label::CAR == label || Label::TRUCK == label || Label::BUS == label || + Label::TRAILER == label; +} + void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstSharedPtr input_msg) { stop_watch_ptr_->toc("processing_time", true); @@ -76,11 +92,9 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared // Estimate shape for each object and pack msg for (const auto & feature_object : input_msg->feature_objects) { const auto & object = feature_object.object; - const auto & label = object.classification.front().label; + const auto label = get_label(object.classification); + const auto is_vehicle = label_is_vehicle(label); const auto & feature = feature_object.feature; - const bool is_vehicle = Label::CAR == label || Label::TRUCK == label || Label::BUS == label || - Label::TRAILER == label; - // convert ros to pcl pcl::PointCloud::Ptr cluster(new pcl::PointCloud); pcl::fromROSMsg(feature.cluster, *cluster);