@@ -33,7 +33,8 @@ TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & n
33
33
detected_rois_sub_(this , " input/detected_rois" , rclcpp::QoS{1 }.get_rmw_qos_profile()),
34
34
rough_rois_sub_(this , " input/rough_rois" , rclcpp::QoS{1 }.get_rmw_qos_profile()),
35
35
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_)
37
38
{
38
39
{
39
40
stop_watch_ptr_ =
@@ -48,37 +49,24 @@ TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & n
48
49
using std::placeholders::_1;
49
50
using std::placeholders::_2;
50
51
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));
52
55
53
- camera_info_sub_ = create_subscription<sensor_msgs::msg::CameraInfo>(
54
- " input/camera_info" , rclcpp::SensorDataQoS (),
55
- std::bind (&TrafficLightSelectorNode::cameraInfoCallback, this , _1));
56
56
// Publisher
57
57
pub_traffic_light_rois_ =
58
58
create_publisher<TrafficLightRoiArray>(" output/traffic_rois" , rclcpp::QoS{1 });
59
59
}
60
60
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
-
73
61
void TrafficLightSelectorNode::objectsCallback (
74
62
const DetectedObjectsWithFeature::ConstSharedPtr & detected_traffic_light_msg,
75
63
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)
77
66
{
78
67
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 ;
82
70
std::map<int , sensor_msgs::msg::RegionOfInterest> rough_rois_map;
83
71
for (const auto & roi : rough_rois_msg->rois ) {
84
72
rough_rois_map[roi.traffic_light_id ] = roi.roi ;
@@ -99,9 +87,9 @@ void TrafficLightSelectorNode::objectsCallback(
99
87
expect_rois.push_back (expected_roi.roi );
100
88
}
101
89
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 ));
103
91
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 ));
105
93
// for (const auto expect_roi : expect_rois) {
106
94
for (const auto & expect_traffic_roi : expected_rois_msg->rois ) {
107
95
const auto & expect_roi = expect_traffic_roi.roi ;
@@ -135,10 +123,10 @@ void TrafficLightSelectorNode::objectsCallback(
135
123
// fit top lef corner of detected roi to inside of image
136
124
detected_roi_shifted.x_offset = std::clamp (
137
125
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 ));
139
127
detected_roi_shifted.y_offset = std::clamp (
140
128
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 ));
142
130
143
131
double iou = utils::getGenIoU (expect_roi.roi , detected_roi_shifted);
144
132
if (iou > max_iou) {
0 commit comments