qt_listener.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # License: BSD
00004 #   https://raw.github.com/robotics-in-concert/rocon_tutorials/license/LICENSE
00005 #
00006 """
00007   A simple pyqt listener
00008 """
00009 ##############################################################################
00010 # Imports
00011 ##############################################################################
00012 
00013 import sys
00014 import signal
00015 import rocon_console.console as console
00016 
00017 try:
00018     from PyQt4 import QtCore, QtGui
00019 except ImportError:
00020     print(console.red + "[ERROR] : this app requires you to pre-install pyqt modules." + console.reset)
00021     sys.exit(1)
00022 
00023 import rospy
00024 import std_msgs.msg as std_msgs
00025 import rocon_python_utils
00026 import time
00027 
00028 ##############################################################################
00029 # Classes
00030 ##############################################################################
00031 
00032 
00033 class Window(QtGui.QWidget):
00034 
00035     def __init__(self):
00036         super(Window, self).__init__()
00037         self._icon = rocon_python_utils.ros.find_resource_from_string('rocon_bubble_icons/rocon.png')
00038         self.initUI()
00039 
00040     def initUI(self):
00041         self._list_view = QtGui.QListWidget(self)
00042         self._list_view.resize(400, 400)
00043 
00044         self.setWindowTitle("Qt Listener")
00045         self.setWindowIcon(QtGui.QIcon(self._icon))
00046         self.putUnderMouse()
00047 
00048     def putUnderMouse(self):
00049         mouse = QtGui.QCursor.pos()
00050         self.move(mouse.x() - self._list_view.geometry().width() / 2, mouse.y() - self._list_view.geometry().height() / 2)
00051 
00052     def listener(self, data):
00053         QtGui.QListWidgetItem("I heard %s" % data.data, self._list_view)
00054         self._list_view.scrollToBottom()
00055         #rospy.loginfo(rospy.get_name() + ": I heard %s" % data.data)
00056 
00057 
00058 def shutdown(signal_number, unused_frame):
00059     """
00060     We have to catch any SIGINT's before the qt engine catches them
00061     because we have to ensure we shut down gracefully with ros so that
00062     it doesn't leave a zombie node on the ros master.
00063 
00064     Other signals are ok, qt handles them.
00065     """
00066     app.exit()
00067     # this will let the rest of the main code to run its course
00068 
00069 
00070 ##############################################################################
00071 # Main
00072 ##############################################################################
00073 
00074 if __name__ == '__main__':
00075     rospy.init_node('listener', anonymous=True, disable_signals=True)
00076 
00077     #signal.signal(signal.SIGINT, signal.SIG_DFL)  # make sure this comes after the rospy call, otherwise it will handle signals.
00078     signal.signal(signal.SIGINT, shutdown)  # make sure this comes after the rospy call, otherwise it will handle signals.
00079     app = QtGui.QApplication(sys.argv)
00080     window = Window()
00081     window.show()
00082     time.sleep(0.5)  # funny, qt window disappears from focus without this.
00083     rospy.Subscriber('chatter', std_msgs.String, window.listener)
00084 
00085     # Forces the qt main loop to stop for a while and let the python interpreter run some code
00086     # see http://stackoverflow.com/questions/4938723/what-is-the-correct-way-to-make-my-pyqt-application-quit-when-killed-from-the-co
00087     timer = QtCore.QTimer()
00088     timer.start(500)  # trigger a timeout periodically (ms)
00089     timer.timeout.connect(lambda: None)  # Let the interpreter run each 500 ms.
00090     result = app.exec_()
00091     rospy.signal_shutdown("manual shutdown of a pyqt program")
00092     sys.exit(result)


rocon_qt_listener
Author(s): Daniel Stonier
autogenerated on Fri Feb 12 2016 02:50:14