Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007 #include <ros/ros.h>
00008 #include <ros/node_handle.h>
00009 #include "sensor_msgs/Image.h"
00010 #include "image_transport/image_transport.h"
00011 #include "cv_bridge/CvBridge.h"
00012 #include <opencv/cv.h>
00013 #include <opencv/highgui.h>
00014 #include <string.h>
00015 #include "std_msgs/String.h"
00016 #include <zbar.h>
00017 #include <Magick++.h>
00018 #include "comp_barcoo/send_barcode.h"
00019
00020
00021 using namespace std;
00022 using namespace zbar;
00023 class zbar_image_reader
00024 {
00025 protected:
00026 ros::NodeHandle n_;
00027 image_transport::ImageTransport it_;
00028 ros::Publisher barcode_pub_;
00029 ros::ServiceClient client;
00030 comp_barcoo::send_barcode srv;
00031 public:
00032 zbar_image_reader(ros::NodeHandle &n,string img_path, int toKnowrob): n_(n), it_(n_)
00033 {
00034 cv::Mat image = cv::imread(img_path,0);
00035 client = n.serviceClient<comp_barcoo::send_barcode>("/send_barcode");
00036
00037 extract_publish_barcode(image, toKnowrob);
00038 }
00039
00040 ~zbar_image_reader() {
00041
00042 }
00043
00044 void extract_publish_barcode(cv::Mat img,int to_knowrob)
00045 {
00046
00047 ImageScanner scanner;
00048
00049
00050 scanner.set_config(ZBAR_NONE, ZBAR_CFG_ENABLE, 1);
00051
00052 int width = img.cols;
00053 int height = img.rows;
00054
00055
00056 Magick::Blob blob(img.ptr(0), width * height);
00057
00058 const void *raw = blob.data();
00059
00060
00061 Image image(width, height, "Y800", raw, width * height);
00062
00063
00064 int n = scanner.scan(image);
00065
00066
00067 std::stringstream ss;
00068 for( Image::SymbolIterator symbol = image.symbol_begin(); symbol != image.symbol_end(); ++symbol )
00069 {
00070
00071 ROS_INFO_STREAM("Publishing: barcode type: " << symbol->get_type_name() << " barcode value " << symbol->get_data());
00072
00073 std_msgs::String msg;
00074
00075 ss << symbol->get_data();
00076 srv.request.barcode.data = ss.str();
00077 srv.request.knowrob = to_knowrob;
00078 if (client.call(srv))
00079 {
00080 std::cout << "received: " << srv.response.recieved << "\n";
00081 }
00082 }
00083 if (n == 0)
00084 {
00085 ROS_WARN("Barcode not found");
00086 return;
00087 }
00088
00089 if (n < 0)
00090 {
00091 ROS_ERROR("Error occured while finding barcode");
00092 return;
00093 }
00094
00095 }
00096 };
00097
00098 int main(int argc, char** argv)
00099 {
00100 ros::init(argc, argv, "barcode_image_node");
00101 ros::AsyncSpinner spinner(1);
00102 spinner.start();
00103 ros::NodeHandle n("~");
00104 zbar_image_reader reader(n,argv[1],atoi(argv[2]));
00105 ros::spinOnce();
00106
00107 return 0;
00108 }