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 import os
00034 import rospkg
00035 import roslib
00036
00037 from python_qt_binding import loadUi
00038 from python_qt_binding.QtCore import Qt, QTimer, qWarning, Slot
00039 from python_qt_binding.QtGui import QIcon
00040 from python_qt_binding.QtWidgets import QAction, QMenu, QWidget
00041
00042 import rospy
00043
00044 from rqt_py_common.topic_completer import TopicCompleter
00045 from rqt_py_common import topic_helpers
00046
00047 from . rosplot import ROSData, RosPlotException
00048
00049
00050 def get_plot_fields(topic_name):
00051 topic_type, real_topic, _ = topic_helpers.get_topic_type(topic_name)
00052 if topic_type is None:
00053 message = "topic %s does not exist" % (topic_name)
00054 return [], message
00055 field_name = topic_name[len(real_topic) + 1:]
00056
00057 slot_type, is_array, array_size = roslib.msgs.parse_type(topic_type)
00058 field_class = roslib.message.get_message_class(slot_type)
00059 if field_class is None:
00060 message = "type of topic %s is unknown" % (topic_name)
00061 return [], message
00062
00063 fields = [f for f in field_name.split('/') if f]
00064
00065 for field in fields:
00066
00067 try:
00068 field, _, field_index = roslib.msgs.parse_type(field)
00069 except roslib.msgs.MsgSpecException:
00070 message = "invalid field %s in topic %s" % (field, real_topic)
00071 return [], message
00072
00073 if field not in getattr(field_class, '__slots__', []):
00074 message = "no field %s in topic %s" % (field_name, real_topic)
00075 return [], message
00076 slot_type = field_class._slot_types[field_class.__slots__.index(field)]
00077 slot_type, slot_is_array, array_size = roslib.msgs.parse_type(slot_type)
00078 is_array = slot_is_array and field_index is None
00079
00080 field_class = topic_helpers.get_type_class(slot_type)
00081
00082 if field_class in (int, float, bool):
00083 topic_kind = 'boolean' if field_class == bool else 'numeric'
00084 if is_array:
00085 if array_size is not None:
00086 message = "topic %s is fixed-size %s array" % (topic_name, topic_kind)
00087 return ["%s[%d]" % (topic_name, i) for i in range(array_size)], message
00088 else:
00089 message = "topic %s is variable-size %s array" % (topic_name, topic_kind)
00090 return [], message
00091 else:
00092 message = "topic %s is %s" % (topic_name, topic_kind)
00093 return [topic_name], message
00094 else:
00095 if not roslib.msgs.is_valid_constant_type(slot_type):
00096 numeric_fields = []
00097 for i, slot in enumerate(field_class.__slots__):
00098 slot_type = field_class._slot_types[i]
00099 slot_type, is_array, array_size = roslib.msgs.parse_type(slot_type)
00100 slot_class = topic_helpers.get_type_class(slot_type)
00101 if slot_class in (int, float) and not is_array:
00102 numeric_fields.append(slot)
00103 message = ""
00104 if len(numeric_fields) > 0:
00105 message = "%d plottable fields in %s" % (len(numeric_fields), topic_name)
00106 else:
00107 message = "No plottable fields in %s" % (topic_name)
00108 return ["%s/%s" % (topic_name, f) for f in numeric_fields], message
00109 else:
00110 message = "Topic %s is not numeric" % (topic_name)
00111 return [], message
00112
00113
00114 def is_plottable(topic_name):
00115 fields, message = get_plot_fields(topic_name)
00116 return len(fields) > 0, message
00117
00118
00119 class PlotWidget(QWidget):
00120 _redraw_interval = 40
00121
00122 def __init__(self, initial_topics=None, start_paused=False):
00123 super(PlotWidget, self).__init__()
00124 self.setObjectName('PlotWidget')
00125
00126 self._initial_topics = initial_topics
00127
00128 rp = rospkg.RosPack()
00129 ui_file = os.path.join(rp.get_path('rqt_plot'), 'resource', 'plot.ui')
00130 loadUi(ui_file, self)
00131 self.subscribe_topic_button.setIcon(QIcon.fromTheme('list-add'))
00132 self.remove_topic_button.setIcon(QIcon.fromTheme('list-remove'))
00133 self.pause_button.setIcon(QIcon.fromTheme('media-playback-pause'))
00134 self.clear_button.setIcon(QIcon.fromTheme('edit-clear'))
00135 self.data_plot = None
00136
00137 self.subscribe_topic_button.setEnabled(False)
00138 if start_paused:
00139 self.pause_button.setChecked(True)
00140
00141 self._topic_completer = TopicCompleter(self.topic_edit)
00142 self._topic_completer.update_topics()
00143 self.topic_edit.setCompleter(self._topic_completer)
00144
00145 self._start_time = rospy.get_time()
00146 self._rosdata = {}
00147 self._remove_topic_menu = QMenu()
00148
00149
00150 self._update_plot_timer = QTimer(self)
00151 self._update_plot_timer.timeout.connect(self.update_plot)
00152
00153 def switch_data_plot_widget(self, data_plot):
00154 self.enable_timer(enabled=False)
00155
00156 self.data_plot_layout.removeWidget(self.data_plot)
00157 if self.data_plot is not None:
00158 self.data_plot.close()
00159
00160 self.data_plot = data_plot
00161 self.data_plot_layout.addWidget(self.data_plot)
00162 self.data_plot.autoscroll(self.autoscroll_checkbox.isChecked())
00163
00164
00165 self.data_plot.dropEvent = self.dropEvent
00166 self.data_plot.dragEnterEvent = self.dragEnterEvent
00167
00168 if self._initial_topics:
00169 for topic_name in self._initial_topics:
00170 self.add_topic(topic_name)
00171 self._initial_topics = None
00172 else:
00173 for topic_name, rosdata in self._rosdata.items():
00174 data_x, data_y = rosdata.next()
00175 self.data_plot.add_curve(topic_name, topic_name, data_x, data_y)
00176
00177 self._subscribed_topics_changed()
00178
00179 @Slot('QDragEnterEvent*')
00180 def dragEnterEvent(self, event):
00181
00182 if not event.mimeData().hasText():
00183 if not hasattr(event.source(), 'selectedItems') or \
00184 len(event.source().selectedItems()) == 0:
00185 qWarning(
00186 'Plot.dragEnterEvent(): not hasattr(event.source(), selectedItems) or '
00187 'len(event.source().selectedItems()) == 0')
00188 return
00189 item = event.source().selectedItems()[0]
00190 topic_name = item.data(0, Qt.UserRole)
00191 if topic_name == None:
00192 qWarning('Plot.dragEnterEvent(): not hasattr(item, ros_topic_name_)')
00193 return
00194 else:
00195 topic_name = str(event.mimeData().text())
00196
00197
00198 plottable, message = is_plottable(topic_name)
00199 if plottable:
00200 event.acceptProposedAction()
00201 else:
00202 qWarning('Plot.dragEnterEvent(): rejecting: "%s"' % (message))
00203
00204 @Slot('QDropEvent*')
00205 def dropEvent(self, event):
00206 if event.mimeData().hasText():
00207 topic_name = str(event.mimeData().text())
00208 else:
00209 droped_item = event.source().selectedItems()[0]
00210 topic_name = str(droped_item.data(0, Qt.UserRole))
00211 self.add_topic(topic_name)
00212
00213 @Slot(str)
00214 def on_topic_edit_textChanged(self, topic_name):
00215
00216 if topic_name in ('', '/'):
00217 self._topic_completer.update_topics()
00218
00219 plottable, message = is_plottable(topic_name)
00220 self.subscribe_topic_button.setEnabled(plottable)
00221 self.subscribe_topic_button.setToolTip(message)
00222
00223 @Slot()
00224 def on_topic_edit_returnPressed(self):
00225 if self.subscribe_topic_button.isEnabled():
00226 self.add_topic(str(self.topic_edit.text()))
00227
00228 @Slot()
00229 def on_subscribe_topic_button_clicked(self):
00230 self.add_topic(str(self.topic_edit.text()))
00231
00232 @Slot(bool)
00233 def on_pause_button_clicked(self, checked):
00234 self.enable_timer(not checked)
00235
00236 @Slot(bool)
00237 def on_autoscroll_checkbox_clicked(self, checked):
00238 self.data_plot.autoscroll(checked)
00239 if checked:
00240 self.data_plot.redraw()
00241
00242 @Slot()
00243 def on_clear_button_clicked(self):
00244 self.clear_plot()
00245
00246 def update_plot(self):
00247 if self.data_plot is not None:
00248 needs_redraw = False
00249 for topic_name, rosdata in self._rosdata.items():
00250 try:
00251 data_x, data_y = rosdata.next()
00252 if data_x or data_y:
00253 self.data_plot.update_values(topic_name, data_x, data_y)
00254 needs_redraw = True
00255 except RosPlotException as e:
00256 qWarning('PlotWidget.update_plot(): error in rosplot: %s' % e)
00257 if needs_redraw:
00258 self.data_plot.redraw()
00259
00260 def _subscribed_topics_changed(self):
00261 self._update_remove_topic_menu()
00262 if not self.pause_button.isChecked():
00263
00264 self.enable_timer(self._rosdata)
00265 self.data_plot.redraw()
00266
00267 def _update_remove_topic_menu(self):
00268 def make_remove_topic_function(x):
00269 return lambda: self.remove_topic(x)
00270
00271 self._remove_topic_menu.clear()
00272 for topic_name in sorted(self._rosdata.keys()):
00273 action = QAction(topic_name, self._remove_topic_menu)
00274 action.triggered.connect(make_remove_topic_function(topic_name))
00275 self._remove_topic_menu.addAction(action)
00276
00277 if len(self._rosdata) > 1:
00278 all_action = QAction('All', self._remove_topic_menu)
00279 all_action.triggered.connect(self.clean_up_subscribers)
00280 self._remove_topic_menu.addAction(all_action)
00281
00282 self.remove_topic_button.setMenu(self._remove_topic_menu)
00283
00284 def add_topic(self, topic_name):
00285 topics_changed = False
00286 for topic_name in get_plot_fields(topic_name)[0]:
00287 if topic_name in self._rosdata:
00288 qWarning('PlotWidget.add_topic(): topic already subscribed: %s' % topic_name)
00289 continue
00290 self._rosdata[topic_name] = ROSData(topic_name, self._start_time)
00291 if self._rosdata[topic_name].error is not None:
00292 qWarning(str(self._rosdata[topic_name].error))
00293 del self._rosdata[topic_name]
00294 else:
00295 data_x, data_y = self._rosdata[topic_name].next()
00296 self.data_plot.add_curve(topic_name, topic_name, data_x, data_y)
00297 topics_changed = True
00298
00299 if topics_changed:
00300 self._subscribed_topics_changed()
00301
00302 def remove_topic(self, topic_name):
00303 self._rosdata[topic_name].close()
00304 del self._rosdata[topic_name]
00305 self.data_plot.remove_curve(topic_name)
00306
00307 self._subscribed_topics_changed()
00308
00309 def clear_plot(self):
00310 for topic_name, _ in self._rosdata.items():
00311 self.data_plot.clear_values(topic_name)
00312 self.data_plot.redraw()
00313
00314 def clean_up_subscribers(self):
00315 for topic_name, rosdata in self._rosdata.items():
00316 rosdata.close()
00317 self.data_plot.remove_curve(topic_name)
00318 self._rosdata = {}
00319
00320 self._subscribed_topics_changed()
00321
00322 def enable_timer(self, enabled=True):
00323 if enabled:
00324 self._update_plot_timer.start(self._redraw_interval)
00325 else:
00326 self._update_plot_timer.stop()