zbargui.cpp
Go to the documentation of this file.
00001 #include "zbargui.h"
00002 #include "sensor_msgs/Image.h"
00003 #include "cv_bridge/CvBridge.h"
00004 #include <ros/ros.h>
00005 #include <opencv/highgui.h>
00006 #include "CQTImageConvertor.h"
00007 #include <zbar_barcode_reader_node/enable_barcode_reader.h>
00008 
00009 zbarGui::zbarGui(QWidget *parent) :
00010     QMainWindow(parent)
00011 {
00012     setupUi(this);
00013     uvc_sub = n_.subscribe("/image_raw", 1, &zbarGui::cameraDisplay, this);
00014     connect( pushButton, SIGNAL( clicked() ), this, SLOT( doStart() ));
00015     connect( pushButton_2, SIGNAL( clicked() ), this, SLOT( doQuit() ));
00016 
00017     connect(this, SIGNAL( SIG_updateImage(const IplImage*) ), this, SLOT( SLT_updateImage(const IplImage*) ) );
00018     connect(this, SIGNAL( SIG_updateImage2(const IplImage*) ), this, SLOT( SLT_updateImage2(const IplImage*) ) );
00019      client = n_.serviceClient<zbar_barcode_reader_node::enable_barcode_reader>("/barcode_reader_node/enable_barcode_reader_service");
00020 }
00021 
00022 zbarGui::~zbarGui()
00023 {
00024 
00025 }
00026 
00027 void zbarGui::doStart()
00028 {
00029 
00030           zbar_barcode_reader_node::enable_barcode_reader srv;
00031           srv.request.enable = 1;
00032 
00033           if (client.call(srv))
00034           {
00035                   product_name->setText(QApplication::translate("zbarGui",srv.response.title.data.c_str() , 0, QApplication::UnicodeUTF8));
00036                   product_producer->setText(QApplication::translate("zbarGui",srv.response.subtitle.data.c_str() , 0, QApplication::UnicodeUTF8));
00037                   product_category->setText(QApplication::translate("zbarGui",srv.response.category_key.data.c_str() , 0, QApplication::UnicodeUTF8));
00038                   IplImage* cv_image = NULL;
00039                             try
00040                             {
00041                                   sensor_msgs::ImageConstPtr img_msg_ptr(new sensor_msgs::Image(srv.response.image_msg));
00042                                   cv_image = bridge_.imgMsgToCv(img_msg_ptr, "passthrough");
00043 
00044                             }
00045                             catch (sensor_msgs::CvBridgeException error)
00046                             {
00047                                   ROS_ERROR("error");
00048                             }
00049 
00050                             emit SIG_updateImage2(cv_image);
00051           }
00052           else
00053           {
00054             ROS_ERROR("Failed to call service ");
00055             return;
00056           }
00057 }
00058 
00059 
00060 void zbarGui::doQuit()
00061 {
00062     exit(0);
00063 }
00064 
00065 void zbarGui::cameraDisplay(const sensor_msgs::ImageConstPtr& msg_ptr)
00066 {
00067         IplImage* cv_image = NULL;
00068         try
00069         {
00070                 cv_image = bridge_.imgMsgToCv(msg_ptr, "mono8");
00071         }
00072         catch (sensor_msgs::CvBridgeException error)
00073         {
00074                 ROS_ERROR("error");
00075         }
00076 
00077         emit SIG_updateImage(cv_image);
00078 }
00079 
00080 void zbarGui::SLT_updateImage(const IplImage* pIplImage)
00081 {
00082         QImage *qimg = new QImage(pIplImage->width, pIplImage->height, QImage::Format_RGB32);
00083 
00084         CQTImageConvertor::IplImage2QImage(pIplImage, qimg);
00085 
00086         label->setPixmap(QPixmap::fromImage(*qimg));
00087 
00088         delete qimg;
00089 
00090         label->show();
00091 }
00092 
00093 void zbarGui::SLT_updateImage2(const IplImage* pIplImage)
00094 {
00095         QImage *qimg = new QImage(pIplImage->width, pIplImage->height, QImage::Format_RGB32);
00096 
00097         CQTImageConvertor::IplImage2QImage(pIplImage, qimg);
00098 
00099         //QPixmap q = QPixmap::fromImage(*qimg);
00100         //q = q.scaled ( 251, 271, Qt::IgnoreAspectRatio, Qt::FastTransformation );
00101         std::cerr << "you are hereee\n";
00102 
00103         label_2->setPixmap((QPixmap::fromImage(*qimg)).scaled ( 251, 271, Qt::IgnoreAspectRatio, Qt::FastTransformation ));
00104         std::cerr << "nowwwww\n";
00105         delete qimg;
00106 
00107         label_2->show();
00108 }


zbar_qt_ros
Author(s): banacer
autogenerated on Mon Oct 6 2014 10:57:25