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


zbar_ros
Author(s): Paul Bovbel
autogenerated on Thu Jun 6 2019 19:19:39