Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010 from __future__ import division
00011
00012 from python_qt_binding.QtCore import Qt, SIGNAL, pyqtSlot, QRectF
00013 from python_qt_binding.QtGui import QGraphicsView, QGraphicsScene, QPixmap
00014
00015 import os
00016 import rospkg
00017 import sensor_msgs.msg as sensor_msgs
00018
00019
00020
00021
00022
00023
00024 class QCameraView(QGraphicsView):
00025 """
00026 Accepts an image of a teleop compressed image type and draws that in the
00027 scene/view.
00028 """
00029
00030 def __init__(self, parent=None):
00031 super(QCameraView, self).__init__(parent)
00032 self.scene = QGraphicsScene(self)
00033 self.setScene(self.scene)
00034 self._load_default_image()
00035
00036 self.connect(self, SIGNAL("load_default_image"), self._load_default_image)
00037
00038 def _load_default_image(self):
00039 joystick_icon = os.path.join(rospkg.RosPack().get_path('rocon_bubble_icons'), 'icons', 'joystick.png')
00040 pixmap = QPixmap(joystick_icon, format="png")
00041 if self.scene:
00042 self.scene.addPixmap(pixmap)
00043 self.scene.update()
00044 self.fitInView(QRectF(0, 0, self.scene.width(), self.scene.height()), Qt.KeepAspectRatio)
00045
00046 def load_default_image(self):
00047 self.emit(SIGNAL("load_default_image"))
00048
00049 @pyqtSlot(sensor_msgs.CompressedImage, name='image_received')
00050 def on_compressed_image_received(self, image):
00051 '''
00052 :param sensor_msgs.CompressedImage image: convert and display this in the QGraphicsView.
00053 '''
00054 if len(self.scene.items()) > 1:
00055 self.scene.removeItem(self.scene.items()[0])
00056 pixmap = QPixmap()
00057 pixmap.loadFromData(image.data, format=image.format)
00058 self.scene.addPixmap(pixmap)
00059 self.scene.update()
00060
00061 self.fitInView(QRectF(0, 0, self.scene.width(), self.scene.height()), Qt.KeepAspectRatio)
00062
00063 def resizeEvent(self, evt=None):
00064 self.fitInView(QRectF(0, 0, self.scene.width(), self.scene.height()), Qt.KeepAspectRatio)