barcode_reader_nodelet.cpp
Go to the documentation of this file.
1 
32 
33 #include <utility>
34 #include <string>
35 
37 #include "std_msgs/String.h"
38 
39 namespace zbar_ros
40 {
41 
43  {
44  scanner_.set_config(zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1);
45  }
46 
48  {
49  nh_ = getNodeHandle();
51 
52  barcode_pub_ = nh_.advertise<std_msgs::String>("barcode", 10,
53  boost::bind(&BarcodeReaderNodelet::connectCb, this),
54  boost::bind(&BarcodeReaderNodelet::disconnectCb, this));
55 
56  private_nh_.param<double>("throttle_repeated_barcodes", throttle_, 0.0);
57  if (throttle_ > 0.0)
58  {
60  }
61  };
62 
64  {
66  {
67  NODELET_INFO("Connecting to camera topic.");
69  }
70  }
71 
73  {
75  {
76  NODELET_INFO("Unsubscribing from camera topic.");
78  }
79  }
80 
81  void BarcodeReaderNodelet::imageCb(const sensor_msgs::ImageConstPtr &image)
82  {
84  cv_image = cv_bridge::toCvShare(image, "mono8");
85 
86  zbar::Image zbar_image(cv_image->image.cols, cv_image->image.rows, "Y800", cv_image->image.data,
87  cv_image->image.cols * cv_image->image.rows);
88  scanner_.scan(zbar_image);
89 
90  // iterate over all barcode readings from image
91  for (zbar::Image::SymbolIterator symbol = zbar_image.symbol_begin();
92  symbol != zbar_image.symbol_end(); ++symbol)
93  {
94  std::string barcode = symbol->get_data();
95  // verify if repeated barcode throttling is enabled
96  if (throttle_ > 0.0)
97  {
98  const std::lock_guard<std::mutex> lock(memory_mutex_);
99 
100  // check if barcode has been recorded as seen, and skip detection
101  if (barcode_memory_.count(barcode) > 0)
102  {
103  // check if time reached to forget barcode
104  if (ros::Time::now() > barcode_memory_.at(barcode))
105  {
106  NODELET_DEBUG("Memory timed out for barcode, publishing");
107  barcode_memory_.erase(barcode);
108  }
109  else
110  {
111  // if timeout not reached, skip this reading
112  continue;
113  }
114  }
115  // record barcode as seen, with a timeout to 'forget'
116  barcode_memory_.insert(std::make_pair(barcode, ros::Time::now() + ros::Duration(throttle_)));
117  }
118 
119  // publish barcode
120  std_msgs::String barcode_string;
121  barcode_string.data = barcode;
122  barcode_pub_.publish(barcode_string);
123  }
124 
125  zbar_image.set_data(NULL, 0);
126  }
127 
129  {
130  const std::lock_guard<std::mutex> lock(memory_mutex_);
131  boost::unordered_map<std::string, ros::Time>::iterator it = barcode_memory_.begin();
132  while (it != barcode_memory_.end())
133  {
134  if (ros::Time::now() > it->second)
135  {
136  NODELET_DEBUG_STREAM("Cleaned " << it->first << " from memory");
137  it = barcode_memory_.erase(it);
138  }
139  else
140  {
141  ++it;
142  }
143  }
144  }
145 } // namespace zbar_ros
146 
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
boost::shared_ptr
zbar_ros::BarcodeReaderNodelet::clean_timer_
ros::Timer clean_timer_
Definition: barcode_reader_nodelet.h:63
zbar_ros::BarcodeReaderNodelet::private_nh_
ros::NodeHandle private_nh_
Definition: barcode_reader_nodelet.h:60
zbar_ros::BarcodeReaderNodelet
Definition: barcode_reader_nodelet.h:48
ros::Subscriber::shutdown
void shutdown()
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(zbar_ros::BarcodeReaderNodelet, nodelet::Nodelet)
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
zbar_ros::BarcodeReaderNodelet::barcode_memory_
boost::unordered_map< std::string, ros::Time > barcode_memory_
Definition: barcode_reader_nodelet.h:67
zbar_ros::BarcodeReaderNodelet::connectCb
void connectCb()
Definition: barcode_reader_nodelet.cpp:63
class_list_macros.h
zbar_ros::BarcodeReaderNodelet::disconnectCb
void disconnectCb()
Definition: barcode_reader_nodelet.cpp:72
zbar_ros
Definition: barcode_reader_nodelet.h:45
zbar_ros::BarcodeReaderNodelet::nh_
ros::NodeHandle nh_
Definition: barcode_reader_nodelet.h:60
zbar_ros::BarcodeReaderNodelet::BarcodeReaderNodelet
BarcodeReaderNodelet()
Definition: barcode_reader_nodelet.cpp:42
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
zbar_ros::BarcodeReaderNodelet::throttle_
double throttle_
Definition: barcode_reader_nodelet.h:69
zbar_ros::BarcodeReaderNodelet::cleanCb
void cleanCb()
Definition: barcode_reader_nodelet.cpp:128
NODELET_INFO
#define NODELET_INFO(...)
zbar_ros::BarcodeReaderNodelet::scanner_
zbar::ImageScanner scanner_
Definition: barcode_reader_nodelet.h:64
zbar_ros::BarcodeReaderNodelet::imageCb
void imageCb(const sensor_msgs::ImageConstPtr &image)
Definition: barcode_reader_nodelet.cpp:81
nodelet::Nodelet
NODELET_DEBUG_STREAM
#define NODELET_DEBUG_STREAM(...)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
zbar_ros::BarcodeReaderNodelet::barcode_pub_
ros::Publisher barcode_pub_
Definition: barcode_reader_nodelet.h:62
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
zbar_ros::BarcodeReaderNodelet::memory_mutex_
std::mutex memory_mutex_
Definition: barcode_reader_nodelet.h:66
zbar_ros::BarcodeReaderNodelet::onInit
virtual void onInit()
Definition: barcode_reader_nodelet.cpp:47
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()
barcode_reader_nodelet.h
zbar_ros::BarcodeReaderNodelet::camera_sub_
ros::Subscriber camera_sub_
Definition: barcode_reader_nodelet.h:61


zbar_ros
Author(s): Paul Bovbel
autogenerated on Sat Jul 2 2022 02:50:32