From 0e90edaef07055564724bf45cc00966f097ece6a Mon Sep 17 00:00:00 2001 From: Kenji Brameld Date: Sun, 21 Aug 2022 07:31:40 +0900 Subject: [PATCH] bring non-deprecated code before deprecated code Signed-off-by: Kenji Brameld --- zbar_ros/include/zbar_ros/barcode_reader_node.hpp | 2 +- zbar_ros/src/barcode_reader_node.cpp | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/zbar_ros/include/zbar_ros/barcode_reader_node.hpp b/zbar_ros/include/zbar_ros/barcode_reader_node.hpp index a80b4fb..76f2822 100644 --- a/zbar_ros/include/zbar_ros/barcode_reader_node.hpp +++ b/zbar_ros/include/zbar_ros/barcode_reader_node.hpp @@ -53,8 +53,8 @@ class BarcodeReaderNode : public rclcpp::Node void cleanCb(); rclcpp::Subscription::SharedPtr camera_sub_; - rclcpp::Publisher::SharedPtr barcode_pub_; // DEPRECATED rclcpp::Publisher::SharedPtr symbol_pub_; + rclcpp::Publisher::SharedPtr barcode_pub_; // DEPRECATED zbar::ImageScanner scanner_; rclcpp::TimerBase::SharedPtr clean_timer_; diff --git a/zbar_ros/src/barcode_reader_node.cpp b/zbar_ros/src/barcode_reader_node.cpp index 5a27811..562c094 100644 --- a/zbar_ros/src/barcode_reader_node.cpp +++ b/zbar_ros/src/barcode_reader_node.cpp @@ -47,8 +47,8 @@ BarcodeReaderNode::BarcodeReaderNode() camera_sub_ = this->create_subscription( "image", 10, std::bind(&BarcodeReaderNode::imageCb, this, std::placeholders::_1)); - barcode_pub_ = this->create_publisher("barcode", 10); symbol_pub_ = this->create_publisher("symbol", 10); + barcode_pub_ = this->create_publisher("barcode", 10); throttle_ = this->declare_parameter("throttle_repeated_barcodes", 0.0); RCLCPP_DEBUG(get_logger(), "throttle_repeated_barcodes : %f", throttle_); @@ -96,7 +96,7 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image) if (throttle_ > 0.0) { const std::lock_guard lock(memory_mutex_); - std::string barcode = symbol.data; + const 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 @@ -115,15 +115,15 @@ void BarcodeReaderNode::imageCb(sensor_msgs::msg::Image::ConstSharedPtr image) now() + rclcpp::Duration(std::chrono::duration(throttle_)))); } - // publish barcode + // publish symbol + RCLCPP_DEBUG(get_logger(), "Publishing Symbol"); + symbol_pub_->publish(symbol); + + // publish on deprecated barcode topic RCLCPP_DEBUG(get_logger(), "Publishing data as string"); std_msgs::msg::String barcode_string; barcode_string.data = symbol.data; barcode_pub_->publish(barcode_string); - - // publish symbol - RCLCPP_DEBUG(get_logger(), "Publishing Symbol"); - symbol_pub_->publish(symbol); } } else { RCLCPP_DEBUG(get_logger(), "No barcode detected in image");