Go to the documentation of this file.
37 #include "std_msgs/String.h"
44 scanner_.set_config(zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1);
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);
91 for (zbar::Image::SymbolIterator symbol = zbar_image.symbol_begin();
92 symbol != zbar_image.symbol_end(); ++symbol)
94 std::string barcode = symbol->get_data();
120 std_msgs::String barcode_string;
121 barcode_string.data = barcode;
125 zbar_image.set_data(NULL, 0);
131 boost::unordered_map<std::string, ros::Time>::iterator it =
barcode_memory_.begin();
ros::NodeHandle & getNodeHandle() const
ros::NodeHandle private_nh_
PLUGINLIB_EXPORT_CLASS(zbar_ros::BarcodeReaderNodelet, nodelet::Nodelet)
ros::NodeHandle & getPrivateNodeHandle() const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
boost::unordered_map< std::string, ros::Time > barcode_memory_
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())
#define NODELET_INFO(...)
zbar::ImageScanner scanner_
void imageCb(const sensor_msgs::ImageConstPtr &image)
#define NODELET_DEBUG_STREAM(...)
T param(const std::string ¶m_name, const T &default_val) const
ros::Publisher barcode_pub_
uint32_t getNumSubscribers() const
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
#define NODELET_DEBUG(...)
ros::Subscriber camera_sub_
zbar_ros
Author(s): Paul Bovbel
autogenerated on Sat Jul 2 2022 02:50:32