Skip to content

Commit 2901c06

Browse files
technolojinsaka1-s
authored andcommitted
feat(lidar_centerpoint): optimize non-maximum suppression algorithm (#1689)
Refactor the `NonMaximumSuppression` class in the `lidar_centerpoint` module to optimize the non-maximum suppression algorithm. This includes removing the `isTargetLabel` function and modifying the `isTargetPairObject` function to handle pedestrian labels differently. Additionally, the `search_distance_2d_sq_` variable is now initialized in the `setParameters` function.
1 parent d013ee4 commit 2901c06

File tree

2 files changed

+8
-14
lines changed

2 files changed

+8
-14
lines changed

perception/lidar_centerpoint/include/lidar_centerpoint/postprocess/non_maximum_suppression.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -66,14 +66,14 @@ class NonMaximumSuppression
6666
std::vector<DetectedObject> apply(const std::vector<DetectedObject> &);
6767

6868
private:
69-
bool isTargetLabel(const std::uint8_t);
70-
7169
bool isTargetPairObject(const DetectedObject &, const DetectedObject &);
7270

7371
Eigen::MatrixXd generateIoUMatrix(const std::vector<DetectedObject> &);
7472

7573
NMSParams params_{};
7674
std::vector<bool> target_class_mask_{};
75+
76+
double search_distance_2d_sq_{};
7777
};
7878

7979
} // namespace centerpoint

perception/lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp

+6-12
Original file line numberDiff line numberDiff line change
@@ -19,38 +19,32 @@
1919
#include "object_recognition_utils/object_recognition_utils.hpp"
2020
namespace centerpoint
2121
{
22+
using Label = autoware_perception_msgs::msg::ObjectClassification;
2223

2324
void NonMaximumSuppression::setParameters(const NMSParams & params)
2425
{
2526
assert(params.search_distance_2d_ >= 0.0);
2627
assert(params.iou_threshold_ >= 0.0 && params.iou_threshold_ <= 1.0);
2728

2829
params_ = params;
30+
search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_;
2931
target_class_mask_ = classNamesToBooleanMask(params.target_class_names_);
3032
}
3133

32-
bool NonMaximumSuppression::isTargetLabel(const uint8_t label)
33-
{
34-
if (label >= target_class_mask_.size()) {
35-
return false;
36-
}
37-
return target_class_mask_.at(label);
38-
}
39-
4034
bool NonMaximumSuppression::isTargetPairObject(
4135
const DetectedObject & object1, const DetectedObject & object2)
4236
{
4337
const auto label1 = object_recognition_utils::getHighestProbLabel(object1.classification);
4438
const auto label2 = object_recognition_utils::getHighestProbLabel(object2.classification);
4539

46-
if (isTargetLabel(label1) && isTargetLabel(label2)) {
47-
return true;
40+
// if labels are not the same, and one of them is pedestrian, do not suppress
41+
if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) {
42+
return false;
4843
}
4944

50-
const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_;
5145
const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d(
5246
object_recognition_utils::getPose(object1), object_recognition_utils::getPose(object2));
53-
return sqr_dist_2d <= search_sqr_dist_2d;
47+
return sqr_dist_2d <= search_distance_2d_sq_;
5448
}
5549

5650
Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix(

0 commit comments

Comments
 (0)