Go to the documentation of this file.00001
00032 #include "zbar_ros/barcode_reader_nodelet.h"
00033 #include "pluginlib/class_list_macros.h"
00034 #include "std_msgs/String.h"
00035
00036 namespace zbar_ros
00037 {
00038
00039 BarcodeReaderNodelet::BarcodeReaderNodelet()
00040 {
00041 scanner_.set_config(zbar::ZBAR_NONE, zbar::ZBAR_CFG_ENABLE, 1);
00042 }
00043
00044 void BarcodeReaderNodelet::onInit()
00045 {
00046 nh_ = getNodeHandle();
00047 private_nh_ = getPrivateNodeHandle();
00048
00049 barcode_pub_ = nh_.advertise<std_msgs::String>("barcode", 10,
00050 boost::bind(&BarcodeReaderNodelet::connectCb, this),
00051 boost::bind(&BarcodeReaderNodelet::disconnectCb, this));
00052
00053 private_nh_.param<double>("throttle_repeated_barcodes", throttle_, 0.0);
00054 if (throttle_ > 0.0){
00055 clean_timer_ = nh_.createTimer(ros::Duration(10.0), boost::bind(&BarcodeReaderNodelet::cleanCb, this));
00056 }
00057 };
00058
00059 void BarcodeReaderNodelet::connectCb()
00060 {
00061 if (!camera_sub_ && barcode_pub_.getNumSubscribers() > 0)
00062 {
00063 NODELET_INFO("Connecting to camera topic.");
00064 camera_sub_ = nh_.subscribe("image", 10, &BarcodeReaderNodelet::imageCb, this);
00065 }
00066 }
00067
00068 void BarcodeReaderNodelet::disconnectCb()
00069 {
00070 if (barcode_pub_.getNumSubscribers() == 0)
00071 {
00072 NODELET_INFO("Unsubscribing from camera topic.");
00073 camera_sub_.shutdown();
00074 }
00075 }
00076
00077 void BarcodeReaderNodelet::imageCb(const sensor_msgs::ImageConstPtr &image)
00078 {
00079 cv_bridge::CvImageConstPtr cv_image;
00080 cv_image = cv_bridge::toCvShare(image, "mono8");
00081
00082 zbar::Image zbar_image(cv_image->image.cols, cv_image->image.rows, "Y800", cv_image->image.data,
00083 cv_image->image.cols * cv_image->image.rows);
00084 scanner_.scan(zbar_image);
00085
00086
00087 for (zbar::Image::SymbolIterator symbol = zbar_image.symbol_begin();
00088 symbol != zbar_image.symbol_end(); ++symbol)
00089 {
00090 std::string barcode = symbol->get_data();
00091
00092 if (throttle_ > 0.0)
00093 {
00094
00095 if (barcode_memory_.count(barcode) > 0)
00096 {
00097
00098 if (ros::Time::now() > barcode_memory_.at(barcode))
00099 {
00100 NODELET_DEBUG("Memory timed out for barcode, publishing");
00101 barcode_memory_.erase(barcode);
00102 }
00103 else
00104 {
00105
00106 continue;
00107 }
00108 }
00109
00110 barcode_memory_.insert(std::make_pair(barcode, ros::Time::now() + ros::Duration(throttle_)));
00111 }
00112
00113
00114 std_msgs::String barcode_string;
00115 barcode_string.data = barcode;
00116 barcode_pub_.publish(barcode_string);
00117 }
00118
00119 zbar_image.set_data(NULL, 0);
00120 }
00121
00122 void BarcodeReaderNodelet::cleanCb()
00123 {
00124 for (boost::unordered_map<std::string, ros::Time>::iterator it = barcode_memory_.begin();
00125 it != barcode_memory_.end(); ++it)
00126 {
00127 if (ros::Time::now() > it->second)
00128 {
00129 NODELET_DEBUG_STREAM("Cleaned " << it->first << " from memory");
00130 barcode_memory_.erase(it);
00131 }
00132 }
00133
00134 }
00135 }
00136
00137 PLUGINLIB_DECLARE_CLASS(zbar_ros, BarcodeReaderNodelet, zbar_ros::BarcodeReaderNodelet, nodelet::Nodelet);