@@ -44,10 +44,10 @@ BarcodeReaderNode::BarcodeReaderNode()
44
44
{
45
45
scanner_.set_config (zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1 );
46
46
47
-
48
47
camera_sub_ = this ->create_subscription <sensor_msgs::msg::Image>(
49
48
" image" , 10 , std::bind (&BarcodeReaderNode::imageCb, this , std::placeholders::_1));
50
49
50
+ symbol_pub_ = this ->create_publisher <zbar_ros_interfaces::msg::Symbol>(" symbol" , 10 );
51
51
barcode_pub_ = this ->create_publisher <std_msgs::msg::String>(" barcode" , 10 );
52
52
53
53
throttle_ = this ->declare_parameter <double >(" throttle_repeated_barcodes" , 0.0 );
@@ -74,14 +74,29 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image)
74
74
auto it_end = zbar_image.symbol_end ();
75
75
if (it_start != it_end) {
76
76
// If there are barcodes in the image, iterate over all barcode readings from image
77
- for (zbar::Image::SymbolIterator symbol = it_start; symbol != it_end; ++symbol) {
78
- std::string barcode = symbol->get_data ();
79
- RCLCPP_DEBUG (get_logger (), " Barcode detected with data: '%s'" , barcode.c_str ());
77
+ for (zbar::Image::SymbolIterator symbol_it = it_start; symbol_it != it_end; ++symbol_it) {
78
+ zbar_ros_interfaces::msg::Symbol symbol;
79
+ symbol.data = symbol_it->get_data ();
80
+ RCLCPP_DEBUG (get_logger (), " Barcode detected with data: '%s'" , symbol.data .c_str ());
81
+
82
+ RCLCPP_DEBUG (
83
+ get_logger (), " Polygon around barcode has %d points" , symbol_it->get_location_size ());
84
+ for (zbar::Symbol::PointIterator point_it = symbol_it->point_begin ();
85
+ point_it != symbol_it->point_end ();
86
+ ++point_it)
87
+ {
88
+ vision_msgs::msg::Point2D point;
89
+ point.x = (*point_it).x ;
90
+ point.y = (*point_it).y ;
91
+ RCLCPP_DEBUG (get_logger (), " Point: %f, %f" , point.x , point.y );
92
+ symbol.points .push_back (point);
93
+ }
80
94
81
95
// verify if repeated barcode throttling is enabled
82
96
if (throttle_ > 0.0 ) {
83
97
const std::lock_guard<std::mutex> lock (memory_mutex_);
84
98
99
+ const std::string & barcode = symbol.data ;
85
100
// check if barcode has been recorded as seen, and skip detection
86
101
if (barcode_memory_.count (barcode) > 0 ) {
87
102
// check if time reached to forget barcode
@@ -100,16 +115,32 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image)
100
115
now () + rclcpp::Duration (std::chrono::duration<double >(throttle_))));
101
116
}
102
117
103
- // publish barcode
118
+ // publish symbol
119
+ RCLCPP_DEBUG (get_logger (), " Publishing Symbol" );
120
+ symbol_pub_->publish (symbol);
121
+
122
+ // publish on deprecated barcode topic
104
123
RCLCPP_DEBUG (get_logger (), " Publishing data as string" );
105
124
std_msgs::msg::String barcode_string;
106
- barcode_string.data = barcode ;
125
+ barcode_string.data = symbol. data ;
107
126
barcode_pub_->publish (barcode_string);
108
127
}
109
128
} else {
110
129
RCLCPP_DEBUG (get_logger (), " No barcode detected in image" );
111
130
}
112
131
132
+ // Warn if there are subscriptions on barcode topic, because it's deprecated.
133
+ static bool alreadyWarnedDeprecation = false ;
134
+ if (!alreadyWarnedDeprecation && count_subscribers (" barcode" ) > 0 ) {
135
+ alreadyWarnedDeprecation = true ;
136
+ RCLCPP_WARN (
137
+ get_logger (),
138
+ " A subscription was detected on the deprecated topic 'barcode'. Please update the node "
139
+ " that is subscribing to use the new topic 'symbol' with type "
140
+ " 'zbar_ros_interfaces::msg::Symbol' instead. The 'barcode' topic will be removed "
141
+ " in the next distribution." );
142
+ }
143
+
113
144
zbar_image.set_data (NULL , 0 );
114
145
}
115
146
0 commit comments