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 2 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 @@ -5,3 +5,4 @@
use_vehicle_reference_yaw: false
use_vehicle_reference_shape_size: false
use_boost_bbox_optimizer: false
keep_supper_large_vehicle: true
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
10 changes: 7 additions & 3 deletions perception/shape_estimation/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
use_vehicle_reference_yaw_ = declare_parameter<bool>("use_vehicle_reference_yaw");
use_vehicle_reference_shape_size_ = declare_parameter<bool>("use_vehicle_reference_shape_size");
bool use_boost_bbox_optimizer = declare_parameter<bool>("use_boost_bbox_optimizer");
keep_supper_large_vehicle_ = declare_parameter<bool>("keep_supper_large_vehicle");

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

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L50

Added line #L50 was not covered by tests
RCLCPP_INFO(this->get_logger(), "using boost shape estimation : %d", use_boost_bbox_optimizer);
estimator_ =
std::make_unique<ShapeEstimator>(use_corrector, use_filter, use_boost_bbox_optimizer);
Expand Down Expand Up @@ -103,12 +104,15 @@
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 (!estimated_success) {
// If the shape estimation fails, change to Unknown object.
if (!keep_supper_large_vehicle_ && !estimated_success) {

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

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L108

Added line #L108 was not covered by tests
continue;
}

output_msg.feature_objects.push_back(feature_object);
if (!estimated_success) {
output_msg.feature_objects.back().object.classification.front().label = Label::UNKNOWN;

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

View check run for this annotation

Codecov / codecov/patch

perception/shape_estimation/src/node.cpp#L112-L113

Added lines #L112 - L113 were not covered by tests
}

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

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

ShapeEstimationNode::callback increases in cyclomatic complexity from 14 to 16, 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.back().object.shape = shape;
output_msg.feature_objects.back().object.kinematics.pose_with_covariance.pose = pose;
}
Expand Down
1 change: 1 addition & 0 deletions perception/shape_estimation/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ class ShapeEstimationNode : public rclcpp::Node
std::unique_ptr<ShapeEstimator> estimator_;
bool use_vehicle_reference_yaw_;
bool use_vehicle_reference_shape_size_;
bool keep_supper_large_vehicle_;

public:
explicit ShapeEstimationNode(const rclcpp::NodeOptions & node_options);
Expand Down
Loading