@@ -33,8 +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_ ),
37
- camera_info_subscribed_( false )
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_ )
38
38
{
39
39
{
40
40
stop_watch_ptr_ =
@@ -49,40 +49,23 @@ TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & n
49
49
using std::placeholders::_1;
50
50
using std::placeholders::_2;
51
51
using std::placeholders::_3;
52
- sync_.registerCallback (std::bind (&TrafficLightSelectorNode::objectsCallback, this , _1, _2, _3));
52
+ using std::placeholders::_4;
53
+ sync_.registerCallback (std::bind (&TrafficLightSelectorNode::objectsCallback, this , _1, _2, _3, _4));
53
54
54
- camera_info_sub_ = create_subscription<sensor_msgs::msg::CameraInfo>(
55
- " input/camera_info" , rclcpp::SensorDataQoS (),
56
- std::bind (&TrafficLightSelectorNode::cameraInfoCallback, this , _1));
57
55
// Publisher
58
56
pub_traffic_light_rois_ =
59
57
create_publisher<TrafficLightRoiArray>(" output/traffic_rois" , rclcpp::QoS{1 });
60
58
}
61
59
62
- void TrafficLightSelectorNode::cameraInfoCallback (
63
- const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg)
64
- {
65
- std::lock_guard<std::mutex> lock (mutex_);
66
- if (camera_info_subscribed_) {
67
- return ;
68
- }
69
- image_width_ = input_msg->width ;
70
- image_height_ = input_msg->height ;
71
- camera_info_subscribed_ = true ;
72
- RCLCPP_INFO (get_logger (), " camera_info received" );
73
- }
74
-
75
60
void TrafficLightSelectorNode::objectsCallback (
76
61
const DetectedObjectsWithFeature::ConstSharedPtr & detected_traffic_light_msg,
77
62
const TrafficLightRoiArray::ConstSharedPtr & rough_rois_msg,
78
- const TrafficLightRoiArray::ConstSharedPtr & expected_rois_msg)
63
+ const TrafficLightRoiArray::ConstSharedPtr & expected_rois_msg,
64
+ const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg)
79
65
{
80
66
stop_watch_ptr_->toc (" processing_time" , true );
81
- mutex_.lock ();
82
- if (!camera_info_subscribed_) {
83
- return ;
84
- }
85
- mutex_.unlock ();
67
+ uint32_t image_width = camera_info_msg->width ;
68
+ uint32_t image_height = camera_info_msg->height ;
86
69
std::map<int , sensor_msgs::msg::RegionOfInterest> rough_rois_map;
87
70
for (const auto & roi : rough_rois_msg->rois ) {
88
71
rough_rois_map[roi.traffic_light_id ] = roi.roi ;
@@ -103,9 +86,9 @@ void TrafficLightSelectorNode::objectsCallback(
103
86
expect_rois.push_back (expected_roi.roi );
104
87
}
105
88
cv::Mat expect_roi_img =
106
- utils::createBinaryImageFromRois (expect_rois, cv::Size (image_width_, image_height_ ));
89
+ utils::createBinaryImageFromRois (expect_rois, cv::Size (image_width, image_height ));
107
90
cv::Mat det_roi_img =
108
- utils::createBinaryImageFromRois (det_rois, cv::Size (image_width_, image_height_ ));
91
+ utils::createBinaryImageFromRois (det_rois, cv::Size (image_width, image_height ));
109
92
// for (const auto expect_roi : expect_rois) {
110
93
for (const auto & expect_traffic_roi : expected_rois_msg->rois ) {
111
94
const auto & expect_roi = expect_traffic_roi.roi ;
@@ -139,10 +122,10 @@ void TrafficLightSelectorNode::objectsCallback(
139
122
// fit top lef corner of detected roi to inside of image
140
123
detected_roi_shifted.x_offset = std::clamp (
141
124
static_cast <int >(detected_roi.feature .roi .x_offset ) - det_roi_shift_x, 0 ,
142
- static_cast <int >(image_width_ - detected_roi.feature .roi .width ));
125
+ static_cast <int >(image_width - detected_roi.feature .roi .width ));
143
126
detected_roi_shifted.y_offset = std::clamp (
144
127
static_cast <int >(detected_roi.feature .roi .y_offset ) - det_roi_shift_y, 0 ,
145
- static_cast <int >(image_height_ - detected_roi.feature .roi .height ));
128
+ static_cast <int >(image_height - detected_roi.feature .roi .height ));
146
129
147
130
double iou = utils::getGenIoU (expect_roi.roi , detected_roi_shifted);
148
131
if (iou > max_iou) {
0 commit comments