Skip to content

Commit

Permalink
fix: add existence probability update, refactoring
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Sep 24, 2024
1 parent 9f7ba86 commit b86720d
Showing 1 changed file with 12 additions and 28 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ void RoiClusterFusionNode::fuseOnSingleImage(
int index = -1;
bool associated = false;
double max_iou = 0.0;
bool is_roi_label_known =
const bool is_roi_label_known =
feature_obj.object.classification.front().label != ObjectClassification::UNKNOWN;
for (const auto & cluster_map : m_cluster_roi) {
double iou(0.0);
Expand Down Expand Up @@ -196,34 +196,18 @@ void RoiClusterFusionNode::fuseOnSingleImage(
}

if (!output_cluster_msg.feature_objects.empty()) {
bool is_roi_existence_prob_higher =
output_cluster_msg.feature_objects.at(index).object.existence_probability <=
feature_obj.object.existence_probability;
if (iou_threshold_ < max_iou && is_roi_existence_prob_higher && is_roi_label_known) {
output_cluster_msg.feature_objects.at(index).object.classification =
feature_obj.object.classification;

// Update existence_probability for fused objects
if (
output_cluster_msg.feature_objects.at(index).object.existence_probability <
min_roi_existence_prob_) {
output_cluster_msg.feature_objects.at(index).object.existence_probability =
min_roi_existence_prob_;
}
}

// fuse with unknown roi

if (unknown_iou_threshold_ < max_iou && is_roi_existence_prob_higher && !is_roi_label_known) {
output_cluster_msg.feature_objects.at(index).object.classification =
feature_obj.object.classification;
auto & fused_object = output_cluster_msg.feature_objects.at(index).object;
const bool is_roi_existence_prob_higher =
fused_object.existence_probability <= feature_obj.object.existence_probability;

Check warning on line 201 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp#L200-L201

Added lines #L200 - L201 were not covered by tests
const bool is_roi_iou_over_threshold =
(is_roi_label_known && iou_threshold_ < max_iou) ||
(!is_roi_label_known && unknown_iou_threshold_ < max_iou);

if (is_roi_iou_over_threshold && is_roi_existence_prob_higher) {

Check notice on line 206 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Conditional

RoiClusterFusionNode::fuseOnSingleImage decreases from 3 complex conditionals with 7 branches to 1 complex conditionals with 3 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.
fused_object.classification = feature_obj.object.classification;
// Update existence_probability for fused objects
if (
output_cluster_msg.feature_objects.at(index).object.existence_probability <
min_roi_existence_prob_) {
output_cluster_msg.feature_objects.at(index).object.existence_probability =
min_roi_existence_prob_;
}
fused_object.existence_probability =

Check warning on line 209 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp#L209

Added line #L209 was not covered by tests
std::clamp(feature_obj.object.existence_probability, min_roi_existence_prob_, 1.0f);

Check notice on line 210 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

RoiClusterFusionNode::fuseOnSingleImage decreases in cyclomatic complexity from 43 to 40, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check notice on line 210 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Bumpy Road Ahead

RoiClusterFusionNode::fuseOnSingleImage decreases from 6 to 5 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.
}
}
if (debugger_) debugger_->image_rois_.push_back(feature_obj.feature.roi);
Expand Down

0 comments on commit b86720d

Please sign in to comment.