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 rqt_console plugin's main class. Handles communication with ros_gui and contains
00051 callbacks to handle incoming message
00052 """
00053 def __init__(self, context):
00054 """
00055 :param context: plugin context hook to enable adding widgets as a ROS_GUI pane, ''PluginContext''
00056 """
00057 super(Console, self).__init__(context)
00058 self.setObjectName('Console')
00059
00060 self._rospack = rospkg.RosPack()
00061
00062 self._model = MessageDataModel()
00063 self._proxy_model = MessageProxyModel()
00064 self._proxy_model.setSourceModel(self._model)
00065
00066 self._widget = ConsoleWidget(self._proxy_model, self._rospack)
00067 if context.serial_number() > 1:
00068 self._widget.setWindowTitle(self._widget.windowTitle() + (' (%d)' % context.serial_number()))
00069 context.add_widget(self._widget)
00070
00071
00072
00073 self._message_queue = []
00074 self._mutex = QMutex()
00075 self._timer = QTimer()
00076 self._timer.timeout.connect(self.insert_messages)
00077 self._timer.start(100)
00078
00079 self._subscriber = None
00080 self._topic = '/rosout_agg'
00081 self._subscribe(self._topic)
00082
00083 def queue_message(self, log_msg):
00084 """
00085 Callback for adding an incomming message to the queue.
00086 """
00087 if not self._widget._paused:
00088 msg = Console.convert_rosgraph_log_message(log_msg)
00089 with QMutexLocker(self._mutex):
00090 self._message_queue.append(msg)
00091
00092 @staticmethod
00093 def convert_rosgraph_log_message(log_msg):
00094 msg = Message()
00095 msg.set_stamp_format('hh:mm:ss.ZZZ (yyyy-MM-dd)')
00096 msg.message = log_msg.msg
00097 msg.severity = log_msg.level
00098 msg.node = log_msg.name
00099 msg.stamp = (log_msg.header.stamp.secs, log_msg.header.stamp.nsecs)
00100 msg.topics = sorted(log_msg.topics)
00101 msg.location = log_msg.file + ':' + log_msg.function + ':' + str(log_msg.line)
00102 return msg
00103
00104 def insert_messages(self):
00105 """
00106 Callback for flushing incoming Log messages from the queue to the model.
00107 """
00108 with QMutexLocker(self._mutex):
00109 msgs = self._message_queue
00110 self._message_queue = []
00111 if msgs:
00112 self._model.insert_rows(msgs)
00113
00114 def shutdown_plugin(self):
00115 self._subscriber.unregister()
00116 self._timer.stop()
00117 self._widget.cleanup_browsers_on_close()
00118
00119 def save_settings(self, plugin_settings, instance_settings):
00120 self._widget.save_settings(plugin_settings, instance_settings)
00121
00122 def restore_settings(self, plugin_settings, instance_settings):
00123 self._widget.restore_settings(plugin_settings, instance_settings)
00124
00125 def trigger_configuration(self):
00126 topics = [t for t in rospy.get_published_topics() if t[1] == 'rosgraph_msgs/Log']
00127 topics.sort(key=lambda tup: tup[0])
00128 dialog = ConsoleSettingsDialog(topics, self._rospack)
00129 (topic, message_limit) = dialog.query(self._topic, self._model.get_message_limit())
00130 if topic != self._topic:
00131 self._subscribe(topic)
00132 if message_limit != self._model.get_message_limit():
00133 self._model.set_message_limit(message_limit)
00134
00135 def _subscribe(self, topic):
00136 if self._subscriber:
00137 self._subscriber.unregister()
00138 self._subscriber = rospy.Subscriber(topic, Log, self.queue_message)
00139 self._currenttopic = topic