Classes | |
struct | memoryStruct |
struct | UserData |
Public Member Functions | |
BarcodeReaderNode (ros::NodeHandle &n) | |
bool | enable_barcode_reader (zbar_barcode_reader_node::enable_barcode_reader::Request &req, zbar_barcode_reader_node::enable_barcode_reader::Response &res) |
void | findElement (TiXmlNode *pParent, std::string &picture, std::string tag) |
int | getBarcooXML (std::string bar_code, std::string &buffer) |
int | getHTMLpage (std::string url, std::string &buffer) |
int | getImage (std::string image, cv::Mat *imgTmp) |
int | getPictureLink (std::string buffer, std::string &picture) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg_ptr) |
~BarcodeReaderNode () | |
Static Public Member Functions | |
static void * | CURL_realloc (void *ptr, size_t size) |
static size_t | WriteMemoryCallback (void *ptr, size_t size, size_t nmemb, void *data) |
static int | writer (char *data, size_t size, size_t nmemb, std::string *buffer) |
Protected Attributes | |
ros::Publisher | barcode_pub_ |
sensor_msgs::CvBridge | bridge_ |
cv_bridge::CvImagePtr | cv_bridge_ptr_ |
image_transport::Subscriber | image_sub_ |
std::string | input_image_topic_ |
image_transport::ImageTransport | it_ |
ros::NodeHandle | n_ |
std::string | output_barcode_topic_ |
std::string | product_category |
std::string | product_producer |
std::string | product_title |
sensor_msgs::ImagePtr | ros_image |
ros::ServiceServer | service_ |
Private Attributes | |
TiXmlDocument | doc |
int | enable_barcode_reader_ |
int | image_found_ |
int | image_received_ |
std::string | link1_ |
std::string | link2_ |
std::string | pattern_ |
std::string | tag1_ |
std::string | tag2_ |
std::string | tag3_ |
Definition at line 27 of file zbar_barcode_reader_node.cpp.
BarcodeReaderNode::BarcodeReaderNode | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 51 of file zbar_barcode_reader_node.cpp.
BarcodeReaderNode::~BarcodeReaderNode | ( | ) | [inline] |
Definition at line 70 of file zbar_barcode_reader_node.cpp.
static void* BarcodeReaderNode::CURL_realloc | ( | void * | ptr, |
size_t | size | ||
) | [inline, static] |
Definition at line 106 of file zbar_barcode_reader_node.cpp.
bool BarcodeReaderNode::enable_barcode_reader | ( | zbar_barcode_reader_node::enable_barcode_reader::Request & | req, |
zbar_barcode_reader_node::enable_barcode_reader::Response & | res | ||
) | [inline] |
Definition at line 75 of file zbar_barcode_reader_node.cpp.
void BarcodeReaderNode::findElement | ( | TiXmlNode * | pParent, |
std::string & | picture, | ||
std::string | tag | ||
) | [inline] |
Definition at line 191 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::getBarcooXML | ( | std::string | bar_code, |
std::string & | buffer | ||
) | [inline] |
Definition at line 241 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::getHTMLpage | ( | std::string | url, |
std::string & | buffer | ||
) | [inline] |
Definition at line 285 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::getImage | ( | std::string | image, |
cv::Mat * | imgTmp | ||
) | [inline] |
Definition at line 154 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::getPictureLink | ( | std::string | buffer, |
std::string & | picture | ||
) | [inline] |
Definition at line 214 of file zbar_barcode_reader_node.cpp.
void BarcodeReaderNode::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) | [inline] |
Definition at line 324 of file zbar_barcode_reader_node.cpp.
static size_t BarcodeReaderNode::WriteMemoryCallback | ( | void * | ptr, |
size_t | size, | ||
size_t | nmemb, | ||
void * | data | ||
) | [inline, static] |
Definition at line 117 of file zbar_barcode_reader_node.cpp.
static int BarcodeReaderNode::writer | ( | char * | data, |
size_t | size, | ||
size_t | nmemb, | ||
std::string * | buffer | ||
) | [inline, static] |
Definition at line 135 of file zbar_barcode_reader_node.cpp.
ros::Publisher BarcodeReaderNode::barcode_pub_ [protected] |
Definition at line 468 of file zbar_barcode_reader_node.cpp.
sensor_msgs::CvBridge BarcodeReaderNode::bridge_ [protected] |
Definition at line 469 of file zbar_barcode_reader_node.cpp.
Definition at line 476 of file zbar_barcode_reader_node.cpp.
TiXmlDocument BarcodeReaderNode::doc [private] |
Definition at line 34 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::enable_barcode_reader_ [private] |
Definition at line 35 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::image_found_ [private] |
Definition at line 37 of file zbar_barcode_reader_node.cpp.
int BarcodeReaderNode::image_received_ [private] |
Definition at line 36 of file zbar_barcode_reader_node.cpp.
Definition at line 467 of file zbar_barcode_reader_node.cpp.
std::string BarcodeReaderNode::input_image_topic_ [protected] |
Definition at line 470 of file zbar_barcode_reader_node.cpp.
Definition at line 466 of file zbar_barcode_reader_node.cpp.
std:: string BarcodeReaderNode::link1_ [private] |
Definition at line 28 of file zbar_barcode_reader_node.cpp.
std:: string BarcodeReaderNode::link2_ [private] |
Definition at line 29 of file zbar_barcode_reader_node.cpp.
ros::NodeHandle BarcodeReaderNode::n_ [protected] |
Definition at line 465 of file zbar_barcode_reader_node.cpp.
std::string BarcodeReaderNode::output_barcode_topic_ [protected] |
Definition at line 470 of file zbar_barcode_reader_node.cpp.
std:: string BarcodeReaderNode::pattern_ [private] |
Definition at line 33 of file zbar_barcode_reader_node.cpp.
std::string BarcodeReaderNode::product_category [protected] |
Definition at line 474 of file zbar_barcode_reader_node.cpp.
std::string BarcodeReaderNode::product_producer [protected] |
Definition at line 473 of file zbar_barcode_reader_node.cpp.
std::string BarcodeReaderNode::product_title [protected] |
Definition at line 472 of file zbar_barcode_reader_node.cpp.
sensor_msgs::ImagePtr BarcodeReaderNode::ros_image [protected] |
Definition at line 471 of file zbar_barcode_reader_node.cpp.
ros::ServiceServer BarcodeReaderNode::service_ [protected] |
Definition at line 475 of file zbar_barcode_reader_node.cpp.
std:: string BarcodeReaderNode::tag1_ [private] |
Definition at line 30 of file zbar_barcode_reader_node.cpp.
std:: string BarcodeReaderNode::tag2_ [private] |
Definition at line 31 of file zbar_barcode_reader_node.cpp.
std:: string BarcodeReaderNode::tag3_ [private] |
Definition at line 32 of file zbar_barcode_reader_node.cpp.