Skip to content

Commit c85b96f

Browse files
Merge pull request #1803 from tier4/sync-awf-latest
chore: sync awf-latest
2 parents 03f2daf + 2d0ed6f commit c85b96f

File tree

2 files changed

+20
-34
lines changed

2 files changed

+20
-34
lines changed

perception/autoware_traffic_light_selector/src/traffic_light_selector_node.cpp

+13-25
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,8 @@ TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & n
3333
detected_rois_sub_(this, "input/detected_rois", rclcpp::QoS{1}.get_rmw_qos_profile()),
3434
rough_rois_sub_(this, "input/rough_rois", rclcpp::QoS{1}.get_rmw_qos_profile()),
3535
expected_rois_sub_(this, "input/expect_rois", rclcpp::QoS{1}.get_rmw_qos_profile()),
36-
sync_(SyncPolicy(10), detected_rois_sub_, rough_rois_sub_, expected_rois_sub_)
36+
camera_info_sub_(this, "input/camera_info", rclcpp::SensorDataQoS().get_rmw_qos_profile()),
37+
sync_(SyncPolicy(10), detected_rois_sub_, rough_rois_sub_, expected_rois_sub_, camera_info_sub_)
3738
{
3839
{
3940
stop_watch_ptr_ =
@@ -48,37 +49,24 @@ TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & n
4849
using std::placeholders::_1;
4950
using std::placeholders::_2;
5051
using std::placeholders::_3;
51-
sync_.registerCallback(std::bind(&TrafficLightSelectorNode::objectsCallback, this, _1, _2, _3));
52+
using std::placeholders::_4;
53+
sync_.registerCallback(
54+
std::bind(&TrafficLightSelectorNode::objectsCallback, this, _1, _2, _3, _4));
5255

53-
camera_info_sub_ = create_subscription<sensor_msgs::msg::CameraInfo>(
54-
"input/camera_info", rclcpp::SensorDataQoS(),
55-
std::bind(&TrafficLightSelectorNode::cameraInfoCallback, this, _1));
5656
// Publisher
5757
pub_traffic_light_rois_ =
5858
create_publisher<TrafficLightRoiArray>("output/traffic_rois", rclcpp::QoS{1});
5959
}
6060

61-
void TrafficLightSelectorNode::cameraInfoCallback(
62-
const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg)
63-
{
64-
if (camera_info_subscribed_) {
65-
return;
66-
}
67-
RCLCPP_INFO(get_logger(), "camera_info received");
68-
image_width_ = input_msg->width;
69-
image_height_ = input_msg->height;
70-
camera_info_subscribed_ = true;
71-
}
72-
7361
void TrafficLightSelectorNode::objectsCallback(
7462
const DetectedObjectsWithFeature::ConstSharedPtr & detected_traffic_light_msg,
7563
const TrafficLightRoiArray::ConstSharedPtr & rough_rois_msg,
76-
const TrafficLightRoiArray::ConstSharedPtr & expected_rois_msg)
64+
const TrafficLightRoiArray::ConstSharedPtr & expected_rois_msg,
65+
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg)
7766
{
7867
stop_watch_ptr_->toc("processing_time", true);
79-
if (!camera_info_subscribed_) {
80-
return;
81-
}
68+
uint32_t image_width = camera_info_msg->width;
69+
uint32_t image_height = camera_info_msg->height;
8270
std::map<int, sensor_msgs::msg::RegionOfInterest> rough_rois_map;
8371
for (const auto & roi : rough_rois_msg->rois) {
8472
rough_rois_map[roi.traffic_light_id] = roi.roi;
@@ -99,9 +87,9 @@ void TrafficLightSelectorNode::objectsCallback(
9987
expect_rois.push_back(expected_roi.roi);
10088
}
10189
cv::Mat expect_roi_img =
102-
utils::createBinaryImageFromRois(expect_rois, cv::Size(image_width_, image_height_));
90+
utils::createBinaryImageFromRois(expect_rois, cv::Size(image_width, image_height));
10391
cv::Mat det_roi_img =
104-
utils::createBinaryImageFromRois(det_rois, cv::Size(image_width_, image_height_));
92+
utils::createBinaryImageFromRois(det_rois, cv::Size(image_width, image_height));
10593
// for (const auto expect_roi : expect_rois) {
10694
for (const auto & expect_traffic_roi : expected_rois_msg->rois) {
10795
const auto & expect_roi = expect_traffic_roi.roi;
@@ -135,10 +123,10 @@ void TrafficLightSelectorNode::objectsCallback(
135123
// fit top lef corner of detected roi to inside of image
136124
detected_roi_shifted.x_offset = std::clamp(
137125
static_cast<int>(detected_roi.feature.roi.x_offset) - det_roi_shift_x, 0,
138-
static_cast<int>(image_width_ - detected_roi.feature.roi.width));
126+
static_cast<int>(image_width - detected_roi.feature.roi.width));
139127
detected_roi_shifted.y_offset = std::clamp(
140128
static_cast<int>(detected_roi.feature.roi.y_offset) - det_roi_shift_y, 0,
141-
static_cast<int>(image_height_ - detected_roi.feature.roi.height));
129+
static_cast<int>(image_height - detected_roi.feature.roi.height));
142130

143131
double iou = utils::getGenIoU(expect_roi.roi, detected_roi_shifted);
144132
if (iou > max_iou) {

perception/autoware_traffic_light_selector/src/traffic_light_selector_node.hpp

+7-9
Original file line numberDiff line numberDiff line change
@@ -57,25 +57,23 @@ class TrafficLightSelectorNode : public rclcpp::Node
5757
message_filters::Subscriber<DetectedObjectsWithFeature> detected_rois_sub_;
5858
message_filters::Subscriber<TrafficLightRoiArray> rough_rois_sub_;
5959
message_filters::Subscriber<TrafficLightRoiArray> expected_rois_sub_;
60+
message_filters::Subscriber<sensor_msgs::msg::CameraInfo> camera_info_sub_;
6061
typedef message_filters::sync_policies::ApproximateTime<
61-
DetectedObjectsWithFeature, TrafficLightRoiArray, TrafficLightRoiArray>
62+
DetectedObjectsWithFeature, TrafficLightRoiArray, TrafficLightRoiArray,
63+
sensor_msgs::msg::CameraInfo>
6264
SyncPolicy;
6365
typedef message_filters::Synchronizer<SyncPolicy> Sync;
6466
Sync sync_;
6567
void objectsCallback(
6668
const DetectedObjectsWithFeature::ConstSharedPtr & detected_rois_msg,
6769
const TrafficLightRoiArray::ConstSharedPtr & rough_rois_msg,
68-
const TrafficLightRoiArray::ConstSharedPtr & expect_rois_msg);
70+
const TrafficLightRoiArray::ConstSharedPtr & expect_rois_msg,
71+
const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg);
6972

70-
void cameraInfoCallback(const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg);
7173
// Publisher
7274
rclcpp::Publisher<TrafficLightRoiArray>::SharedPtr pub_traffic_light_rois_;
73-
// Subscribe camera_info to get width and height of image
74-
rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr camera_info_sub_;
75-
bool camera_info_subscribed_;
76-
uint32_t image_width_{1280};
77-
uint32_t image_height_{960};
78-
double max_iou_threshold_{0.0};
75+
76+
double max_iou_threshold_;
7977

8078
std::unique_ptr<autoware::universe_utils::StopWatch<std::chrono::milliseconds>> stop_watch_ptr_;
8179
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;

0 commit comments

Comments
 (0)