34 #include "std_msgs/String.h" 41 scanner_.set_config(zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1);
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);
87 for (zbar::Image::SymbolIterator symbol = zbar_image.symbol_begin();
88 symbol != zbar_image.symbol_end(); ++symbol)
90 std::string barcode = symbol->get_data();
114 std_msgs::String barcode_string;
115 barcode_string.data = barcode;
119 zbar_image.set_data(NULL, 0);
124 for (boost::unordered_map<std::string, ros::Time>::iterator it =
barcode_memory_.begin();
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 private_nh_
ros::NodeHandle & getPrivateNodeHandle() const
zbar::ImageScanner scanner_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Subscriber camera_sub_
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
ros::Publisher barcode_pub_
#define NODELET_DEBUG(...)