image_play.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2016 PAL Robotics SL. All Rights Reserved
00004 #
00005 # Permission to use, copy, modify, and/or distribute this software for
00006 # any purpose with or without fee is hereby granted, provided that the
00007 # above copyright notice and this permission notice appear in all
00008 # copies.
00009 #
00010 # THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
00011 # WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
00012 # MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
00013 # ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
00014 # WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
00015 # ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
00016 # OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
00017 #
00018 # Author:
00019 #   * Sammy Pfeiffer
00020 
00021 from PyQt4 import QtGui, QtCore
00022 import rospy
00023 from sensor_msgs.msg import CompressedImage
00024 
00025 
00026 class Main(QtGui.QMainWindow):
00027 
00028     def __init__(self, parent=None):
00029         super(Main, self).__init__(parent)
00030         self.image_label = QtGui.QLabel()
00031         self.image_label.resize(640, 480)
00032         self.pixmap = QtGui.QPixmap()
00033 
00034         self.layout = QtGui.QHBoxLayout()
00035         self.layout.addWidget(self.image_label)
00036         self.central_widget = QtGui.QWidget()
00037         self.central_widget.setLayout(self.layout)
00038         self.setCentralWidget(self.central_widget)
00039 
00040         self.last_msg = None
00041         self.image_sub = rospy.Subscriber('/xtion/rgb/image_raw/compressed',
00042                                           CompressedImage,
00043                                           self.image_cb,
00044                                           queue_size=1)
00045         rospy.loginfo(
00046             "Subscribed to: '" + str(self.image_sub.resolved_name) + "' topic.")
00047 
00048         # Use Qt timers to fire up the update of image
00049         # as the ROS callback is in another thread and we can't do it from there
00050         self.timer = QtCore.QTimer()
00051         self.timer.timeout.connect(self.show_image)
00052         self.timer.start(1.0 / 30.0)  # show 30hz image
00053 
00054     def image_cb(self, msg):
00055         self.last_msg = msg
00056 
00057     def show_image(self):
00058         if self.last_msg is not None:
00059             self.pixmap.loadFromData(self.last_msg.data)
00060             self.image_label.setPixmap(self.pixmap)
00061             self.image_label.adjustSize()
00062 
00063 if __name__ == '__main__':
00064     rospy.init_node('image_play')
00065     app = QtGui.QApplication(["image_play window"])
00066     myWidget = Main()
00067     myWidget.show()
00068     app.exec_()


play_with_sensors
Author(s):
autogenerated on Fri Aug 26 2016 13:20:19