Skip to content

Commit abad27f

Browse files
committed
feat: add max_iou_threshold
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 357967f commit abad27f

File tree

2 files changed

+4
-1
lines changed

2 files changed

+4
-1
lines changed

perception/autoware_traffic_light_selector/src/traffic_light_selector_node.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -172,6 +172,8 @@ TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & n
172172
expected_rois_sub_(this, "input/expect_rois", rclcpp::QoS{1}.get_rmw_qos_profile()),
173173
sync_(SyncPolicy(10), detected_rois_sub_, rough_rois_sub_, expected_rois_sub_)
174174
{
175+
max_iou_threshold_ = declare_parameter<double>("max_iou_threshold", 0.0);
176+
RCLCPP_INFO(get_logger(), "max_iou_threshold: %f", max_iou_threshold_);
175177
debug_ = declare_parameter<bool>("debug");
176178
using std::placeholders::_1;
177179
using std::placeholders::_2;
@@ -272,7 +274,7 @@ void TrafficLightSelectorNode::objectsCallback(
272274
max_iou_roi = detected_roi.feature.roi;
273275
}
274276
}
275-
if (max_iou > 0.0) {
277+
if (max_iou > max_iou_threshold_) {
276278
TrafficLightRoi traffic_light_roi;
277279
traffic_light_roi.traffic_light_id = expect_roi.traffic_light_id;
278280
traffic_light_roi.roi = max_iou_roi;

perception/autoware_traffic_light_selector/src/traffic_light_selector_node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ class TrafficLightSelectorNode : public rclcpp::Node
7676
bool camera_info_subscribed_;
7777
uint32_t image_width_{1280};
7878
uint32_t image_height_{960};
79+
double max_iou_threshold_{0.0};
7980
// declare publisher for debug image
8081
// rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr pub_debug_image_;
8182
};

0 commit comments

Comments
 (0)