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
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056
00057
00058
00059
00060
00061
00062
00063
00064
00065 import os
00066 import math
00067 import codecs
00068 import threading
00069 import rospkg
00070 from rqt_bag import MessageView
00071
00072 from python_qt_binding import loadUi
00073 from python_qt_binding.QtCore import Qt, qWarning, Signal
00074 from python_qt_binding.QtGui import QWidget, QPushButton, QTreeWidget, QTreeWidgetItem, QSizePolicy, QDoubleValidator, QIcon
00075
00076 from rqt_plot.data_plot import DataPlot
00077
00078
00079 import rospy
00080
00081 class PlotView(MessageView):
00082 """
00083 Popup plot viewer
00084 """
00085 name = 'Plot'
00086
00087 def __init__(self, timeline, parent, topic):
00088 super(PlotView, self).__init__(timeline, topic)
00089
00090 self.plot_widget = PlotWidget(timeline, parent, topic)
00091
00092 parent.layout().addWidget(self.plot_widget)
00093
00094 def message_viewed(self, bag, msg_details):
00095 """
00096 refreshes the plot
00097 """
00098 _, msg, t = msg_details[:3]
00099
00100 if t is None:
00101 self.message_cleared()
00102 else:
00103 self.plot_widget.message_tree.set_message(msg)
00104 self.plot_widget.set_cursor((t-self.plot_widget.start_stamp).to_sec())
00105
00106 def message_cleared(self):
00107 pass
00108
00109 class PlotWidget(QWidget):
00110
00111 def __init__(self, timeline, parent, topic):
00112 super(PlotWidget, self).__init__(parent)
00113 self.setObjectName('PlotWidget')
00114
00115 self.timeline = timeline
00116 msg_type = self.timeline.get_datatype(topic)
00117 self.msgtopic = topic
00118 self.start_stamp = self.timeline._get_start_stamp()
00119 self.end_stamp = self.timeline._get_end_stamp()
00120
00121
00122
00123 self.limits = [0,(self.end_stamp-self.start_stamp).to_sec()]
00124
00125 rp = rospkg.RosPack()
00126 ui_file = os.path.join(rp.get_path('rqt_bag_plugins'), 'resource', 'plot.ui')
00127 loadUi(ui_file, self)
00128 self.message_tree = MessageTree(msg_type, self)
00129 self.data_tree_layout.addWidget(self.message_tree)
00130
00131
00132
00133 self.auto_res.stateChanged.connect(self.autoChanged)
00134
00135 self.resolution.editingFinished.connect(self.settingsChanged)
00136 self.resolution.setValidator(QDoubleValidator(0.0,1000.0,6,self.resolution))
00137
00138
00139 self.timeline.selected_region_changed.connect(self.region_changed)
00140
00141 self.recompute_timestep()
00142
00143 self.plot = DataPlot(self)
00144 self.plot.set_autoscale(x=False)
00145 self.plot.set_autoscale(y=DataPlot.SCALE_VISIBLE)
00146 self.plot.autoscroll(False)
00147 self.plot.set_xlim(self.limits)
00148 self.data_plot_layout.addWidget(self.plot)
00149
00150 self._home_button = QPushButton()
00151 self._home_button.setToolTip("Reset View")
00152 self._home_button.setIcon(QIcon.fromTheme('go-home'))
00153 self._home_button.clicked.connect(self.home)
00154 self.plot_toolbar_layout.addWidget(self._home_button)
00155
00156 self._config_button = QPushButton("Configure Plot")
00157 self._config_button.clicked.connect(self.plot.doSettingsDialog)
00158 self.plot_toolbar_layout.addWidget(self._config_button)
00159
00160 self.set_cursor(0)
00161
00162 self.paths_on = set()
00163 self._lines = None
00164
00165
00166 bag = None
00167 start_time = self.start_stamp
00168 while bag is None:
00169 bag,entry = self.timeline.get_entry(start_time, topic)
00170 if bag is None:
00171 start_time = self.timeline.get_entry_after(start_time)[1].time
00172
00173 self.bag = bag
00174
00175 msg = bag._read_message(entry.position)
00176 self.message_tree.set_message(msg[1])
00177
00178
00179 self.resampling_active = False
00180 self.resample_thread = None
00181 self.resample_fields = set()
00182
00183 def set_cursor(self, position):
00184 self.plot.vline(position, color=DataPlot.RED)
00185 self.plot.redraw()
00186
00187 def add_plot(self, path):
00188 self.resample_data([path])
00189
00190 def update_plot(self):
00191 if len(self.paths_on)>0:
00192 self.resample_data(self.paths_on)
00193
00194 def remove_plot(self, path):
00195 self.plot.remove_curve(path)
00196 self.paths_on.remove(path)
00197 self.plot.redraw()
00198
00199 def load_data(self):
00200 """get a generator for the specified time range on our bag"""
00201 return self.bag.read_messages(self.msgtopic,
00202 self.start_stamp+rospy.Duration.from_sec(self.limits[0]),
00203 self.start_stamp+rospy.Duration.from_sec(self.limits[1]))
00204
00205 def resample_data(self, fields):
00206 if self.resample_thread:
00207
00208 self.resampling_active = False
00209 self.resample_thread.join()
00210
00211 for f in fields:
00212 self.resample_fields.add(f)
00213
00214
00215 self.resampling_active = True
00216 self.resample_thread = threading.Thread(target=self._resample_thread)
00217
00218
00219 self.resample_thread.setDaemon(True)
00220 self.resample_thread.start()
00221
00222 def _resample_thread(self):
00223
00224
00225
00226
00227 x = {}
00228 y = {}
00229 for path in self.resample_fields:
00230 x[path] = []
00231 y[path] = []
00232
00233 msgdata = self.load_data()
00234
00235 for entry in msgdata:
00236
00237 if not self.resampling_active:
00238 return
00239
00240 for path in self.resample_fields:
00241
00242
00243
00244
00245
00246 if x[path]==[] or (entry[2]-self.start_stamp).to_sec()-x[path][-1] >= self.timestep:
00247 y_value = entry[1]
00248 for field in path.split('.'):
00249 index = None
00250 if field.endswith(']'):
00251 field = field[:-1]
00252 field, _, index = field.rpartition('[')
00253 y_value = getattr(y_value, field)
00254 if index:
00255 index = int(index)
00256 y_value = y_value[index]
00257 y[path].append(y_value)
00258 x[path].append((entry[2]-self.start_stamp).to_sec())
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270 for path in self.resample_fields:
00271 if len(x[path]) < 1:
00272 qWarning("Resampling resulted in 0 data points for %s" % path)
00273 else:
00274 if path in self.paths_on:
00275 self.plot.clear_values(path)
00276 self.plot.update_values(path, x[path], y[path])
00277 else:
00278 self.plot.add_curve(path, path, x[path], y[path])
00279 self.paths_on.add(path)
00280
00281 self.plot.redraw()
00282
00283 self.resample_fields.clear()
00284 self.resampling_active = False
00285
00286 def recompute_timestep(self):
00287
00288
00289 limits = self.limits
00290 if self.auto_res.isChecked():
00291 timestep = round((limits[1]-limits[0])/200.0,5)
00292 else:
00293 timestep = float(self.resolution.text())
00294 self.resolution.setText(str(timestep))
00295 self.timestep = timestep
00296
00297 def region_changed(self, start, end):
00298
00299 limits = [ (start - self.start_stamp).to_sec(),
00300 (end - self.start_stamp).to_sec() ]
00301
00302
00303 if limits[0]<0:
00304 limits = [0.0,limits[1]]
00305 if limits[1]>(self.end_stamp-self.start_stamp).to_sec():
00306 limits = [limits[0],(self.end_stamp-self.start_stamp).to_sec()]
00307
00308 self.limits = limits
00309
00310 self.recompute_timestep()
00311 self.plot.set_xlim(limits)
00312 self.plot.redraw()
00313 self.update_plot()
00314
00315 def settingsChanged(self):
00316
00317 self.recompute_timestep()
00318 self.update_plot()
00319
00320 def autoChanged(self, state):
00321 if state==2:
00322
00323 self.resolution.setDisabled(True)
00324 self.recompute_timestep()
00325 self.update_plot()
00326 else:
00327
00328
00329 self.resolution.setDisabled(False)
00330
00331 def home(self):
00332
00333
00334
00335
00336
00337 self.plot.set_xlim(self.limits)
00338
00339 self.plot.redraw()
00340
00341
00342
00343 class MessageTree(QTreeWidget):
00344 def __init__(self, msg_type, parent):
00345 super(MessageTree, self).__init__(parent)
00346 self.setSizePolicy(QSizePolicy.Expanding, QSizePolicy.Expanding)
00347 self.setHeaderHidden(True)
00348 self.itemChanged.connect(self.handleChanged)
00349 self._msg_type = msg_type
00350 self._msg = None
00351
00352 self._expanded_paths = None
00353 self._checked_states = set()
00354 self.plot_list = set()
00355
00356
00357
00358
00359 @property
00360 def msg(self):
00361 return self._msg
00362
00363 def set_message(self, msg):
00364
00365 if self._msg:
00366 for item in self.get_all_items():
00367 path = self.get_item_path(item)
00368 if item.isExpanded():
00369 self._expanded_paths.add(path)
00370 elif path in self._expanded_paths:
00371 self._expanded_paths.remove(path)
00372 if item.checkState(0)==Qt.Checked:
00373 self._checked_states.add(path)
00374 elif path in self._checked_states:
00375 self._checked_states.remove(path)
00376 self.clear()
00377 if msg:
00378
00379 self._add_msg_object(None, '', '', msg, msg._type)
00380
00381 if self._expanded_paths is None:
00382 self._expanded_paths = set()
00383 else:
00384
00385 for item in self.get_all_items():
00386 path = self.get_item_path(item)
00387 if path in self._expanded_paths:
00388 item.setExpanded(True)
00389 else:
00390 item.setExpanded(False)
00391 self._msg = msg
00392 self.update()
00393
00394 def get_item_path(self, item):
00395 return item.data(0, Qt.UserRole)[0].replace(' ', '')
00396
00397 def get_all_items(self):
00398 items = []
00399 try:
00400 root = self.invisibleRootItem()
00401 self.traverse(root, items.append)
00402 except Exception:
00403
00404 pass
00405 return items
00406
00407 def traverse(self, root, function):
00408 for i in range(root.childCount()):
00409 child = root.child(i)
00410 function(child)
00411 self.traverse(child, function)
00412
00413 def _add_msg_object(self, parent, path, name, obj, obj_type):
00414 label = name
00415
00416 if hasattr(obj, '__slots__'):
00417 subobjs = [(slot, getattr(obj, slot)) for slot in obj.__slots__]
00418 elif type(obj) in [list, tuple]:
00419 len_obj = len(obj)
00420 if len_obj == 0:
00421 subobjs = []
00422 else:
00423 w = int(math.ceil(math.log10(len_obj)))
00424 subobjs = [('[%*d]' % (w, i), subobj) for (i, subobj) in enumerate(obj)]
00425 else:
00426 subobjs = []
00427
00428 plotitem=False
00429 if type(obj) in [int, long, float]:
00430 plotitem=True
00431 if type(obj) == float:
00432 obj_repr = '%.6f' % obj
00433 else:
00434 obj_repr = str(obj)
00435
00436 if obj_repr[0] == '-':
00437 label += ': %s' % obj_repr
00438 else:
00439 label += ': %s' % obj_repr
00440
00441 elif type(obj) in [str, bool, int, long, float, complex, rospy.Time]:
00442
00443 obj_repr = codecs.utf_8_decode(str(obj), 'ignore')[0]
00444
00445
00446 if len(obj_repr) >= 50:
00447 obj_repr = obj_repr[:50] + '...'
00448
00449 label += ': ' + obj_repr
00450 item = QTreeWidgetItem([label])
00451 if name == '':
00452 pass
00453 elif path.find('.') == -1 and path.find('[') == -1:
00454 self.addTopLevelItem(item)
00455 else:
00456 parent.addChild(item)
00457 if plotitem == True:
00458 if path.replace(' ', '') in self._checked_states:
00459 item.setCheckState (0, Qt.Checked)
00460 else:
00461 item.setCheckState (0, Qt.Unchecked)
00462 item.setData(0, Qt.UserRole, (path, obj_type))
00463
00464
00465 for subobj_name, subobj in subobjs:
00466 if subobj is None:
00467 continue
00468
00469 if path == '':
00470 subpath = subobj_name
00471 elif subobj_name.startswith('['):
00472 subpath = '%s%s' % (path, subobj_name)
00473 else:
00474 subpath = '%s.%s' % (path, subobj_name)
00475
00476 if hasattr(subobj, '_type'):
00477 subobj_type = subobj._type
00478 else:
00479 subobj_type = type(subobj).__name__
00480
00481 self._add_msg_object(item, subpath, subobj_name, subobj, subobj_type)
00482
00483 def handleChanged(self, item, column):
00484 if item.data(0, Qt.UserRole)==None:
00485 pass
00486 else:
00487 path = self.get_item_path(item)
00488 if item.checkState(column) == Qt.Checked:
00489 if path not in self.plot_list:
00490 self.plot_list.add(path)
00491 self.parent().parent().parent().add_plot(path)
00492 if item.checkState(column) == Qt.Unchecked:
00493 if path in self.plot_list:
00494 self.plot_list.remove(path)
00495 self.parent().parent().parent().remove_plot(path)