Skip to content

Commit 10ed352

Browse files
fix(shape_estimation): preserve irregular large size vehicle detected by camera_lidar_fusion as unknown (#6598)
* fix(shape_estimation): keep excluded objects as unknown Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: add optional param Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: rename param Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Co-authored-by: Yoshi Ri <yoshiyoshidetteiu@gmail.com>
1 parent 47d1212 commit 10ed352

File tree

4 files changed

+20
-7
lines changed

4 files changed

+20
-7
lines changed

perception/shape_estimation/config/shape_estimation.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -5,3 +5,4 @@
55
use_vehicle_reference_yaw: false
66
use_vehicle_reference_shape_size: false
77
use_boost_bbox_optimizer: false
8+
fix_filtered_objects_label_to_unknown: true

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

+8-3
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,8 @@ ShapeEstimationNode::ShapeEstimationNode(const rclcpp::NodeOptions & node_option
4747
use_vehicle_reference_yaw_ = declare_parameter<bool>("use_vehicle_reference_yaw");
4848
use_vehicle_reference_shape_size_ = declare_parameter<bool>("use_vehicle_reference_shape_size");
4949
bool use_boost_bbox_optimizer = declare_parameter<bool>("use_boost_bbox_optimizer");
50+
fix_filtered_objects_label_to_unknown_ =
51+
declare_parameter<bool>("fix_filtered_objects_label_to_unknown");
5052
RCLCPP_INFO(this->get_logger(), "using boost shape estimation : %d", use_boost_bbox_optimizer);
5153
estimator_ =
5254
std::make_unique<ShapeEstimator>(use_corrector, use_filter, use_boost_bbox_optimizer);
@@ -103,12 +105,15 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
103105
const bool estimated_success = estimator_->estimateShapeAndPose(
104106
label, *cluster, ref_yaw_info, ref_shape_size_info, shape, pose);
105107

106-
// If the shape estimation fails, ignore it.
107-
if (!estimated_success) {
108+
// If the shape estimation fails, change to Unknown object.
109+
if (!fix_filtered_objects_label_to_unknown_ && !estimated_success) {
108110
continue;
109111
}
110-
111112
output_msg.feature_objects.push_back(feature_object);
113+
if (!estimated_success) {
114+
output_msg.feature_objects.back().object.classification.front().label = Label::UNKNOWN;
115+
}
116+
112117
output_msg.feature_objects.back().object.shape = shape;
113118
output_msg.feature_objects.back().object.kinematics.pose_with_covariance.pose = pose;
114119
}

perception/shape_estimation/src/node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ class ShapeEstimationNode : public rclcpp::Node
4444
std::unique_ptr<ShapeEstimator> estimator_;
4545
bool use_vehicle_reference_yaw_;
4646
bool use_vehicle_reference_shape_size_;
47+
bool fix_filtered_objects_label_to_unknown_;
4748

4849
public:
4950
explicit ShapeEstimationNode(const rclcpp::NodeOptions & node_options);

0 commit comments

Comments
 (0)