diff --git a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp index d435ac4dfcea8..60ebc6d1a89c6 100644 --- a/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp +++ b/perception/autoware_lidar_centerpoint/include/autoware/lidar_centerpoint/postprocess/non_maximum_suppression.hpp @@ -45,18 +45,6 @@ struct NMSParams // double distance_threshold_{}; }; -std::vector classNamesToBooleanMask(const std::vector & class_names) -{ - std::vector mask; - constexpr std::size_t num_object_classification = 8; - mask.resize(num_object_classification); - for (const auto & class_name : class_names) { - const auto semantic_type = getSemanticType(class_name); - mask.at(semantic_type) = true; - } - - return mask; -} class NonMaximumSuppression { @@ -66,14 +54,12 @@ class NonMaximumSuppression std::vector apply(const std::vector &); private: - bool isTargetLabel(const std::uint8_t); bool isTargetPairObject(const DetectedObject &, const DetectedObject &); Eigen::MatrixXd generateIoUMatrix(const std::vector &); NMSParams params_{}; - std::vector target_class_mask_{}; double search_distance_2d_sq_{}; }; diff --git a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp index 2ba04753400f0..878ce8dad7475 100644 --- a/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp +++ b/perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp @@ -22,6 +22,7 @@ namespace autoware::lidar_centerpoint { +using Label = autoware_perception_msgs::msg::ObjectClassification; void NonMaximumSuppression::setParameters(const NMSParams & params) { @@ -30,15 +31,6 @@ void NonMaximumSuppression::setParameters(const NMSParams & params) params_ = params; search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_; - target_class_mask_ = classNamesToBooleanMask(params.target_class_names_); -} - -bool NonMaximumSuppression::isTargetLabel(const uint8_t label) -{ - if (label >= target_class_mask_.size()) { - return false; - } - return target_class_mask_.at(label); } bool NonMaximumSuppression::isTargetPairObject( @@ -49,7 +41,8 @@ bool NonMaximumSuppression::isTargetPairObject( const auto label2 = autoware::object_recognition_utils::getHighestProbLabel(object2.classification); - if (!isTargetLabel(label1) || !isTargetLabel(label2)) { + // if labels are not the same, and one of them is pedestrian, do not suppress + if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) { return false; }