Skip to content

Commit f73c162

Browse files
committed
chore: add optional param
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent e9e97b9 commit f73c162

File tree

3 files changed

+6
-0
lines changed

3 files changed

+6
-0
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+
keep_supper_large_vehicle: true

perception/shape_estimation/src/node.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,7 @@ 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+
keep_supper_large_vehicle_ = declare_parameter<bool>("keep_supper_large_vehicle");
5051
RCLCPP_INFO(this->get_logger(), "using boost shape estimation : %d", use_boost_bbox_optimizer);
5152
estimator_ =
5253
std::make_unique<ShapeEstimator>(use_corrector, use_filter, use_boost_bbox_optimizer);
@@ -104,6 +105,9 @@ void ShapeEstimationNode::callback(const DetectedObjectsWithFeature::ConstShared
104105
label, *cluster, ref_yaw_info, ref_shape_size_info, shape, pose);
105106

106107
// If the shape estimation fails, change to Unknown object.
108+
if (!keep_supper_large_vehicle_ && !estimated_success) {
109+
continue;
110+
}
107111
output_msg.feature_objects.push_back(feature_object);
108112
if (!estimated_success) {
109113
output_msg.feature_objects.back().object.classification.front().label = Label::UNKNOWN;

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 keep_supper_large_vehicle_;
4748

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

0 commit comments

Comments
 (0)