Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 from rosgraph_msgs.msg import Log
00034 import rospkg
00035 import rospy
00036
00037 from python_qt_binding.QtCore import QMutex, QMutexLocker, QTimer
00038
00039 from qt_gui.plugin import Plugin
00040
00041 from .console_settings_dialog import ConsoleSettingsDialog
00042 from .console_widget import ConsoleWidget
00043 from .message import Message
00044 from .message_data_model import MessageDataModel
00045 from .message_proxy_model import MessageProxyModel
00046
00047
00048 class Console(Plugin):
00049
00050 """
00051 rqt_console plugin's main class. Handles communication with ros_gui and contains
00052 callbacks to handle incoming message
00053 """
00054
00055 def __init__(self, context):
00056 """
00057 :param context: plugin context hook to enable adding widgets as a ROS_GUI pane,
00058 ''PluginContext''
00059 """
00060 super(Console, self).__init__(context)
00061 self.setObjectName('Console')
00062
00063 self._rospack = rospkg.RosPack()
00064
00065 self._model = MessageDataModel()
00066 self._proxy_model = MessageProxyModel()
00067 self._proxy_model.setSourceModel(self._model)
00068
00069 self._widget = ConsoleWidget(self._proxy_model, self._rospack)
00070 if context.serial_number() > 1:
00071 self._widget.setWindowTitle(
00072 self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00073 context.add_widget(self._widget)
00074
00075
00076
00077 self._message_queue = []
00078 self._mutex = QMutex()
00079 self._timer = QTimer()
00080 self._timer.timeout.connect(self.insert_messages)
00081 self._timer.start(100)
00082
00083 self._subscriber = None
00084 self._topic = '/rosout_agg'
00085 self._subscribe(self._topic)
00086
00087 def queue_message(self, log_msg):
00088 """
00089 Callback for adding an incomming message to the queue.
00090 """
00091 if not self._widget._paused:
00092 msg = Console.convert_rosgraph_log_message(log_msg)
00093 with QMutexLocker(self._mutex):
00094 self._message_queue.append(msg)
00095
00096 @staticmethod
00097 def convert_rosgraph_log_message(log_msg):
00098 msg = Message()
00099 msg.set_stamp_format('hh:mm:ss.ZZZ (yyyy-MM-dd)')
00100 msg.message = log_msg.msg
00101 msg.severity = log_msg.level
00102 msg.node = log_msg.name
00103 msg.stamp = (log_msg.header.stamp.secs, log_msg.header.stamp.nsecs)
00104 msg.topics = sorted(log_msg.topics)
00105 msg.location = log_msg.file + ':' + log_msg.function + ':' + str(log_msg.line)
00106 return msg
00107
00108 def insert_messages(self):
00109 """
00110 Callback for flushing incoming Log messages from the queue to the model.
00111 """
00112 with QMutexLocker(self._mutex):
00113 msgs = self._message_queue
00114 self._message_queue = []
00115 if msgs:
00116 self._model.insert_rows(msgs)
00117
00118 def shutdown_plugin(self):
00119 self._subscriber.unregister()
00120 self._timer.stop()
00121 self._widget.cleanup_browsers_on_close()
00122
00123 def save_settings(self, plugin_settings, instance_settings):
00124 self._widget.save_settings(plugin_settings, instance_settings)
00125
00126 def restore_settings(self, plugin_settings, instance_settings):
00127 self._widget.restore_settings(plugin_settings, instance_settings)
00128
00129 def trigger_configuration(self):
00130 topics = [t for t in rospy.get_published_topics() if t[1] == 'rosgraph_msgs/Log']
00131 topics.sort(key=lambda tup: tup[0])
00132 dialog = ConsoleSettingsDialog(topics, self._rospack)
00133 (topic, message_limit) = dialog.query(self._topic, self._model.get_message_limit())
00134 if topic != self._topic:
00135 self._subscribe(topic)
00136 if message_limit != self._model.get_message_limit():
00137 self._model.set_message_limit(message_limit)
00138
00139 def _subscribe(self, topic):
00140 if self._subscriber:
00141 self._subscriber.unregister()
00142 self._subscriber = rospy.Subscriber(topic, Log, self.queue_message)
00143 self._currenttopic = topic