Skip to content

Commit

Permalink
feat(lidar_centerpoint): do not suppress if one side of the object is…
Browse files Browse the repository at this point in the history
… pedestrian

Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Dec 9, 2024
1 parent 948af5f commit 6199cca
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -45,18 +45,6 @@ struct NMSParams
// 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
{
Expand All @@ -66,14 +54,12 @@ 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_{};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

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

void NonMaximumSuppression::setParameters(const NMSParams & params)
{
Expand All @@ -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(
Expand All @@ -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)) {

Check warning on line 45 in perception/autoware_lidar_centerpoint/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;
}

Expand Down

0 comments on commit 6199cca

Please sign in to comment.