Skip to content

Commit

Permalink
add code to deprecate barcode topic
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Brameld <kenjibrameld@gmail.com>
  • Loading branch information
ijnek committed Aug 20, 2022
1 parent b9418a6 commit 9babaea
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 8 deletions.
3 changes: 2 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,8 @@ Subscriptions:
* `image` (`sensor_msgs/msg/Image.msg`)

Publisher:
* `barcode` (`zbar_ros_interfaces/msg/Symbol`)
* `barcode` (`std_msgs/msg/String`) - **DEPRECATED**
* `symbol` (`zbar_ros_interfaces/msg/Symbol`)


### (Optional) Debugging the barcode_reader node
Expand Down
4 changes: 3 additions & 1 deletion zbar_ros/include/zbar_ros/barcode_reader_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
#include "rclcpp/timer.hpp"
#include "./zbar.h"
#include "sensor_msgs/msg/image.hpp"
#include "std_msgs/msg/string.hpp"
#include "zbar_ros_interfaces/msg/symbol.hpp"

namespace zbar_ros
Expand All @@ -52,7 +53,8 @@ class BarcodeReaderNode : public rclcpp::Node
void cleanCb();

rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr camera_sub_;
rclcpp::Publisher<zbar_ros_interfaces::msg::Symbol>::SharedPtr barcode_pub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr barcode_pub_; // DEPRECATED
rclcpp::Publisher<zbar_ros_interfaces::msg::Symbol>::SharedPtr symbol_pub_;
zbar::ImageScanner scanner_;

rclcpp::TimerBase::SharedPtr clean_timer_;
Expand Down
1 change: 1 addition & 0 deletions zbar_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<depend>zbar</depend>
<depend>cv_bridge</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
<depend>zbar_ros_interfaces</depend>

<test_depend>ament_lint_auto</test_depend>
Expand Down
18 changes: 13 additions & 5 deletions zbar_ros/src/barcode_reader_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,11 @@ BarcodeReaderNode::BarcodeReaderNode()
{
scanner_.set_config(zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1);


camera_sub_ = this->create_subscription<sensor_msgs::msg::Image>(
"image", 10, std::bind(&BarcodeReaderNode::imageCb, this, std::placeholders::_1));

barcode_pub_ = this->create_publisher<std_msgs::msg::String>("barcode", 10);
barcode_pub_ = this->create_publisher<zbar_ros_interfaces::msg::Symbol>("symbol", 10);
symbol_pub_ = this->create_publisher<zbar_ros_interfaces::msg::Symbol>("symbol", 10);

throttle_ = this->declare_parameter<double>("throttle_repeated_barcodes", 0.0);
RCLCPP_DEBUG(get_logger(), "throttle_repeated_barcodes : %f", throttle_);
Expand Down Expand Up @@ -77,7 +76,6 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image)
// If there are barcodes in the image, iterate over all barcode readings from image
for (zbar::Image::SymbolIterator symbol_it = it_start; symbol_it != it_end; ++symbol_it) {
zbar_ros_interfaces::msg::Symbol symbol;

symbol.data = symbol_it->get_data();
RCLCPP_DEBUG(get_logger(), "Barcode detected with data: '%s'", symbol.data.c_str());

Expand All @@ -98,6 +96,7 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image)
if (throttle_ > 0.0) {
const std::lock_guard<std::mutex> lock(memory_mutex_);

std::string barcode = symbol.data;
// check if barcode has been recorded as seen, and skip detection
if (barcode_memory_.count(barcode) > 0) {
// check if time reached to forget barcode
Expand All @@ -119,17 +118,26 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image)
// publish barcode
RCLCPP_DEBUG(get_logger(), "Publishing data as string");
std_msgs::msg::String barcode_string;
barcode_string.data = barcode;
barcode_string.data = symbol.data;
barcode_pub_->publish(barcode_string);

// publish symbol
RCLCPP_DEBUG(get_logger(), "Publishing Symbol");
barcode_pub_->publish(symbol);
symbol_pub_->publish(symbol);
}
} else {
RCLCPP_DEBUG(get_logger(), "No barcode detected in image");
}

// Warn if there are subscriptions on barcode topic, because it's deprecated.
static bool alreadyWarnedDeprecation = false;
if (!alreadyWarnedDeprecation && count_subscribers("barcode") > 0) {
alreadyWarnedDeprecation = true;
RCLCPP_WARN(get_logger(), "A subscription was detected on the deprecated 'barcode'"
"topic. Please subscribe to the new 'symbol' topic with type"
"'zbar_ros_interfaces::msg::Symbol'.");
}

zbar_image.set_data(NULL, 0);
}

Expand Down
2 changes: 1 addition & 1 deletion zbar_ros_interfaces/msg/Symbol.msg
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
string data
geometry_msgs/Point[] points
geometry_msgs/Point[] points

0 comments on commit 9babaea

Please sign in to comment.