class PlotWidget(QWidget): _redraw_interval = 40 def __init__(self, arguments=None, initial_topics=None): super(PlotWidget, self).__init__() self.setObjectName('PlotWidget') ui_file = os.path.join(os.path.dirname(os.path.realpath(__file__)), 'plot.ui') loadUi(ui_file, self) self.subscribe_topic_button.setIcon(QIcon.fromTheme('add')) self.remove_topic_button.setIcon(QIcon.fromTheme('remove')) self.pause_button.setIcon(QIcon.fromTheme('media-playback-pause')) self.clear_button.setIcon(QIcon.fromTheme('edit-clear')) self.data_plot = None self.subscribe_topic_button.setEnabled(False) self._topic_completer = TopicCompleter(self.topic_edit) self._topic_completer.update_topics() self.topic_edit.setCompleter(self._topic_completer) self._start_time = rospy.get_time() self._rosdata = {} self._ordered_topics = [] self._remove_topic_menu = QMenu() # init and start update timer for plot self._update_plot_timer = QTimer(self) self._update_plot_timer.timeout.connect(self.update_plot) # save command line arguments self._arguments = arguments self._initial_topics = initial_topics def switch_data_plot_widget(self, data_plot): self.enable_timer(enabled=False) self.data_plot_layout.removeWidget(self.data_plot) if self.data_plot is not None: self.data_plot.close() self.data_plot = data_plot self.data_plot_layout.addWidget(self.data_plot) # setup drag 'n drop self.data_plot.dropEvent = self.dropEvent self.data_plot.dragEnterEvent = self.dragEnterEvent if self._initial_topics: for topic_name in self._initial_topics: self.add_topic(topic_name) self._initial_topics = None else: for topic_name, rosdata in self._rosdata.items(): data_x, data_y = rosdata.next() self.data_plot.add_curve(topic_name, topic_name, data_x, data_y) self._subscribed_topics_changed() @Slot('QDragEnterEvent*') def dragEnterEvent(self, event): # get topic name if not event.mimeData().hasText(): if not hasattr(event.source(), 'selectedItems') or len( event.source().selectedItems()) == 0: qWarning( 'Plot.dragEnterEvent(): not hasattr(event.source(), selectedItems) or len(event.source().selectedItems()) == 0' ) return item = event.source().selectedItems()[0] topic_name = item.data(0, Qt.UserRole) if topic_name == None: qWarning( 'Plot.dragEnterEvent(): not hasattr(item, ros_topic_name_)' ) return else: topic_name = str(event.mimeData().text()) # check for numeric field type is_numeric, is_array, message = is_slot_numeric(topic_name) if is_numeric and not is_array: event.acceptProposedAction() else: qWarning('Plot.dragEnterEvent(): rejecting: "%s"' % (message)) @Slot('QDropEvent*') def dropEvent(self, event): if event.mimeData().hasText(): topic_name = str(event.mimeData().text()) else: droped_item = event.source().selectedItems()[0] topic_name = str(droped_item.data(0, Qt.UserRole)) self.add_topic(topic_name) @Slot(str) def on_topic_edit_textChanged(self, topic_name): # on empty topic name, update topics if topic_name in ('', '/'): self._topic_completer.update_topics() is_numeric, is_array, message = is_slot_numeric(topic_name) self.subscribe_topic_button.setEnabled(is_numeric and not is_array) self.subscribe_topic_button.setToolTip(message) @Slot() def on_subscribe_topic_button_clicked(self): self.add_topic(str(self.topic_edit.text())) @Slot() def on_mass_button_clicked(self): topics = str(self.mass_edit.toPlainText()).split() for topic in topics: self.add_topic(topic) @Slot(bool) def on_pause_button_clicked(self, checked): self.enable_timer(not checked) @Slot() def on_clear_button_clicked(self): self.clean_up_subscribers() def update_plot(self): if self.data_plot is not None: for topic_name, rosdata in self._rosdata.items(): try: data_x, data_y = rosdata.next() self.data_plot.update_values(topic_name, data_x, data_y) except RosPlotException as e: qWarning('PlotWidget.update_plot(): error in rosplot: %s' % e) self.data_plot.redraw() def _subscribed_topics_changed(self): self._update_remove_topic_menu() if self._arguments: if self._arguments.start_paused: self.pause_button.setChecked(True) if not self.pause_button.isChecked(): # if pause button is not pressed, enable timer based on subscribed topics self.enable_timer(self._rosdata) def _update_remove_topic_menu(self): def make_remove_topic_function(x): return lambda: self.remove_topic(x) self._remove_topic_menu.clear() for topic_name in sorted(self._rosdata.keys()): action = QAction(topic_name, self._remove_topic_menu) action.triggered.connect(make_remove_topic_function(topic_name)) self._remove_topic_menu.addAction(action) self.remove_topic_button.setMenu(self._remove_topic_menu) def add_topic(self, topic_name): if topic_name in self._rosdata: qWarning('PlotWidget.add_topic(): topic already subscribed: %s' % topic_name) return self._ordered_topics.append(topic_name) self._rosdata[topic_name] = ROSData(topic_name, self._start_time) data_x, data_y = self._rosdata[topic_name].next() self.data_plot.add_curve(topic_name, topic_name, data_x, data_y) self._subscribed_topics_changed() def remove_topic(self, topic_name): self._rosdata[topic_name].close() del self._rosdata[topic_name] self._ordered_topics.remove(topic_name) self.data_plot.remove_curve(topic_name) self._subscribed_topics_changed() def clean_up_subscribers(self): for topic_name, rosdata in self._rosdata.items(): rosdata.close() self.data_plot.remove_curve(topic_name) self._rosdata = {} self._ordered_topics = [] self._subscribed_topics_changed() def enable_timer(self, enabled=True): if enabled: self._update_plot_timer.start(self._redraw_interval) else: self._update_plot_timer.stop()
class Plot3DWidget(QWidget): _redraw_interval = 40 def __init__(self, initial_topics=None, start_paused=False, buffer_length=100, use_poly=True, no_legend=False): super(Plot3DWidget, self).__init__() self.setObjectName('Plot3DWidget') self._buffer_length = buffer_length self._initial_topics = initial_topics rp = rospkg.RosPack() ui_file = os.path.join(rp.get_path('jsk_rqt_plugins'), 'resource', 'plot3d.ui') loadUi(ui_file, self) self.subscribe_topic_button.setIcon(QIcon.fromTheme('add')) self.remove_topic_button.setIcon(QIcon.fromTheme('remove')) self.pause_button.setIcon(QIcon.fromTheme('media-playback-pause')) self.clear_button.setIcon(QIcon.fromTheme('edit-clear')) self.data_plot = MatDataPlot3D(self, self._buffer_length, use_poly, no_legend) self.data_plot_layout.addWidget(self.data_plot) self.data_plot.autoscroll(self.autoscroll_checkbox.isChecked()) self.data_plot.dropEvent = self.dropEvent self.data_plot.dragEnterEvent = self.dragEnterEvent self.subscribe_topic_button.setEnabled(False) if start_paused: self.pause_button.setChecked(True) self._topic_completer = TopicCompleter(self.topic_edit) self._topic_completer.update_topics() self.topic_edit.setCompleter(self._topic_completer) self._start_time = rospy.get_time() self._rosdata = {} self._remove_topic_menu = QMenu() # init and start update timer for plot self._update_plot_timer = QTimer(self) self._update_plot_timer.timeout.connect(self.update_plot) if self._initial_topics: for topic_name in self._initial_topics: self.add_topic(topic_name) self._initial_topics = None @Slot('QDragEnterEvent*') def dragEnterEvent(self, event): # get topic name if not event.mimeData().hasText(): if not hasattr(event.source(), 'selectedItems') or len(event.source().selectedItems()) == 0: qWarning('Plot.dragEnterEvent(): not hasattr(event.source(), selectedItems) or len(event.source().selectedItems()) == 0') return item = event.source().selectedItems()[0] topic_name = item.data(0, Qt.UserRole) if topic_name == None: qWarning('Plot.dragEnterEvent(): not hasattr(item, ros_topic_name_)') return else: topic_name = str(event.mimeData().text()) # check for numeric field type is_numeric, is_array, message = is_slot_numeric(topic_name) if is_numeric and not is_array: event.acceptProposedAction() else: qWarning('Plot.dragEnterEvent(): rejecting: "%s"' % (message)) @Slot('QDropEvent*') def dropEvent(self, event): if event.mimeData().hasText(): topic_name = str(event.mimeData().text()) else: droped_item = event.source().selectedItems()[0] topic_name = str(droped_item.data(0, Qt.UserRole)) self.add_topic(topic_name) @Slot(str) def on_topic_edit_textChanged(self, topic_name): # on empty topic name, update topics if topic_name in ('', '/'): self._topic_completer.update_topics() is_numeric, is_array, message = is_slot_numeric(topic_name) self.subscribe_topic_button.setEnabled(is_numeric and not is_array) self.subscribe_topic_button.setToolTip(message) @Slot() def on_topic_edit_returnPressed(self): if self.subscribe_topic_button.isEnabled(): self.add_topic(str(self.topic_edit.text())) @Slot() def on_subscribe_topic_button_clicked(self): self.add_topic(str(self.topic_edit.text())) @Slot(bool) def on_pause_button_clicked(self, checked): self.enable_timer(not checked) @Slot(bool) def on_autoscroll_checkbox_clicked(self, checked): self.data_plot.autoscroll(checked) @Slot() def on_clear_button_clicked(self): self.clean_up_subscribers() def update_plot(self): if self.data_plot is not None: needs_redraw = False for topic_name, rosdata in self._rosdata.items(): try: data_x, data_y = rosdata.next() if data_x or data_y: self.data_plot.update_values(topic_name, data_x, data_y) needs_redraw = True except RosPlotException as e: qWarning('PlotWidget.update_plot(): error in rosplot: %s' % e) if needs_redraw: self.data_plot.redraw() def _subscribed_topics_changed(self): self._update_remove_topic_menu() if not self.pause_button.isChecked(): # if pause button is not pressed, enable timer based on subscribed topics self.enable_timer(self._rosdata) def _update_remove_topic_menu(self): def make_remove_topic_function(x): return lambda: self.remove_topic(x) self._remove_topic_menu.clear() for topic_name in sorted(self._rosdata.keys()): action = QAction(topic_name, self._remove_topic_menu) action.triggered.connect(make_remove_topic_function(topic_name)) self._remove_topic_menu.addAction(action) self.remove_topic_button.setMenu(self._remove_topic_menu) def add_topic(self, topic_name): if topic_name in self._rosdata: qWarning('PlotWidget.add_topic(): topic already subscribed: %s' % topic_name) return self._rosdata[topic_name] = ROSData(topic_name, self._start_time) if self._rosdata[topic_name].error is not None: qWarning(str(self._rosdata[topic_name].error)) del self._rosdata[topic_name] else: data_x, data_y = self._rosdata[topic_name].next() self.data_plot.add_curve(topic_name, topic_name, data_x, data_y) self._subscribed_topics_changed() def remove_topic(self, topic_name): self._rosdata[topic_name].close() del self._rosdata[topic_name] self.data_plot.remove_curve(topic_name) self._subscribed_topics_changed() def clean_up_subscribers(self): for topic_name, rosdata in self._rosdata.items(): rosdata.close() self.data_plot.remove_curve(topic_name) self._rosdata = {} self._subscribed_topics_changed() def enable_timer(self, enabled=True): if enabled: self._update_plot_timer.start(self._redraw_interval) else: self._update_plot_timer.stop()