Skip to content

Commit 01944ef

Browse files
fix(lidar_centerpoint): non-maximum suppression target decision logic (#9595)
* refactor(lidar_centerpoint): optimize non-maximum suppression search distance calculation Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * feat(lidar_centerpoint): do not suppress if one side of the object is pedestrian Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * style(pre-commit): autofix * refactor(lidar_centerpoint): remove unused variables Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: remove unused variables Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> fix: implement non-maximum suppression logic to the transfusion Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> refactor: remove unused parameter iou_nms_target_class_names Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> Revert "fix: implement non-maximum suppression logic to the transfusion" This reverts commit b8017fc. fix: revert transfusion modification --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 386d2af commit 01944ef

File tree

13 files changed

+17
-79
lines changed

13 files changed

+17
-79
lines changed

perception/autoware_image_projection_based_fusion/config/pointpainting.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,6 @@
99
post_process_params:
1010
# post-process params
1111
circle_nms_dist_threshold: 0.3
12-
iou_nms_target_class_names: ["CAR"]
1312
iou_nms_search_distance_2d: 10.0
1413
iou_nms_threshold: 0.1
1514
score_threshold: 0.35

perception/autoware_image_projection_based_fusion/docs/pointpainting-fusion.md

-1
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,6 @@ The lidar points are projected onto the output of an image-only 2d object detect
4343
| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` |
4444
| `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored |
4545
| `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. |
46-
| `post_process_params.iou_nms_target_class_names` | list[string] | ["CAR"] | An array of class names to be target in NMS. |
4746
| `post_process_params.iou_nms_search_distance_2d` | double | 10.0 | A maximum distance value to search the nearest objects. |
4847
| `post_process_params.iou_nms_threshold` | double | 0.1 | A threshold value of NMS using IoU score. |
4948
| `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. |

perception/autoware_image_projection_based_fusion/schema/pointpainting.schema.json

-6
Original file line numberDiff line numberDiff line change
@@ -46,12 +46,6 @@
4646
"minimum": 0.0,
4747
"maximum": 1.0
4848
},
49-
"iou_nms_target_class_names": {
50-
"type": "array",
51-
"description": "An array of class names to be target in NMS.",
52-
"default": ["CAR"],
53-
"uniqueItems": true
54-
},
5549
"iou_nms_search_distance_2d": {
5650
"type": "number",
5751
"description": "A maximum distance value to search the nearest objects.",

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

-3
Original file line numberDiff line numberDiff line change
@@ -171,9 +171,6 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt
171171

172172
{
173173
autoware::lidar_centerpoint::NMSParams p;
174-
p.nms_type_ = autoware::lidar_centerpoint::NMS_TYPE::IoU_BEV;
175-
p.target_class_names_ = this->declare_parameter<std::vector<std::string>>(
176-
"post_process_params.iou_nms_target_class_names");
177174
p.search_distance_2d_ =
178175
this->declare_parameter<double>("post_process_params.iou_nms_search_distance_2d");
179176
p.iou_threshold_ = this->declare_parameter<double>("post_process_params.iou_nms_threshold");

perception/autoware_lidar_centerpoint/README.md

-2
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,6 @@ Note that these parameters are associated with ONNX file, predefined during the
5656
| `trt_precision` | string | `fp16` | TensorRT inference precision: `fp32` or `fp16` |
5757
| `post_process_params.score_threshold` | double | `0.4` | detected objects with score less than threshold are ignored |
5858
| `post_process_params.yaw_norm_thresholds` | list[double] | [0.3, 0.3, 0.3, 0.3, 0.0] | An array of distance threshold values of norm of yaw [rad]. |
59-
| `post_process_params.iou_nms_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression |
6059
| `post_process_params.iou_nms_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. |
6160
| `post_process_params.iou_nms_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression |
6261
| `post_process_params.has_twist` | boolean | false | Indicates whether the model outputs twist value. |
@@ -267,7 +266,6 @@ point_cloud_range, point_feature_size, voxel_size, etc. according to the trainin
267266
encoder_in_feature_size: 9
268267
# post-process params
269268
circle_nms_dist_threshold: 0.5
270-
iou_nms_target_class_names: ["CAR"]
271269
iou_nms_search_distance_2d: 10.0
272270
iou_nms_threshold: 0.1
273271
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]

perception/autoware_lidar_centerpoint/config/centerpoint.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@
1010
post_process_params:
1111
# post-process params
1212
circle_nms_dist_threshold: 0.5
13-
iou_nms_target_class_names: ["CAR"]
1413
iou_nms_search_distance_2d: 10.0
1514
iou_nms_threshold: 0.1
1615
score_threshold: 0.35

perception/autoware_lidar_centerpoint/config/centerpoint_sigma.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,6 @@
1111
post_process_params:
1212
# post-process params
1313
circle_nms_dist_threshold: 0.5
14-
iou_nms_target_class_names: ["CAR"]
1514
iou_nms_search_distance_2d: 10.0
1615
iou_nms_threshold: 0.1
1716
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0]

perception/autoware_lidar_centerpoint/config/centerpoint_tiny.param.yaml

-1
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@
1010
post_process_params:
1111
# post-process params
1212
circle_nms_dist_threshold: 0.5
13-
iou_nms_target_class_names: ["CAR"]
1413
iou_nms_search_distance_2d: 10.0
1514
iou_nms_threshold: 0.1
1615
score_threshold: 0.35

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

+2-27
Original file line numberDiff line numberDiff line change
@@ -28,36 +28,12 @@ namespace autoware::lidar_centerpoint
2828
{
2929
using autoware_perception_msgs::msg::DetectedObject;
3030

31-
// TODO(yukke42): now only support IoU_BEV
32-
enum class NMS_TYPE {
33-
IoU_BEV
34-
// IoU_3D
35-
// Distance_2D
36-
// Distance_3D
37-
};
38-
3931
struct NMSParams
4032
{
41-
NMS_TYPE nms_type_{};
42-
std::vector<std::string> target_class_names_{};
4333
double search_distance_2d_{};
4434
double iou_threshold_{};
45-
// double distance_threshold_{};
4635
};
4736

48-
std::vector<bool> classNamesToBooleanMask(const std::vector<std::string> & class_names)
49-
{
50-
std::vector<bool> mask;
51-
constexpr std::size_t num_object_classification = 8;
52-
mask.resize(num_object_classification);
53-
for (const auto & class_name : class_names) {
54-
const auto semantic_type = getSemanticType(class_name);
55-
mask.at(semantic_type) = true;
56-
}
57-
58-
return mask;
59-
}
60-
6137
class NonMaximumSuppression
6238
{
6339
public:
@@ -66,14 +42,13 @@ class NonMaximumSuppression
6642
std::vector<DetectedObject> apply(const std::vector<DetectedObject> &);
6743

6844
private:
69-
bool isTargetLabel(const std::uint8_t);
70-
7145
bool isTargetPairObject(const DetectedObject &, const DetectedObject &);
7246

7347
Eigen::MatrixXd generateIoUMatrix(const std::vector<DetectedObject> &);
7448

7549
NMSParams params_{};
76-
std::vector<bool> target_class_mask_{};
50+
51+
double search_distance_2d_sq_{};
7752
};
7853

7954
} // namespace autoware::lidar_centerpoint

perception/autoware_lidar_centerpoint/lib/postprocess/non_maximum_suppression.cpp

+15-25
Original file line numberDiff line numberDiff line change
@@ -22,22 +22,15 @@
2222

2323
namespace autoware::lidar_centerpoint
2424
{
25+
using Label = autoware_perception_msgs::msg::ObjectClassification;
2526

2627
void NonMaximumSuppression::setParameters(const NMSParams & params)
2728
{
2829
assert(params.search_distance_2d_ >= 0.0);
2930
assert(params.iou_threshold_ >= 0.0 && params.iou_threshold_ <= 1.0);
3031

3132
params_ = params;
32-
target_class_mask_ = classNamesToBooleanMask(params.target_class_names_);
33-
}
34-
35-
bool NonMaximumSuppression::isTargetLabel(const uint8_t label)
36-
{
37-
if (label >= target_class_mask_.size()) {
38-
return false;
39-
}
40-
return target_class_mask_.at(label);
33+
search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_;
4134
}
4235

4336
bool NonMaximumSuppression::isTargetPairObject(
@@ -48,15 +41,15 @@ bool NonMaximumSuppression::isTargetPairObject(
4841
const auto label2 =
4942
autoware::object_recognition_utils::getHighestProbLabel(object2.classification);
5043

51-
if (isTargetLabel(label1) && isTargetLabel(label2)) {
52-
return true;
44+
// if labels are not the same, and one of them is pedestrian, do not suppress
45+
if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) {
46+
return false;
5347
}
5448

55-
const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_;
5649
const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d(
5750
autoware::object_recognition_utils::getPose(object1),
5851
autoware::object_recognition_utils::getPose(object2));
59-
return sqr_dist_2d <= search_sqr_dist_2d;
52+
return sqr_dist_2d <= search_distance_2d_sq_;
6053
}
6154

6255
Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix(
@@ -73,14 +66,12 @@ Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix(
7366
continue;
7467
}
7568

76-
if (params_.nms_type_ == NMS_TYPE::IoU_BEV) {
77-
const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj);
78-
triangular_matrix(target_i, source_i) = iou;
79-
// NOTE: If the target object has any objects with iou > iou_threshold, it
80-
// will be suppressed regardless of later results.
81-
if (iou > params_.iou_threshold_) {
82-
break;
83-
}
69+
const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj);
70+
triangular_matrix(target_i, source_i) = iou;
71+
// NOTE: If the target object has any objects with iou > iou_threshold, it
72+
// will be suppressed regardless of later results.
73+
if (iou > params_.iou_threshold_) {
74+
break;
8475
}
8576
}
8677
}
@@ -97,10 +88,9 @@ std::vector<DetectedObject> NonMaximumSuppression::apply(
9788
output_objects.reserve(input_objects.size());
9889
for (std::size_t i = 0; i < input_objects.size(); ++i) {
9990
const auto value = iou_matrix.row(i).maxCoeff();
100-
if (params_.nms_type_ == NMS_TYPE::IoU_BEV) {
101-
if (value <= params_.iou_threshold_) {
102-
output_objects.emplace_back(input_objects.at(i));
103-
}
91+
92+
if (value <= params_.iou_threshold_) {
93+
output_objects.emplace_back(input_objects.at(i));
10494
}
10595
}
10696

perception/autoware_lidar_centerpoint/schema/centerpoint.schemal.json

-6
Original file line numberDiff line numberDiff line change
@@ -42,12 +42,6 @@
4242
"minimum": 0.0,
4343
"maximum": 1.0
4444
},
45-
"iou_nms_target_class_names": {
46-
"type": "array",
47-
"description": "An array of class names to be target in NMS.",
48-
"default": ["CAR"],
49-
"uniqueItems": true
50-
},
5145
"iou_nms_search_distance_2d": {
5246
"type": "number",
5347
"description": "A maximum distance value to search the nearest objects.",

perception/autoware_lidar_centerpoint/src/node.cpp

-3
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,6 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti
8080

8181
{
8282
NMSParams p;
83-
p.nms_type_ = NMS_TYPE::IoU_BEV;
84-
p.target_class_names_ = this->declare_parameter<std::vector<std::string>>(
85-
"post_process_params.iou_nms_target_class_names");
8683
p.search_distance_2d_ =
8784
this->declare_parameter<double>("post_process_params.iou_nms_search_distance_2d");
8885
p.iou_threshold_ = this->declare_parameter<double>("post_process_params.iou_nms_threshold");

perception/autoware_lidar_centerpoint/test/test_nms.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,6 @@ TEST(NonMaximumSuppressionTest, Apply)
2424
autoware::lidar_centerpoint::NMSParams params;
2525
params.search_distance_2d_ = 1.0;
2626
params.iou_threshold_ = 0.2;
27-
params.nms_type_ = autoware::lidar_centerpoint::NMS_TYPE::IoU_BEV;
28-
params.target_class_names_ = {"CAR"};
2927
nms.setParameters(params);
3028

3129
std::vector<autoware::lidar_centerpoint::DetectedObject> input_objects(4);

0 commit comments

Comments
 (0)