Skip to content

Commit e9e97b9

Browse files
committed
fix(shape_estimation): keep excluded objects as unknown
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 4747e74 commit e9e97b9

File tree

2 files changed

+13
-7
lines changed

2 files changed

+13
-7
lines changed

perception/shape_estimation/lib/shape_estimator.cpp

+10-4
Original file line numberDiff line numberDiff line change
@@ -39,25 +39,31 @@ bool ShapeEstimator::estimateShapeAndPose(
3939
autoware_auto_perception_msgs::msg::Shape shape;
4040
geometry_msgs::msg::Pose pose;
4141
// estimate shape
42+
bool reverse_to_unknown = false;
4243
if (!estimateOriginalShapeAndPose(label, cluster, ref_yaw_info, shape, pose)) {
43-
return false;
44+
reverse_to_unknown = true;
4445
}
4546

4647
// rule based filter
4748
if (use_filter_) {
4849
if (!applyFilter(label, shape, pose)) {
49-
return false;
50+
reverse_to_unknown = true;
5051
}
5152
}
5253

5354
// rule based corrector
5455
if (use_corrector_) {
5556
bool use_reference_yaw = ref_yaw_info ? true : false;
5657
if (!applyCorrector(label, use_reference_yaw, ref_shape_size_info, shape, pose)) {
57-
return false;
58+
reverse_to_unknown = true;
5859
}
5960
}
60-
61+
if (reverse_to_unknown) {
62+
estimateOriginalShapeAndPose(Label::UNKNOWN, cluster, ref_yaw_info, shape, pose);
63+
shape_output = shape;
64+
pose_output = pose;
65+
return false;
66+
}
6167
shape_output = shape;
6268
pose_output = pose;
6369
return true;

perception/shape_estimation/src/node.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -103,12 +103,12 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
103103
const bool estimated_success = estimator_->estimateShapeAndPose(
104104
label, *cluster, ref_yaw_info, ref_shape_size_info, shape, pose);
105105

106-
// If the shape estimation fails, ignore it.
106+
// If the shape estimation fails, change to Unknown object.
107+
output_msg.feature_objects.push_back(feature_object);
107108
if (!estimated_success) {
108-
continue;
109+
output_msg.feature_objects.back().object.classification.front().label = Label::UNKNOWN;
109110
}
110111

111-
output_msg.feature_objects.push_back(feature_object);
112112
output_msg.feature_objects.back().object.shape = shape;
113113
output_msg.feature_objects.back().object.kinematics.pose_with_covariance.pose = pose;
114114
}

0 commit comments

Comments
 (0)