00001
00002 #include <ros/ros.h>
00003 #include <ros/node_handle.h>
00004 #include "sensor_msgs/Image.h"
00005 #include "image_transport/image_transport.h"
00006 #include "cv_bridge/CvBridge.h"
00007 #include <opencv/cv.h>
00008 #include <opencv/highgui.h>
00009 #include <string.h>
00010 #include "std_msgs/String.h"
00011 #include <sstream>
00012 #include "curl/curl.h"
00013 #include "tinyxml.h"
00014 #include <highgui.h>
00015 #include <zbar_barcode_reader_node/enable_barcode_reader.h>
00016 #include <cv_bridge/cv_bridge.h>
00017 #include <fstream>
00018
00019 #include <Magick++.h>
00020
00021 #include <zbar.h>
00022
00023 using namespace std;
00024 using namespace zbar;
00025 using namespace boost;
00026
00027 class BarcodeReaderNode {
00028 std:: string link1_;
00029 std:: string link2_;
00030 std:: string tag1_;
00031 std:: string tag2_;
00032 std:: string tag3_;
00033 std:: string pattern_;
00034 TiXmlDocument doc;
00035 int enable_barcode_reader_;
00036 int image_received_;
00037 int image_found_;
00038 public:
00039 struct memoryStruct {
00040 char *memory;
00041 size_t size;
00042 };
00043
00044 struct UserData {
00045 memoryStruct *memory;
00046 BarcodeReaderNode *self;
00047 UserData(memoryStruct *memory, BarcodeReaderNode *self)
00048 : memory(memory), self(self) {}
00049 };
00050
00051 BarcodeReaderNode(ros::NodeHandle &n) :
00052 n_(n), it_(n_)
00053 {
00054 n_.param ("input_image_topic", input_image_topic_, std::string("/image_raw"));
00055 n_.param ("outout_barcode_topic", output_barcode_topic_, std::string("barcode"));
00056 n_.param ("link1", link1_, std::string("http://www.barcoo.com/api/get_product_complete?pi="));
00057 n_.param ("link2", link2_, std::string("&pins=ean&format=xml&source=ias-tum"));
00058 n_.param ("tag2", tag2_, std::string("picture_high"));
00059 n_.param ("tag3", tag3_, std::string("picture_low"));
00060 n_.param ("image_pattern", pattern_, std::string("<meta property=\"og:image\" content=\""));
00061 image_sub_ = it_.subscribe(
00062 input_image_topic_, 1, &BarcodeReaderNode::imageCallback, this);
00063 barcode_pub_ =
00064 n_.advertise<std_msgs::String>(output_barcode_topic_, 1);
00065 enable_barcode_reader_ = 0;
00066 service_ = n.advertiseService("enable_barcode_reader_service", &BarcodeReaderNode::enable_barcode_reader,this);
00067 image_received_ = 0;
00068 }
00069
00070 ~BarcodeReaderNode()
00071 {
00072 cv::destroyAllWindows();
00073 }
00074
00075 bool enable_barcode_reader(zbar_barcode_reader_node::enable_barcode_reader::Request &req,
00076 zbar_barcode_reader_node::enable_barcode_reader::Response &res )
00077 {
00078 enable_barcode_reader_ = req.enable;
00079 while(!image_received_)
00080 {
00081 sleep(1);
00082 }
00083
00084 if(image_found_)
00085 {
00086 res.title.data = product_title;
00087 res.subtitle.data = product_producer;
00088 res.category_key.data = product_category;
00089
00090 res.image_msg = *ros_image;
00091 enable_barcode_reader_ = 0;
00092 image_received_ = 0;
00093 image_found_ = 0;
00094 enable_barcode_reader_ = 0;
00095
00096 return true;
00097 }
00098 else
00099 {
00100 image_received_ = 0;
00101 enable_barcode_reader_ = 0;
00102 return false;
00103 }
00104 }
00105
00106 static void* CURL_realloc(void *ptr, size_t size)
00107 {
00108
00109
00110 if(ptr)
00111 return realloc(ptr, size);
00112 else
00113 return malloc(size);
00114 }
00115
00116 static size_t WriteMemoryCallback
00117 (void *ptr, size_t size, size_t nmemb, void *data)
00118 {
00119 UserData *userdata = reinterpret_cast<UserData *>(data);
00120 struct memoryStruct *mem = userdata->memory;
00121
00122 size_t realsize = size * nmemb;
00123
00124 mem->memory = (char *)
00125 CURL_realloc(mem->memory, mem->size + realsize + 1);
00126 if (mem->memory) {
00127 memcpy(&(mem->memory[mem->size]), ptr, realsize);
00128 mem->size += realsize;
00129 mem->memory[mem->size] = 0;
00130 }
00131 return realsize;
00132 }
00133
00134
00135 static int writer(char *data, size_t size, size_t nmemb,
00136 std::string *buffer)
00137 {
00138
00139 int result = 0;
00140
00141
00142 if (buffer != NULL)
00143 {
00144
00145 buffer->append(data, size * nmemb);
00146
00147
00148 result = size * nmemb;
00149 }
00150
00151 return result;
00152 }
00153
00154 int getImage(std::string image, cv::Mat * imgTmp)
00155 {
00156 CURL *curl;
00157 CURLcode res;
00158 memoryStruct buffer;
00159 UserData userdata(&buffer, this);
00160
00161 curl = curl_easy_init();
00162
00163 if(curl)
00164 {
00165
00166
00167 buffer.memory = NULL;
00168 buffer.size = 0;
00169
00170
00171 curl_easy_setopt(curl, CURLOPT_URL, image.c_str());
00172 curl_easy_setopt(curl, CURLOPT_VERBOSE, 1);
00173
00174
00175
00176 curl_easy_setopt(curl,CURLOPT_WRITEFUNCTION, &BarcodeReaderNode::WriteMemoryCallback);
00177 curl_easy_setopt(curl,CURLOPT_WRITEDATA, (void *) &userdata);
00178
00179
00180 res = curl_easy_perform(curl);
00181
00182 *imgTmp = cv::imdecode(cv::Mat(1, buffer.size, CV_8UC1, buffer.memory), CV_LOAD_IMAGE_UNCHANGED);
00183
00184
00185 curl_easy_cleanup(curl);
00186 free(buffer.memory);
00187 }
00188 return 1;
00189 }
00190
00191 void findElement( TiXmlNode* pParent, std::string & picture, std:: string tag)
00192 {
00193
00194
00195 TiXmlNode* pChild;
00196 std::string pstring = pParent->Value();
00197
00198
00199 size_t found=pstring.find(tag);
00200 if (found!=std::string::npos)
00201 {
00202 ROS_INFO_STREAM("First child: " << pParent->FirstChild()->Value());
00203 picture = pParent->FirstChild()->Value();
00204 return;
00205 }
00206
00207 for( pChild = pParent->FirstChild(); pChild != 0; pChild = pChild->NextSibling())
00208 {
00209 findElement(pChild, picture,tag);
00210 }
00211 }
00212
00213
00214 int getPictureLink(std::string buffer,std::string & picture)
00215 {
00216 doc.Parse((const char*)buffer.c_str(), 0, TIXML_ENCODING_UTF8);
00217
00218
00219 std:: string result;
00220 findElement(&doc,result,tag1_);
00221 if(result.compare("0") == 0)
00222 {
00223 ROS_INFO_STREAM("Barcode does not correspond to any object in the barcoo database");
00224 return 0;
00225 }
00226
00227
00228 findElement (&doc, picture,tag2_);
00229
00230 if(picture == "")
00231 findElement (&doc, picture,tag3_);
00232
00233 ROS_INFO_STREAM ("Picture link: " << picture);
00234 if (picture == "")
00235 return -1;
00236
00237 return 1;
00238 }
00239
00240
00241 int getBarcooXML(std::string bar_code, std::string & buffer)
00242 {
00243 char errorBuffer[CURL_ERROR_SIZE];
00244
00245 CURL *curl;
00246 CURLcode result;
00247
00248 curl = curl_easy_init();
00249 std::string full_url = link1_ + bar_code + link2_;
00250 ROS_INFO_STREAM("full_url: " << full_url);
00251
00252 if (curl)
00253 {
00254
00255 curl_easy_setopt(curl, CURLOPT_ERRORBUFFER, errorBuffer);
00256 curl_easy_setopt(curl, CURLOPT_URL, full_url.c_str());
00257 curl_easy_setopt(curl, CURLOPT_HEADER, 0);
00258 curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1);
00259 curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, &BarcodeReaderNode::writer);
00260
00261 curl_easy_setopt(curl, CURLOPT_WRITEDATA, &buffer);
00262
00263
00264 result = curl_easy_perform(curl);
00265
00266
00267 curl_easy_cleanup(curl);
00268
00269
00270 if (result == CURLE_OK)
00271 {
00272 ROS_INFO_STREAM ("CURLE_OK");
00273 return 1;
00274 }
00275 else
00276 {
00277 ROS_INFO_STREAM ( "CURLE_NOT OK");
00278 ROS_ERROR_STREAM ("Error: [" << result << "] - " << errorBuffer);
00279 return -1;
00280 }
00281 }
00282 return -1;
00283 }
00284
00285 int getHTMLpage(std::string url, std::string & buffer)
00286 {
00287 char errorBuffer[CURL_ERROR_SIZE];
00288
00289 CURL *curl;
00290 CURLcode result;
00291
00292 curl = curl_easy_init();
00293 if (curl)
00294 {
00295
00296 curl_easy_setopt(curl, CURLOPT_ERRORBUFFER, errorBuffer);
00297 curl_easy_setopt(curl, CURLOPT_URL, url.c_str());
00298 curl_easy_setopt(curl, CURLOPT_HEADER, 0);
00299 curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1);
00300 curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, &BarcodeReaderNode::writer);
00301
00302 curl_easy_setopt(curl, CURLOPT_WRITEDATA, &buffer);
00303
00304
00305 result = curl_easy_perform(curl);
00306
00307
00308 curl_easy_cleanup(curl);
00309
00310
00311 if (result == CURLE_OK)
00312 {
00313
00314 return 1;
00315 }
00316 else
00317 {
00318 return -1;
00319 }
00320 }
00321 return -1;
00322 }
00323
00324 void imageCallback(const sensor_msgs::ImageConstPtr& msg_ptr)
00325 {
00326
00327
00328
00329 ROS_INFO("[BarcodeReaderNode: ] Image received");
00330 try
00331 {
00332 cv_bridge_ptr_ = cv_bridge::toCvCopy(msg_ptr, "mono8");
00333 }
00334 catch (cv_bridge::Exception& e)
00335 {
00336 ROS_ERROR("Error converting ROS Image");
00337 }
00338
00339
00340 ImageScanner scanner;
00341
00342
00343 scanner.set_config(ZBAR_NONE, ZBAR_CFG_ENABLE, 1);
00344
00345 int width = cv_bridge_ptr_->image.cols;
00346 int height = cv_bridge_ptr_->image.rows;
00347
00348
00349 Magick::Blob blob(cv_bridge_ptr_->image.ptr(0), width * height);
00350
00351 const void *raw = blob.data();
00352
00353
00354 Image image(width, height, "Y800", raw, width * height);
00355
00356
00357 int n = scanner.scan(image);
00358
00359
00360 std::stringstream ss;
00361 for(Image::SymbolIterator symbol = image.symbol_begin();
00362 symbol != image.symbol_end();
00363 ++symbol)
00364 {
00365
00366 ROS_INFO_STREAM("Publishing: barcode type: " << symbol->get_type_name()
00367 << " barcode value " << symbol->get_data());
00368
00369 std_msgs::String msg;
00370
00371
00372 ss << symbol->get_data();
00373 msg.data = ss.str();
00374 barcode_pub_.publish(msg);
00375 cv::imwrite("/home/banacer/ros_workspace/yes.jpg",cv_bridge_ptr_->image);
00376 }
00377 if (n == 0)
00378 {
00379 ROS_WARN("Barcode not found");
00380 image_received_ = 1;
00381 return;
00382 }
00383
00384 if (n < 0)
00385 {
00386 ROS_ERROR("Error occured while finding barcode");
00387 image_received_ = 1;
00388 return;
00389 }
00390
00391
00392
00393
00394
00395
00396
00397
00398
00399
00400
00401
00402
00403
00404
00405
00406
00407
00408
00409
00410
00411
00412
00413
00414
00415
00416
00417
00418
00419
00420
00421
00422
00423
00424
00425
00426
00427
00428
00429
00430
00431
00432
00433
00434
00435
00436
00437
00438
00439
00440
00441
00442
00443
00444
00445
00446
00447
00448
00449
00450
00451
00452
00453
00454
00455
00456
00457
00458
00459
00460
00461 }
00462
00463 protected:
00464
00465 ros::NodeHandle n_;
00466 image_transport::ImageTransport it_;
00467 image_transport::Subscriber image_sub_;
00468 ros::Publisher barcode_pub_;
00469 sensor_msgs::CvBridge bridge_;
00470 std::string input_image_topic_, output_barcode_topic_;
00471 sensor_msgs::ImagePtr ros_image;
00472 std::string product_title;
00473 std::string product_producer;
00474 std::string product_category;
00475 ros::ServiceServer service_;
00476 cv_bridge::CvImagePtr cv_bridge_ptr_;
00477 };
00478
00479 int main(int argc, char** argv)
00480 {
00481 ros::init(argc, argv, "barcode_reader_node");
00482 ros::AsyncSpinner spinner(1);
00483 spinner.start();
00484 ros::NodeHandle n("~");
00485 BarcodeReaderNode br(n);
00486 ros::spin();
00487
00488 return 0;
00489 }