33 from rosgraph_msgs.msg
import Log
37 from python_qt_binding.QtCore
import QMutex, QMutexLocker, QTimer
41 from .console_settings_dialog
import ConsoleSettingsDialog
42 from .console_widget
import ConsoleWidget
43 from .message
import Message
44 from .message_data_model
import MessageDataModel
45 from .message_proxy_model
import MessageProxyModel
51 rqt_console plugin's main class. Handles communication with ros_gui and contains 52 callbacks to handle incoming message 57 :param context: plugin context hook to enable adding widgets as a ROS_GUI pane, 60 super(Console, self).
__init__(context)
61 self.setObjectName(
'Console')
67 self._proxy_model.setSourceModel(self.
_model)
70 if context.serial_number() > 1:
71 self._widget.setWindowTitle(
72 self._widget.windowTitle() + (
' (%d)' % context.serial_number()))
73 context.add_widget(self.
_widget)
81 self._timer.start(100)
89 Callback for adding an incomming message to the queue. 91 if not self._widget._paused:
92 msg = Console.convert_rosgraph_log_message(log_msg)
93 with QMutexLocker(self.
_mutex):
94 self._message_queue.append(msg)
99 msg.set_stamp_format(
'hh:mm:ss.ZZZ (yyyy-MM-dd)')
100 msg.message = log_msg.msg
101 msg.severity = log_msg.level
102 msg.node = log_msg.name
103 msg.stamp = (log_msg.header.stamp.secs, log_msg.header.stamp.nsecs)
104 msg.topics = sorted(log_msg.topics)
105 msg.location = log_msg.file +
':' + log_msg.function +
':' + str(log_msg.line)
110 Callback for flushing incoming Log messages from the queue to the model. 112 with QMutexLocker(self.
_mutex):
116 self._model.insert_rows(msgs)
119 self._subscriber.unregister()
121 self._widget.cleanup_browsers_on_close()
124 self._widget.save_settings(plugin_settings, instance_settings)
127 self._widget.restore_settings(plugin_settings, instance_settings)
130 topics = [t
for t
in rospy.get_published_topics()
if t[1] ==
'rosgraph_msgs/Log']
131 topics.sort(key=
lambda tup: tup[0])
132 dialog = ConsoleSettingsDialog(topics, self.
_rospack)
133 (topic, message_limit) = dialog.query(self.
_topic, self._model.get_message_limit())
136 if message_limit != self._model.get_message_limit():
137 self._model.set_message_limit(message_limit)
141 self._subscriber.unregister()
def convert_rosgraph_log_message(log_msg)
def _subscribe(self, topic)
def queue_message(self, log_msg)
def shutdown_plugin(self)
def restore_settings(self, plugin_settings, instance_settings)
def __init__(self, context)
def insert_messages(self)
def save_settings(self, plugin_settings, instance_settings)
def trigger_configuration(self)