plot.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import argparse
4 from distutils.version import LooseVersion
5 import os
6 import sys
7 if not hasattr(sys, 'maxint'):
8  sys.maxint = sys.maxsize
9 
10 import matplotlib
11 from matplotlib.collections import LineCollection
12 from matplotlib.collections import PathCollection
13 from matplotlib.collections import PolyCollection
14 from matplotlib.colors import colorConverter
15 from matplotlib.figure import Figure
16 import matplotlib.pyplot as plt
17 from mpl_toolkits.mplot3d import axes3d
18 from mpl_toolkits.mplot3d import Axes3D # <-- Note the capitalization!
19 import numpy
20 import python_qt_binding
21 from python_qt_binding import loadUi
22 from python_qt_binding.QtCore import Qt
23 from python_qt_binding.QtCore import QTimer
24 from python_qt_binding.QtCore import qWarning
25 from python_qt_binding.QtCore import Slot
26 from python_qt_binding.QtGui import QColor
27 from python_qt_binding.QtGui import QIcon
28 
29 import rospkg
30 import rospy
31 from rqt_gui_py.plugin import Plugin
32 from rqt_plot.rosplot import ROSData, RosPlotException
33 from rqt_py_common.topic_completer import TopicCompleter
34 from rqt_py_common.topic_helpers import is_slot_numeric
35 
36 # Support both qt4 and qt5
37 if LooseVersion(python_qt_binding.QT_BINDING_VERSION).version[0] >= 5:
38  from python_qt_binding.QtWidgets import QAction
39  from python_qt_binding.QtWidgets import QMenu
40  from python_qt_binding.QtWidgets import QSizePolicy
41  from python_qt_binding.QtWidgets import QVBoxLayout
42  from python_qt_binding.QtWidgets import QWidget
43  try:
44  from matplotlib.backends.backend_qt5agg import FigureCanvasQTAgg \
45  as FigureCanvas
46  except ImportError:
47  # work around bug in dateutil
48  import thread
49  sys.modules['_thread'] = thread
50  from matplotlib.backends.backend_qt5agg import FigureCanvasQTAgg \
51  as FigureCanvas
52  try:
53  from matplotlib.backends.backend_qt5agg \
54  import NavigationToolbar2QTAgg as NavigationToolbar
55  except ImportError:
56  from matplotlib.backends.backend_qt5agg import NavigationToolbar2QT \
57  as NavigationToolbar
58 
59 else:
60  from python_qt_binding.QtGui import QAction
61  from python_qt_binding.QtGui import QMenu
62  from python_qt_binding.QtGui import QSizePolicy
63  from python_qt_binding.QtGui import QVBoxLayout
64  from python_qt_binding.QtGui import QWidget
65  try:
66  from matplotlib.backends.backend_qt4agg import FigureCanvasQTAgg \
67  as FigureCanvas
68  except ImportError:
69  # work around bug in dateutil
70  import thread
71  sys.modules['_thread'] = thread
72  from matplotlib.backends.backend_qt4agg import FigureCanvasQTAgg \
73  as FigureCanvas
74  try:
75  from matplotlib.backends.backend_qt4agg \
76  import NavigationToolbar2QTAgg as NavigationToolbar
77  except ImportError:
78  from matplotlib.backends.backend_qt4agg import NavigationToolbar2QT \
79  as NavigationToolbar
80 
81 
82 class MatDataPlot3D(QWidget):
83  class Canvas(FigureCanvas):
84  """Ultimately, this is a QWidget (as well as a FigureCanvasAgg, etc.).
85 """
86  def __init__(self, parent=None):
87  super(MatDataPlot3D.Canvas, self).__init__(Figure())
88  # self.fig = fig = plt.figure()
89  self.axes = self.figure.add_subplot(111, projection='3d')
90  # self.axes = self.figure.gca(projection="3d")
91  # self.axes.grid(True, color='gray')
92  self.axes.set_xlabel('t')
93  self.axes.set_xlim3d(0, 10)
94  self.axes.set_ylabel('Y')
95  self.axes.set_ylim3d(-1, 1)
96  self.axes.set_zlabel('Z')
97  self.axes.set_zlim3d(0, 1)
98 
99  self.figure.tight_layout()
100  self.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding)
101  self.updateGeometry()
102 
103  def resizeEvent(self, event):
104  super(MatDataPlot3D.Canvas, self).resizeEvent(event)
105  self.figure.tight_layout()
106 
107  _colors = [QColor(c) for c in [
108  Qt.red, Qt.blue, Qt.magenta, Qt.cyan, Qt.green, Qt.darkYellow,
109  Qt.black, Qt.darkRed, Qt.gray, Qt.darkCyan]]
110 
111  def __init__(self, parent=None, buffer_length=100, use_poly=True,
112  no_legend=False):
113  super(MatDataPlot3D, self).__init__(parent)
115  self._use_poly = use_poly
116  self._buffer_length = buffer_length
117  self._toolbar = NavigationToolbar(self._canvas, self._canvas)
118  vbox = QVBoxLayout()
119  vbox.addWidget(self._toolbar)
120  vbox.addWidget(self._canvas)
121  self.setLayout(vbox)
122  self._curves_verts = {}
123  self._color_index = 0
124  self._curves = {}
125  self._no_legend = no_legend
126  self._autoscroll = False
127 
128  def autoscroll(self, enabled=True):
129  self._autoscroll = enabled
130 
131  def add_curve(self, curve_id, curve_name, x, y):
132  color = QColor(self._colors[self._color_index % len(self._colors)])
133  self._color_index += 1
134  # line = self._canvas.axes.plot(
135  # [], [], label=curve_name, linewidth=1, picker=5,
136  # color=color.name())[0]
137  line = None
138  self._curves[curve_id] = [[], [], line, [None, None],
139  (color.red() / 255.0,
140  color.green() / 255.0,
141  color.blue() / 255.0,
142  0.6)]
143  self.update_values(curve_id, x, y)
144  self._update_legend()
145 
146  def remove_curve(self, curve_id):
147  curve_id = str(curve_id)
148  if curve_id in self._curves:
149  del self._curves[curve_id]
150  del self._curves_verts[curve_id]
151  self._update_legend()
152 
153  def _update_legend(self):
154  if self._no_legend:
155  return
156  labels = list(self._curves.keys())
157  handles = [
158  plt.Rectangle((0, 0), 1, 1, fc=self._curves[labels[i]][4])
159  for i in range(len(labels))]
160  self._canvas.axes.legend(handles, labels, loc='upper left')
161 
162  @Slot(str, list, list)
163  def update_values(self, curve_id, x, y):
164  data_x, data_y, line, range_y, c = self._curves[curve_id]
165  data_x.extend(x)
166  data_y.extend(y)
167  if len(data_x) > self._buffer_length:
168  data_x = data_x[-self._buffer_length:]
169  data_y = data_y[-self._buffer_length:]
170  self._curves[curve_id][0] = data_x
171  self._curves[curve_id][1] = data_y
172  self._curves_verts[curve_id] = (data_x, data_y)
173  if y:
174  ymin = min(y)
175  if range_y[0]:
176  ymin = min(ymin, range_y[0])
177  range_y[0] = ymin
178  ymax = max(y)
179  if range_y[1]:
180  ymax = max(ymax, range_y[1])
181  range_y[1] = ymax
182 
183  def redraw(self):
184  self._canvas.axes.grid(True, color='gray')
185  # Set axis bounds
186  ymin = ymax = None
187  xmax = 0
188  xmin = sys.maxint
189  for curve in self._curves.values():
190  data_x, _, _, range_y, c = curve
191  if len(data_x) == 0:
192  continue
193  xmax = max(xmax, data_x[-1])
194  xmin = min(xmin, data_x[0])
195  if ymin is None:
196  ymin = range_y[0]
197  ymax = range_y[1]
198  else:
199  ymin = min(range_y[0], ymin)
200  ymax = max(range_y[1], ymax)
201 
202  # pad the min/max
203  # delta = max(ymax - ymin, 0.1)
204  # ymin -= .05 * delta
205  # ymax += .05 * delta
206 
207  if self._autoscroll and ymin is not None:
208  self._canvas.axes.set_xbound(lower=xmin, upper=xmax)
209  self._canvas.axes.set_zbound(lower=ymin, upper=ymax)
210  self._canvas.axes.set_ybound(lower=0,
211  upper=len(self._curves.keys()))
212  # create poly object
213  verts = []
214  colors = []
215  for curve_id in self._curves_verts.keys():
216  (data_x, data_y) = self._curves_verts[curve_id]
217  colors.append(self._curves[curve_id][4])
218  if self._use_poly:
219  verts.append([(xmin, ymin)] + list(zip(data_x, data_y))
220  + [(xmax, ymin)])
221  else:
222  verts.append(list(zip(data_x, data_y)))
223  line_num = len(self._curves.keys())
224  if self._use_poly:
225  poly = PolyCollection(verts, facecolors=colors, closed=False)
226  else:
227  poly = LineCollection(verts, colors=colors)
228  poly.set_alpha(0.7)
229  self._canvas.axes.cla()
230  self._canvas.axes.add_collection3d(poly,
231  zs=range(line_num), zdir='y')
232  self._update_legend()
233  self._canvas.draw()
234 
235 
236 class Plot3D(Plugin):
237  def __init__(self, context):
238  super(Plot3D, self).__init__(context)
239  self.setObjectName('Plot3D')
240  self._args = self._parse_args(context.argv())
242  initial_topics=self._args.topics,
243  start_paused=self._args.start_paused,
244  buffer_length=self._args.buffer,
245  use_poly=not self._args.show_line,
246  no_legend=self._args.no_legend)
247  context.add_widget(self._widget)
248 
249  def _parse_args(self, argv):
250  parser = argparse.ArgumentParser(prog='rqt_3d_plot', add_help=False)
251  Plot3D.add_arguments(parser)
252  args = parser.parse_args(argv)
253  topic_list = []
254  for t in args.topics:
255  # c_topics is the list of topics to plot
256  c_topics = []
257  # compute combined topic list, t == '/foo/bar1,/baz/bar2'
258  for sub_t in [x for x in t.split(',') if x]:
259  # check for shorthand '/foo/field1:field2:field3'
260  if ':' in sub_t:
261  base = sub_t[:sub_t.find(':')]
262  # the first prefix includes a field name,
263  # so save then strip it off
264  c_topics.append(base)
265  if not '/' in base:
266  parser.error(
267  "%s must contain a topic and field name" % sub_t)
268  base = base[:base.rfind('/')]
269 
270  # compute the rest of the field names
271  fields = sub_t.split(':')[1:]
272  c_topics.extend(["%s/%s" % (base, f) for f in fields if f])
273  else:
274  c_topics.append(sub_t)
275  # #1053: resolve command-line topic names
276  import rosgraph
277  c_topics = [rosgraph.names.script_resolve_name('rqt_plot', n)
278  for n in c_topics]
279  if type(c_topics) == list:
280  topic_list.extend(c_topics)
281  else:
282  topic_list.append(c_topics)
283  args.topics = topic_list
284 
285  return args
286 
287  @staticmethod
288  def add_arguments(parser):
289  group = parser.add_argument_group('Options for rqt_plot plugin')
290  group.add_argument(
291  '-P', '--pause', action='store_true', dest='start_paused',
292  help='Start in paused state')
293  group.add_argument(
294  '-L', '--line', action='store_true', dest='show_line',
295  help='Show lines rather than polygon representation')
296  group.add_argument(
297  '--no-legend', action='store_true', dest='no_legend',
298  help='do not show legend')
299  group.add_argument(
300  '-B', '--buffer', dest='buffer', action="store",
301  help='the length of the buffer', default=100, type=int)
302  # group.add_argument(
303  # '-e', '--empty', action='store_true', dest='start_empty',
304  # help='Start without restoring previous topics')
305  group.add_argument(
306  'topics', nargs='*', default=[], help='Topics to plot')
307 
308 
309 class Plot3DWidget(QWidget):
310  _redraw_interval = 40
311 
312  def __init__(self, initial_topics=None, start_paused=False,
313  buffer_length=100, use_poly=True, no_legend=False):
314  super(Plot3DWidget, self).__init__()
315  self.setObjectName('Plot3DWidget')
316  self._buffer_length = buffer_length
317  self._initial_topics = initial_topics
318 
319  rp = rospkg.RosPack()
320  ui_file = os.path.join(rp.get_path('jsk_rqt_plugins'),
321  'resource', 'plot3d.ui')
322  loadUi(ui_file, self)
323  self.subscribe_topic_button.setIcon(QIcon.fromTheme('add'))
324  self.remove_topic_button.setIcon(QIcon.fromTheme('remove'))
325  self.pause_button.setIcon(QIcon.fromTheme('media-playback-pause'))
326  self.clear_button.setIcon(QIcon.fromTheme('edit-clear'))
327  self.data_plot = MatDataPlot3D(self, self._buffer_length,
328  use_poly, no_legend)
329  self.data_plot_layout.addWidget(self.data_plot)
330  self.data_plot.autoscroll(self.autoscroll_checkbox.isChecked())
331  self.data_plot.dropEvent = self.dropEvent
332  self.data_plot.dragEnterEvent = self.dragEnterEvent
333 
334  self.subscribe_topic_button.setEnabled(False)
335  if start_paused:
336  self.pause_button.setChecked(True)
337 
338  self._topic_completer = TopicCompleter(self.topic_edit)
339  self._topic_completer.update_topics()
340  self.topic_edit.setCompleter(self._topic_completer)
341 
342  self._start_time = rospy.get_time()
343  self._rosdata = {}
344  self._remove_topic_menu = QMenu()
345 
346  # init and start update timer for plot
347  self._update_plot_timer = QTimer(self)
348  self._update_plot_timer.timeout.connect(self.update_plot)
349  if self._initial_topics:
350  for topic_name in self._initial_topics:
351  self.add_topic(topic_name)
352  self._initial_topics = None
353 
354  @Slot('QDragEnterEvent*')
355  def dragEnterEvent(self, event):
356  # get topic name
357  if not event.mimeData().hasText():
358  if not hasattr(event.source(), 'selectedItems') or \
359  len(event.source().selectedItems()) == 0:
360  qWarning(
361  'Plot.dragEnterEvent(): not hasattr(event.source(), selectedItems) or len(event.source().selectedItems()) == 0') # NOQA
362  return
363  item = event.source().selectedItems()[0]
364  topic_name = item.data(0, Qt.UserRole)
365  if topic_name == None:
366  qWarning(
367  'Plot.dragEnterEvent(): not hasattr(item, ros_topic_name_)') # NOQA
368  return
369  else:
370  topic_name = str(event.mimeData().text())
371 
372  # check for numeric field type
373  is_numeric, is_array, message = is_slot_numeric(topic_name)
374  if is_numeric and not is_array:
375  event.acceptProposedAction()
376  else:
377  qWarning('Plot.dragEnterEvent(): rejecting: "%s"' % (message))
378 
379  @Slot('QDropEvent*')
380  def dropEvent(self, event):
381  if event.mimeData().hasText():
382  topic_name = str(event.mimeData().text())
383  else:
384  droped_item = event.source().selectedItems()[0]
385  topic_name = str(droped_item.data(0, Qt.UserRole))
386  self.add_topic(topic_name)
387 
388  @Slot(str)
389  def on_topic_edit_textChanged(self, topic_name):
390  # on empty topic name, update topics
391  if topic_name in ('', '/'):
392  self._topic_completer.update_topics()
393 
394  is_numeric, is_array, message = is_slot_numeric(topic_name)
395  self.subscribe_topic_button.setEnabled(is_numeric and not is_array)
396  self.subscribe_topic_button.setToolTip(message)
397 
398  @Slot()
400  if self.subscribe_topic_button.isEnabled():
401  self.add_topic(str(self.topic_edit.text()))
402 
403  @Slot()
405  self.add_topic(str(self.topic_edit.text()))
406 
407  @Slot(bool)
408  def on_pause_button_clicked(self, checked):
409  self.enable_timer(not checked)
410 
411  @Slot(bool)
412  def on_autoscroll_checkbox_clicked(self, checked):
413  self.data_plot.autoscroll(checked)
414 
415  @Slot()
417  self.clean_up_subscribers()
418 
419  def update_plot(self):
420  if self.data_plot is not None:
421  needs_redraw = False
422  for topic_name, rosdata in self._rosdata.items():
423  try:
424  data_x, data_y = rosdata.next()
425  if data_x or data_y:
426  self.data_plot.update_values(
427  topic_name, data_x, data_y)
428  needs_redraw = True
429  except RosPlotException as e:
430  qWarning(
431  'PlotWidget.update_plot(): error in rosplot: %s' % e)
432  if needs_redraw:
433  self.data_plot.redraw()
434 
437  if not self.pause_button.isChecked():
438  # if pause button is not pressed,
439  # enable timer based on subscribed topics
440  self.enable_timer(self._rosdata)
441 
443  def make_remove_topic_function(x):
444  return lambda: self.remove_topic(x)
445 
446  self._remove_topic_menu.clear()
447  for topic_name in sorted(self._rosdata.keys()):
448  action = QAction(topic_name, self._remove_topic_menu)
449  action.triggered.connect(make_remove_topic_function(topic_name))
450  self._remove_topic_menu.addAction(action)
451 
452  self.remove_topic_button.setMenu(self._remove_topic_menu)
453 
454  def add_topic(self, topic_name):
455  if topic_name in self._rosdata:
456  qWarning('PlotWidget.add_topic(): topic already subscribed: %s' % topic_name) # NOQA
457  return
458 
459  self._rosdata[topic_name] = ROSData(topic_name, self._start_time)
460  if self._rosdata[topic_name].error is not None:
461  qWarning(str(self._rosdata[topic_name].error))
462  del self._rosdata[topic_name]
463  else:
464  data_x, data_y = self._rosdata[topic_name].next()
465  self.data_plot.add_curve(topic_name, topic_name, data_x, data_y)
466 
468 
469  def remove_topic(self, topic_name):
470  self._rosdata[topic_name].close()
471  del self._rosdata[topic_name]
472  self.data_plot.remove_curve(topic_name)
473 
475 
477  for topic_name, rosdata in self._rosdata.items():
478  rosdata.close()
479  self.data_plot.remove_curve(topic_name)
480  self._rosdata = {}
481 
483 
484  def enable_timer(self, enabled=True):
485  if enabled:
486  self._update_plot_timer.start(self._redraw_interval)
487  else:
488  self._update_plot_timer.stop()
jsk_rqt_plugins.plot.MatDataPlot3D._use_poly
_use_poly
Definition: plot.py:114
jsk_rqt_plugins.plot.Plot3D._parse_args
def _parse_args(self, argv)
Definition: plot.py:249
jsk_rqt_plugins.plot.MatDataPlot3D._update_legend
def _update_legend(self)
Definition: plot.py:153
jsk_rqt_plugins.plot.MatDataPlot3D.Canvas
Definition: plot.py:83
jsk_rqt_plugins.plot.Plot3DWidget._update_remove_topic_menu
def _update_remove_topic_menu(self)
Definition: plot.py:442
jsk_rqt_plugins.plot.Plot3DWidget.on_clear_button_clicked
def on_clear_button_clicked(self)
Definition: plot.py:416
jsk_rqt_plugins.plot.Plot3D._widget
_widget
Definition: plot.py:241
jsk_rqt_plugins.plot.MatDataPlot3D._curves
_curves
Definition: plot.py:123
jsk_rqt_plugins.plot.MatDataPlot3D.update_values
def update_values(self, curve_id, x, y)
Definition: plot.py:163
jsk_rqt_plugins.plot.Plot3D._args
_args
Definition: plot.py:240
jsk_rqt_plugins.plot.MatDataPlot3D._toolbar
_toolbar
Definition: plot.py:116
jsk_rqt_plugins.plot.MatDataPlot3D.add_curve
def add_curve(self, curve_id, curve_name, x, y)
Definition: plot.py:131
jsk_rqt_plugins.plot.Plot3DWidget.add_topic
def add_topic(self, topic_name)
Definition: plot.py:454
jsk_rqt_plugins.plot.Plot3DWidget.on_subscribe_topic_button_clicked
def on_subscribe_topic_button_clicked(self)
Definition: plot.py:404
jsk_rqt_plugins.plot.MatDataPlot3D.Canvas.__init__
def __init__(self, parent=None)
Definition: plot.py:86
jsk_rqt_plugins.plot.MatDataPlot3D._no_legend
_no_legend
Definition: plot.py:124
rqt_plot::rosplot::ROSData
rqt_gui_py::plugin::Plugin
jsk_rqt_plugins.plot.MatDataPlot3D.Canvas.resizeEvent
def resizeEvent(self, event)
Definition: plot.py:103
jsk_rqt_plugins.plot.MatDataPlot3D.redraw
def redraw(self)
Definition: plot.py:183
jsk_rqt_plugins.plot.MatDataPlot3D.Canvas.axes
axes
Definition: plot.py:89
jsk_rqt_plugins.plot.Plot3DWidget._remove_topic_menu
_remove_topic_menu
Definition: plot.py:343
jsk_rqt_plugins.plot.Plot3DWidget.on_pause_button_clicked
def on_pause_button_clicked(self, checked)
Definition: plot.py:408
jsk_rqt_plugins.plot.Plot3DWidget.dropEvent
def dropEvent(self, event)
Definition: plot.py:380
jsk_rqt_plugins.plot.MatDataPlot3D
Definition: plot.py:82
jsk_rqt_plugins.plot.Plot3DWidget.remove_topic
def remove_topic(self, topic_name)
Definition: plot.py:469
jsk_rqt_plugins.plot.Plot3DWidget.update_plot
def update_plot(self)
Definition: plot.py:419
rqt_py_common::topic_helpers
jsk_rqt_plugins.plot.Plot3DWidget.enable_timer
def enable_timer(self, enabled=True)
Definition: plot.py:484
jsk_rqt_plugins.plot.MatDataPlot3D._buffer_length
_buffer_length
Definition: plot.py:115
jsk_rqt_plugins.plot.Plot3D.add_arguments
def add_arguments(parser)
Definition: plot.py:288
jsk_rqt_plugins.plot.Plot3DWidget._start_time
_start_time
Definition: plot.py:341
jsk_rqt_plugins.plot.Plot3DWidget.on_autoscroll_checkbox_clicked
def on_autoscroll_checkbox_clicked(self, checked)
Definition: plot.py:412
sample_2d_plot.type
type
Definition: sample_2d_plot.py:20
jsk_rqt_plugins.plot.MatDataPlot3D._colors
_colors
Definition: plot.py:107
jsk_rqt_plugins.plot.MatDataPlot3D.autoscroll
def autoscroll(self, enabled=True)
Definition: plot.py:128
jsk_rqt_plugins.plot.Plot3DWidget._redraw_interval
int _redraw_interval
Definition: plot.py:310
jsk_rqt_plugins.plot.MatDataPlot3D._color_index
_color_index
Definition: plot.py:122
jsk_rqt_plugins.plot.Plot3DWidget._topic_completer
_topic_completer
Definition: plot.py:337
jsk_rqt_plugins.plot.Plot3D
Definition: plot.py:236
jsk_rqt_plugins.plot.Plot3DWidget.on_topic_edit_returnPressed
def on_topic_edit_returnPressed(self)
Definition: plot.py:399
jsk_rqt_plugins.plot.MatDataPlot3D._autoscroll
_autoscroll
Definition: plot.py:125
jsk_rqt_plugins.plot.MatDataPlot3D.__init__
def __init__(self, parent=None, buffer_length=100, use_poly=True, no_legend=False)
Definition: plot.py:111
jsk_rqt_plugins.plot.Plot3DWidget._rosdata
_rosdata
Definition: plot.py:342
rqt_plot::rosplot
jsk_rqt_plugins.plot.Plot3DWidget.__init__
def __init__(self, initial_topics=None, start_paused=False, buffer_length=100, use_poly=True, no_legend=False)
Definition: plot.py:312
jsk_rqt_plugins.plot.Plot3DWidget._initial_topics
_initial_topics
Definition: plot.py:316
jsk_rqt_plugins.plot.Plot3DWidget
Definition: plot.py:309
jsk_rqt_plugins.plot.Plot3DWidget._buffer_length
_buffer_length
Definition: plot.py:315
rqt_gui_py::plugin
jsk_rqt_plugins.plot.Plot3DWidget._subscribed_topics_changed
def _subscribed_topics_changed(self)
Definition: plot.py:435
rqt_py_common::topic_completer
jsk_rqt_plugins.plot.Plot3DWidget.clean_up_subscribers
def clean_up_subscribers(self)
Definition: plot.py:476
jsk_rqt_plugins.plot.Plot3DWidget.on_topic_edit_textChanged
def on_topic_edit_textChanged(self, topic_name)
Definition: plot.py:389
jsk_rqt_plugins.plot.Plot3DWidget.dragEnterEvent
def dragEnterEvent(self, event)
Definition: plot.py:355
jsk_rqt_plugins.plot.MatDataPlot3D._canvas
_canvas
Definition: plot.py:113
jsk_rqt_plugins.plot.Plot3DWidget._update_plot_timer
_update_plot_timer
Definition: plot.py:346
rqt_py_common::topic_completer::TopicCompleter
jsk_rqt_plugins.plot.MatDataPlot3D.remove_curve
def remove_curve(self, curve_id)
Definition: plot.py:146
jsk_rqt_plugins.plot.Plot3DWidget.data_plot
data_plot
Definition: plot.py:326
jsk_rqt_plugins.plot.Plot3D.__init__
def __init__(self, context)
Definition: plot.py:237
jsk_rqt_plugins.plot.MatDataPlot3D._curves_verts
_curves_verts
Definition: plot.py:121


jsk_rqt_plugins
Author(s):
autogenerated on Fri Dec 13 2024 03:49:48