Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_lidar_transfusion): non-maximum suppression target decision logic #9612

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
densification_world_frame_id: map
# post-process params
circle_nms_dist_threshold: 0.5
iou_nms_target_class_names: ["CAR"]
iou_nms_search_distance_2d: 10.0
iou_nms_threshold: 0.1
yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] # refers to the class_names
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,35 +28,12 @@ namespace autoware::lidar_transfusion
{
using autoware_perception_msgs::msg::DetectedObject;

enum class NMS_TYPE {
IoU_BEV
// IoU_3D
// Distance_2D
// Distance_3D
};

struct NMSParams
{
NMS_TYPE nms_type_{};
std::vector<std::string> target_class_names_{};
double search_distance_2d_{};
double iou_threshold_{};
// double distance_threshold_{};
};

std::vector<bool> classNamesToBooleanMask(const std::vector<std::string> & class_names)
{
std::vector<bool> 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
{
public:
Expand All @@ -65,14 +42,13 @@ class NonMaximumSuppression
std::vector<DetectedObject> apply(const std::vector<DetectedObject> &);

private:
bool isTargetLabel(const std::uint8_t);

bool isTargetPairObject(const DetectedObject &, const DetectedObject &);

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

NMSParams params_{};
std::vector<bool> target_class_mask_{};

double search_distance_2d_sq_{};
};

} // namespace autoware::lidar_transfusion
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,22 +22,15 @@

namespace autoware::lidar_transfusion
{
using Label = autoware_perception_msgs::msg::ObjectClassification;

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

params_ = params;
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);
search_distance_2d_sq_ = params.search_distance_2d_ * params.search_distance_2d_;
}

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

if (isTargetLabel(label1) && isTargetLabel(label2)) {
return true;
// if labels are not the same, and one of them is pedestrian, do not suppress
if (label1 != label2 && (label1 == Label::PEDESTRIAN || label2 == Label::PEDESTRIAN)) {

Check warning on line 45 in perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

NonMaximumSuppression::isTargetPairObject has 1 complex conditionals with 2 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
return false;
}

const auto search_sqr_dist_2d = params_.search_distance_2d_ * params_.search_distance_2d_;
const auto sqr_dist_2d = autoware::universe_utils::calcSquaredDistance2d(
autoware::object_recognition_utils::getPose(object1),
autoware::object_recognition_utils::getPose(object2));
return sqr_dist_2d <= search_sqr_dist_2d;
return sqr_dist_2d <= search_distance_2d_sq_;
}

Eigen::MatrixXd NonMaximumSuppression::generateIoUMatrix(
Expand All @@ -73,14 +66,12 @@
continue;
}

if (params_.nms_type_ == NMS_TYPE::IoU_BEV) {
const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj);
triangular_matrix(target_i, source_i) = iou;
// NOTE: If the target object has any objects with iou > iou_threshold, it
// will be suppressed regardless of later results.
if (iou > params_.iou_threshold_) {
break;
}
const double iou = autoware::object_recognition_utils::get2dIoU(target_obj, source_obj);
triangular_matrix(target_i, source_i) = iou;
// NOTE: If the target object has any objects with iou > iou_threshold, it
// will be suppressed regardless of later results.
if (iou > params_.iou_threshold_) {
break;

Check notice on line 74 in perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

NonMaximumSuppression::generateIoUMatrix is no longer above the threshold for logical blocks with deeply nested code

Check notice on line 74 in perception/autoware_lidar_transfusion/lib/postprocess/non_maximum_suppression.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Deep, Nested Complexity

NonMaximumSuppression::generateIoUMatrix is no longer above the threshold for nested complexity depth
}
}
}
Expand All @@ -97,10 +88,9 @@
output_objects.reserve(input_objects.size());
for (std::size_t i = 0; i < input_objects.size(); ++i) {
const auto value = iou_matrix.row(i).maxCoeff();
if (params_.nms_type_ == NMS_TYPE::IoU_BEV) {
if (value <= params_.iou_threshold_) {
output_objects.emplace_back(input_objects.at(i));
}

if (value <= params_.iou_threshold_) {
output_objects.emplace_back(input_objects.at(i));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,15 +48,6 @@
"default": 0.5,
"minimum": 0.0
},
"iou_nms_target_class_names": {
"type": "array",
"items": {
"type": "string"
},
"description": "An array of class names to be target in NMS.",
"default": ["CAR"],
"uniqueItems": true
},
"iou_nms_search_distance_2d": {
"type": "number",
"description": "A maximum distance value to search the nearest objects.",
Expand Down Expand Up @@ -95,7 +86,6 @@
"densification_num_past_frames",
"densification_world_frame_id",
"circle_nms_dist_threshold",
"iou_nms_target_class_names",
"iou_nms_search_distance_2d",
"iou_nms_threshold",
"yaw_norm_thresholds",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,10 +64,7 @@
const float circle_nms_dist_threshold =
static_cast<float>(this->declare_parameter<double>("circle_nms_dist_threshold", descriptor));
{ // IoU NMS
NMSParams p;

Check notice on line 67 in perception/autoware_lidar_transfusion/src/lidar_transfusion_node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Large Method

LidarTransfusionNode::LidarTransfusionNode decreases from 81 to 78 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
p.nms_type_ = NMS_TYPE::IoU_BEV;
p.target_class_names_ =
this->declare_parameter<std::vector<std::string>>("iou_nms_target_class_names", descriptor);
p.search_distance_2d_ =
this->declare_parameter<double>("iou_nms_search_distance_2d", descriptor);
p.iou_threshold_ = this->declare_parameter<double>("iou_nms_threshold", descriptor);
Expand Down
2 changes: 0 additions & 2 deletions perception/autoware_lidar_transfusion/test/test_nms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,7 @@
autoware::lidar_transfusion::NonMaximumSuppression nms;
autoware::lidar_transfusion::NMSParams params;
params.search_distance_2d_ = 1.0;
params.iou_threshold_ = 0.2;

Check notice on line 26 in perception/autoware_lidar_transfusion/test/test_nms.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Large Method

TEST:NonMaximumSuppressionTest:Apply decreases from 82 to 80 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
params.nms_type_ = autoware::lidar_transfusion::NMS_TYPE::IoU_BEV;
params.target_class_names_ = {"CAR"};
nms.setParameters(params);

std::vector<autoware::lidar_transfusion::DetectedObject> input_objects(4);
Expand Down
Loading