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 __future__ import division
00034 import os
00035
00036 from python_qt_binding import loadUi
00037 from python_qt_binding.QtCore import Qt, QTimer, Signal, Slot
00038 from python_qt_binding.QtGui import QIcon
00039 from python_qt_binding.QtWidgets import QHeaderView, QMenu, QTreeWidgetItem, QWidget
00040 import roslib
00041 import rospkg
00042 import rospy
00043 from rospy.exceptions import ROSException
00044
00045 from .topic_info import TopicInfo
00046
00047
00048 class TopicWidget(QWidget):
00049 """
00050 main class inherits from the ui window class.
00051
00052 You can specify the topics that the topic pane.
00053
00054 TopicWidget.start must be called in order to update topic pane.
00055 """
00056
00057 SELECT_BY_NAME = 0
00058 SELECT_BY_MSGTYPE = 1
00059
00060 _column_names = ['topic', 'type', 'bandwidth', 'rate', 'value']
00061
00062 def __init__(self, plugin=None, selected_topics=None, select_topic_type=SELECT_BY_NAME):
00063 """
00064 @type selected_topics: list of tuples.
00065 @param selected_topics: [($NAME_TOPIC$, $TYPE_TOPIC$), ...]
00066 @type select_topic_type: int
00067 @param select_topic_type: Can specify either the name of topics or by
00068 the type of topic, to filter the topics to
00069 show. If 'select_topic_type' argument is
00070 None, this arg shouldn't be meaningful.
00071 """
00072 super(TopicWidget, self).__init__()
00073
00074 self._select_topic_type = select_topic_type
00075
00076 rp = rospkg.RosPack()
00077 ui_file = os.path.join(rp.get_path('rqt_topic'), 'resource', 'TopicWidget.ui')
00078 loadUi(ui_file, self)
00079 self._plugin = plugin
00080 self.topics_tree_widget.sortByColumn(0, Qt.AscendingOrder)
00081 header = self.topics_tree_widget.header()
00082 try:
00083 setSectionResizeMode = header.setSectionResizeMode
00084 except AttributeError:
00085 setSectionResizeMode = header.setResizeMode
00086 setSectionResizeMode(QHeaderView.ResizeToContents)
00087 header.customContextMenuRequested.connect(self.handle_header_view_customContextMenuRequested)
00088 header.setContextMenuPolicy(Qt.CustomContextMenu)
00089
00090
00091
00092 self._selected_topics = selected_topics
00093
00094 self._current_topic_list = []
00095 self._topics = {}
00096 self._tree_items = {}
00097 self._column_index = {}
00098 for column_name in self._column_names:
00099 self._column_index[column_name] = len(self._column_index)
00100
00101
00102
00103
00104 self._timer_refresh_topics = QTimer(self)
00105 self._timer_refresh_topics.timeout.connect(self.refresh_topics)
00106
00107 def set_topic_specifier(self, specifier):
00108 self._select_topic_type = specifier
00109
00110 def start(self):
00111 """
00112 This method needs to be called to start updating topic pane.
00113 """
00114 self._timer_refresh_topics.start(1000)
00115
00116 @Slot()
00117 def refresh_topics(self):
00118 """
00119 refresh tree view items
00120 """
00121 try:
00122 if self._selected_topics is None:
00123 topic_list = rospy.get_published_topics()
00124 if topic_list is None:
00125 rospy.logerr('Not even a single published topic found. Check network configuration')
00126 return
00127 else:
00128 topic_list = self._selected_topics
00129 topic_specifiers_server_all = None
00130 topic_specifiers_required = None
00131
00132 rospy.logdebug('refresh_topics) self._selected_topics=%s' % (topic_list,))
00133
00134 if self._select_topic_type == self.SELECT_BY_NAME:
00135 topic_specifiers_server_all = [name for name, type in rospy.get_published_topics()]
00136 topic_specifiers_required = [name for name, type in topic_list]
00137 elif self._select_topic_type == self.SELECT_BY_MSGTYPE:
00138
00139 topic_specifiers_required = [type for name, type in topic_list]
00140
00141
00142 topics_match = [(name, type) for name, type in rospy.get_published_topics() if type in topic_specifiers_required]
00143 topic_list = topics_match
00144 rospy.logdebug('selected & published topic types=%s' % (topic_list,))
00145
00146 rospy.logdebug('server_all=%s\nrequired=%s\ntlist=%s' % (topic_specifiers_server_all, topic_specifiers_required, topic_list))
00147 if len(topic_list) == 0:
00148 rospy.logerr('None of the following required topics are found.\n(NAME, TYPE): %s' % (self._selected_topics,))
00149 return
00150 except IOError as e:
00151 rospy.logerr("Communication with rosmaster failed: {0}".format(e.strerror))
00152 return
00153
00154 if self._current_topic_list != topic_list:
00155 self._current_topic_list = topic_list
00156
00157
00158 new_topics = {}
00159
00160 for topic_name, topic_type in topic_list:
00161
00162 if topic_name not in self._topics or \
00163 self._topics[topic_name]['type'] != topic_type:
00164
00165 topic_info = TopicInfo(topic_name, topic_type)
00166 message_instance = None
00167 if topic_info.message_class is not None:
00168 message_instance = topic_info.message_class()
00169
00170 topic_item = self._recursive_create_widget_items(self.topics_tree_widget, topic_name, topic_type, message_instance)
00171 new_topics[topic_name] = {
00172 'item': topic_item,
00173 'info': topic_info,
00174 'type': topic_type,
00175 }
00176 else:
00177
00178
00179 new_topics[topic_name] = self._topics[topic_name]
00180 del self._topics[topic_name]
00181
00182
00183 for topic_name in self._topics.keys():
00184 self._topics[topic_name]['info'].stop_monitoring()
00185 index = self.topics_tree_widget.indexOfTopLevelItem(
00186 self._topics[topic_name]['item'])
00187 self.topics_tree_widget.takeTopLevelItem(index)
00188 del self._topics[topic_name]
00189
00190
00191 self._topics = new_topics
00192
00193 self._update_topics_data()
00194
00195 def _update_topics_data(self):
00196 for topic in self._topics.values():
00197 topic_info = topic['info']
00198 if topic_info.monitoring:
00199
00200 rate, _, _, _ = topic_info.get_hz()
00201 rate_text = '%1.2f' % rate if rate != None else 'unknown'
00202
00203
00204 bytes_per_s, _, _, _ = topic_info.get_bw()
00205 if bytes_per_s is None:
00206 bandwidth_text = 'unknown'
00207 elif bytes_per_s < 1000:
00208 bandwidth_text = '%.2fB/s' % bytes_per_s
00209 elif bytes_per_s < 1000000:
00210 bandwidth_text = '%.2fKB/s' % (bytes_per_s / 1000.)
00211 else:
00212 bandwidth_text = '%.2fMB/s' % (bytes_per_s / 1000000.)
00213
00214
00215 value_text = ''
00216 self.update_value(topic_info._topic_name, topic_info.last_message)
00217
00218 else:
00219 rate_text = ''
00220 bandwidth_text = ''
00221 value_text = 'not monitored' if topic_info.error is None else topic_info.error
00222
00223 self._tree_items[topic_info._topic_name].setText(self._column_index['rate'], rate_text)
00224 self._tree_items[topic_info._topic_name].setText(self._column_index['bandwidth'], bandwidth_text)
00225 self._tree_items[topic_info._topic_name].setText(self._column_index['value'], value_text)
00226
00227 def update_value(self, topic_name, message):
00228 if hasattr(message, '__slots__') and hasattr(message, '_slot_types'):
00229 for slot_name in message.__slots__:
00230 self.update_value(topic_name + '/' + slot_name, getattr(message, slot_name))
00231
00232 elif type(message) in (list, tuple) and (len(message) > 0) and hasattr(message[0], '__slots__'):
00233
00234 for index, slot in enumerate(message):
00235 if topic_name + '[%d]' % index in self._tree_items:
00236 self.update_value(topic_name + '[%d]' % index, slot)
00237 else:
00238 base_type_str, _ = self._extract_array_info(self._tree_items[topic_name].text(self._column_index['type']))
00239 self._recursive_create_widget_items(self._tree_items[topic_name], topic_name + '[%d]' % index, base_type_str, slot)
00240
00241 if len(message) < self._tree_items[topic_name].childCount():
00242 for i in range(len(message), self._tree_items[topic_name].childCount()):
00243 item_topic_name = topic_name + '[%d]' % i
00244 self._recursive_delete_widget_items(self._tree_items[item_topic_name])
00245 else:
00246 if topic_name in self._tree_items:
00247 self._tree_items[topic_name].setText(self._column_index['value'], repr(message))
00248
00249 def _extract_array_info(self, type_str):
00250 array_size = None
00251 if '[' in type_str and type_str[-1] == ']':
00252 type_str, array_size_str = type_str.split('[', 1)
00253 array_size_str = array_size_str[:-1]
00254 if len(array_size_str) > 0:
00255 array_size = int(array_size_str)
00256 else:
00257 array_size = 0
00258
00259 return type_str, array_size
00260
00261 def _recursive_create_widget_items(self, parent, topic_name, type_name, message):
00262 if parent is self.topics_tree_widget:
00263
00264 topic_text = topic_name
00265 item = TreeWidgetItem(self._toggle_monitoring, topic_name, parent)
00266 else:
00267 topic_text = topic_name.split('/')[-1]
00268 if '[' in topic_text:
00269 topic_text = topic_text[topic_text.index('['):]
00270 item = QTreeWidgetItem(parent)
00271 item.setText(self._column_index['topic'], topic_text)
00272 item.setText(self._column_index['type'], type_name)
00273 item.setData(0, Qt.UserRole, topic_name)
00274 self._tree_items[topic_name] = item
00275 if hasattr(message, '__slots__') and hasattr(message, '_slot_types'):
00276 for slot_name, type_name in zip(message.__slots__, message._slot_types):
00277 self._recursive_create_widget_items(item, topic_name + '/' + slot_name, type_name, getattr(message, slot_name))
00278
00279 else:
00280 base_type_str, array_size = self._extract_array_info(type_name)
00281 try:
00282 base_instance = roslib.message.get_message_class(base_type_str)()
00283 except (ValueError, TypeError):
00284 base_instance = None
00285 if array_size is not None and hasattr(base_instance, '__slots__'):
00286 for index in range(array_size):
00287 self._recursive_create_widget_items(item, topic_name + '[%d]' % index, base_type_str, base_instance)
00288 return item
00289
00290 def _toggle_monitoring(self, topic_name):
00291 item = self._tree_items[topic_name]
00292 if item.checkState(0):
00293 self._topics[topic_name]['info'].start_monitoring()
00294 else:
00295 self._topics[topic_name]['info'].stop_monitoring()
00296
00297 def _recursive_delete_widget_items(self, item):
00298 def _recursive_remove_items_from_tree(item):
00299 for index in reversed(range(item.childCount())):
00300 _recursive_remove_items_from_tree(item.child(index))
00301 topic_name = item.data(0, Qt.UserRole)
00302 del self._tree_items[topic_name]
00303 _recursive_remove_items_from_tree(item)
00304 item.parent().removeChild(item)
00305
00306 @Slot('QPoint')
00307 def handle_header_view_customContextMenuRequested(self, pos):
00308 header = self.topics_tree_widget.header()
00309
00310
00311 menu = QMenu(self)
00312 action_toggle_auto_resize = menu.addAction('Toggle Auto-Resize')
00313 action = menu.exec_(header.mapToGlobal(pos))
00314
00315
00316 if action is action_toggle_auto_resize:
00317 if header.resizeMode(0) == QHeaderView.ResizeToContents:
00318 header.setResizeMode(QHeaderView.Interactive)
00319 else:
00320 header.setResizeMode(QHeaderView.ResizeToContents)
00321
00322 @Slot('QPoint')
00323 def on_topics_tree_widget_customContextMenuRequested(self, pos):
00324 item = self.topics_tree_widget.itemAt(pos)
00325 if item is None:
00326 return
00327
00328
00329 menu = QMenu(self)
00330 action_item_expand = menu.addAction(QIcon.fromTheme('zoom-in'), 'Expand All Children')
00331 action_item_collapse = menu.addAction(QIcon.fromTheme('zoom-out'), 'Collapse All Children')
00332 action = menu.exec_(self.topics_tree_widget.mapToGlobal(pos))
00333
00334
00335 if action in (action_item_expand, action_item_collapse):
00336 expanded = (action is action_item_expand)
00337
00338 def recursive_set_expanded(item):
00339 item.setExpanded(expanded)
00340 for index in range(item.childCount()):
00341 recursive_set_expanded(item.child(index))
00342 recursive_set_expanded(item)
00343
00344 def shutdown_plugin(self):
00345 for topic in self._topics.values():
00346 topic['info'].stop_monitoring()
00347 self._timer_refresh_topics.stop()
00348
00349 def set_selected_topics(self, selected_topics):
00350 """
00351 @param selected_topics: list of tuple. [(topic_name, topic_type)]
00352 @type selected_topics: []
00353 """
00354 rospy.logdebug('set_selected_topics topics={}'.format(
00355 len(selected_topics)))
00356 self._selected_topics = selected_topics
00357
00358
00359 def save_settings(self, plugin_settings, instance_settings):
00360 header_state = self.topics_tree_widget.header().saveState()
00361 instance_settings.set_value('tree_widget_header_state', header_state)
00362
00363 def restore_settings(self, pluggin_settings, instance_settings):
00364 if instance_settings.contains('tree_widget_header_state'):
00365 header_state = instance_settings.value('tree_widget_header_state')
00366 if not self.topics_tree_widget.header().restoreState(header_state):
00367 rospy.logwarn("rqt_topic: Failed to restore header state.")
00368
00369 class TreeWidgetItem(QTreeWidgetItem):
00370
00371 def __init__(self, check_state_changed_callback, topic_name, parent=None):
00372 super(TreeWidgetItem, self).__init__(parent)
00373 self._check_state_changed_callback = check_state_changed_callback
00374 self._topic_name = topic_name
00375 self.setCheckState(0, Qt.Unchecked)
00376
00377 def setData(self, column, role, value):
00378 if role == Qt.CheckStateRole:
00379 state = self.checkState(column)
00380 super(TreeWidgetItem, self).setData(column, role, value)
00381 if role == Qt.CheckStateRole and state != self.checkState(column):
00382 self._check_state_changed_callback(self._topic_name)