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(shape_estimation): preserve irregular large size vehicle detected by camera_lidar_fusion as unknown #6598

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
14 changes: 10 additions & 4 deletions perception/shape_estimation/lib/shape_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,25 +39,31 @@
autoware_auto_perception_msgs::msg::Shape shape;
geometry_msgs::msg::Pose pose;
// estimate shape
bool reverse_to_unknown = false;
if (!estimateOriginalShapeAndPose(label, cluster, ref_yaw_info, shape, pose)) {
return false;
reverse_to_unknown = true;
}

// rule based filter
if (use_filter_) {
if (!applyFilter(label, shape, pose)) {
return false;
reverse_to_unknown = true;
}
}

// rule based corrector
if (use_corrector_) {
bool use_reference_yaw = ref_yaw_info ? true : false;
if (!applyCorrector(label, use_reference_yaw, ref_shape_size_info, shape, pose)) {
return false;
reverse_to_unknown = true;
}
}

if (reverse_to_unknown) {
estimateOriginalShapeAndPose(Label::UNKNOWN, cluster, ref_yaw_info, shape, pose);

Check warning on line 62 in perception/shape_estimation/lib/shape_estimator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/lib/shape_estimator.cpp#L61-L62

Added lines #L61 - L62 were not covered by tests
shape_output = shape;
pose_output = pose;
return false;

Check warning on line 65 in perception/shape_estimation/lib/shape_estimator.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/lib/shape_estimator.cpp#L64-L65

Added lines #L64 - L65 were not covered by tests
}
shape_output = shape;
pose_output = pose;
return true;
Expand Down
6 changes: 3 additions & 3 deletions perception/shape_estimation/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,12 +103,12 @@
const bool estimated_success = estimator_->estimateShapeAndPose(
label, *cluster, ref_yaw_info, ref_shape_size_info, shape, pose);

// If the shape estimation fails, ignore it.
// If the shape estimation fails, change to Unknown object.
output_msg.feature_objects.push_back(feature_object);

Check warning on line 107 in perception/shape_estimation/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L107

Added line #L107 was not covered by tests
if (!estimated_success) {
continue;
output_msg.feature_objects.back().object.classification.front().label = Label::UNKNOWN;

Check warning on line 109 in perception/shape_estimation/src/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L109

Added line #L109 was not covered by tests
}

Check notice on line 111 in perception/shape_estimation/src/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

ShapeEstimationNode::callback decreases in cyclomatic complexity from 14 to 13, 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.
output_msg.feature_objects.push_back(feature_object);
output_msg.feature_objects.back().object.shape = shape;
output_msg.feature_objects.back().object.kinematics.pose_with_covariance.pose = pose;
}
Expand Down
Loading