console.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 from rosgraph_msgs.msg import Log
34 import rospkg
35 import rospy
36 
37 from python_qt_binding.QtCore import QMutex, QMutexLocker, QTimer
38 
39 from qt_gui.plugin import Plugin
40 
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
46 
47 
48 class Console(Plugin):
49 
50  """
51  rqt_console plugin's main class. Handles communication with ros_gui and contains
52  callbacks to handle incoming message
53  """
54 
55  def __init__(self, context):
56  """
57  :param context: plugin context hook to enable adding widgets as a ROS_GUI pane,
58  ''PluginContext''
59  """
60  super(Console, self).__init__(context)
61  self.setObjectName('Console')
62 
63  self._rospack = rospkg.RosPack()
64 
65  self._model = MessageDataModel()
66  self._proxy_model = MessageProxyModel()
67  self._proxy_model.setSourceModel(self._model)
68 
69  self._widget = ConsoleWidget(self._proxy_model, self._rospack)
70  if context.serial_number() > 1:
71  self._widget.setWindowTitle(
72  self._widget.windowTitle() + (' (%d)' % context.serial_number()))
73  context.add_widget(self._widget)
74 
75  # queue to store incoming data which get flushed periodically to the model
76  # required since QSortProxyModel can not handle a high insert rate
77  self._message_queue = []
78  self._mutex = QMutex()
79  self._timer = QTimer()
80  self._timer.timeout.connect(self.insert_messages)
81  self._timer.start(100)
82 
83  self._subscriber = None
84  self._topic = '/rosout_agg'
85  self._subscribe(self._topic)
86 
87  def queue_message(self, log_msg):
88  """
89  Callback for adding an incomming message to the queue.
90  """
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)
95 
96  @staticmethod
98  msg = Message()
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)
106  return msg
107 
108  def insert_messages(self):
109  """
110  Callback for flushing incoming Log messages from the queue to the model.
111  """
112  with QMutexLocker(self._mutex):
113  msgs = self._message_queue
114  self._message_queue = []
115  if msgs:
116  self._model.insert_rows(msgs)
117 
118  def shutdown_plugin(self):
119  self._subscriber.unregister()
120  self._timer.stop()
121  self._widget.cleanup_browsers_on_close()
122 
123  def save_settings(self, plugin_settings, instance_settings):
124  self._widget.save_settings(plugin_settings, instance_settings)
125 
126  def restore_settings(self, plugin_settings, instance_settings):
127  self._widget.restore_settings(plugin_settings, instance_settings)
128 
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())
134  if topic != self._topic:
135  self._subscribe(topic)
136  if message_limit != self._model.get_message_limit():
137  self._model.set_message_limit(message_limit)
138 
139  def _subscribe(self, topic):
140  if self._subscriber:
141  self._subscriber.unregister()
142  self._subscriber = rospy.Subscriber(topic, Log, self.queue_message)
143  self._currenttopic = topic
def convert_rosgraph_log_message(log_msg)
Definition: console.py:97
def _subscribe(self, topic)
Definition: console.py:139
def queue_message(self, log_msg)
Definition: console.py:87
def restore_settings(self, plugin_settings, instance_settings)
Definition: console.py:126
def __init__(self, context)
Definition: console.py:55
def save_settings(self, plugin_settings, instance_settings)
Definition: console.py:123
def trigger_configuration(self)
Definition: console.py:129


rqt_console
Author(s): Aaron Blasdel
autogenerated on Wed Jun 5 2019 21:05:12