dynamic_timeline_frame.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 from python_qt_binding.QtCore import qDebug, QPointF, QRectF, Qt, qWarning, Signal
34 from python_qt_binding.QtGui import QBrush, QCursor, QColor, QFont, \
35  QFontMetrics, QPen, QPolygonF
36 try: # indigo
37  from python_qt_binding.QtGui import QGraphicsItem
38 except ImportError: # kinetic+ (pyqt5)
39  from python_qt_binding.QtWidgets import QGraphicsItem
40 
41 import sys
42 import rospy
43 import bisect
44 import threading
45 
46 from rqt_bag.index_cache_thread import IndexCacheThread
47 from .plugins.raw_view import RawView
48 
49 
50 class _SelectionMode(object):
51  """
52  SelectionMode states consolidated for readability
53  NONE = no region marked or started
54  LEFT_MARKED = one end of the region has been marked
55  MARKED = both ends of the region have been marked
56  SHIFTING = region is marked; currently dragging the region
57  MOVE_LEFT = region is marked; currently changing the left boundry of the selected region
58  MOVE_RIGHT = region is marked; currently changing the right boundry of the selected region
59  """
60  NONE = 'none'
61  LEFT_MARKED = 'left marked'
62  MARKED = 'marked'
63  SHIFTING = 'shifting'
64  MOVE_LEFT = 'move left'
65  MOVE_RIGHT = 'move right'
66 
67 
68 class DynamicTimelineFrame(QGraphicsItem):
69  """
70  TimelineFrame Draws the framing elements for the bag messages
71  (time delimiters, labels, topic names and backgrounds).
72  Also handles mouse callbacks since they interact closely with the drawn elements
73  """
74  def __init__(self, dynamic_timeline):
75  super(DynamicTimelineFrame, self).__init__()
76  self._dynamic_timeline = dynamic_timeline
77  self._clicked_pos = None
78  self._dragged_pos = None
79 
80  # Timeline boundries
81  self._start_stamp = None # earliest of all stamps
82  self._end_stamp = None # latest of all stamps
83  self._stamp_left = None # earliest currently visible timestamp on the timeline
84  self._stamp_right = None # latest currently visible timestamp on the timeline
85  self._history_top = 30
86  self._history_left = 0
87 
88  self._history_width = 0
89  """Width of the history timeline in pixels."""
90 
91  self._history_bottom = 0
92  self._history_bounds = {}
93  self._margin_left = 4
94  self._margin_right = 20
95  self._margin_bottom = 20
96  self._history_top = 30
97 
98  # Background Rendering
99  self._bag_end_color = QColor(0, 0, 0, 25) # color of background of timeline before first message and after last
100  self._history_background_color_alternate = QColor(179, 179, 179, 25)
101  self._history_background_color = QColor(204, 204, 204, 102)
102 
103  # Timeline Division Rendering
104  # Possible time intervals used between divisions
105  # 1ms, 5ms, 10ms, 50ms, 100ms, 500ms
106  # 1s, 5s, 15s, 30s
107  # 1m, 2m, 5m, 10m, 15m, 30m
108  # 1h, 2h, 3h, 6h, 12h
109  # 1d, 7d
110  self._sec_divisions = [0.001, 0.005, 0.01, 0.05, 0.1, 0.5,
111  1, 5, 15, 30,
112  1 * 60, 2 * 60, 5 * 60, 10 * 60, 15 * 60, 30 * 60,
113  1 * 60 * 60, 2 * 60 * 60, 3 * 60 * 60, 6 * 60 * 60, 12 * 60 * 60,
114  1 * 60 * 60 * 24, 7 * 60 * 60 * 24]
115  self._minor_spacing = 15
116  self._major_spacing = 50
117  self._major_divisions_label_indent = 3 # padding in px between line and label
118  self._major_division_pen = QPen(QBrush(Qt.black), 0, Qt.DashLine)
119  self._minor_division_pen = QPen(QBrush(QColor(153, 153, 153, 128)), 0, Qt.DashLine)
120  self._minor_division_tick_pen = QPen(QBrush(QColor(128, 128, 128, 128)), 0)
121 
122  # Topic Rendering
123  self.topics = []
125  self._topic_font_height = None
126  self._topic_name_sizes = None
127  self._topic_name_spacing = 3 # minimum pixels between end of topic name and start of history
128  self._topic_font_size = 10.0
129  self._topic_font = QFont("cairo")
130  self._topic_font.setPointSize(self._topic_font_size)
131  self._topic_font.setBold(False)
133  self._topic_name_max_percent = 25.0 # percentage of the horiz space that can be used for topic display
134 
135  # Time Rendering
137  self._time_font_height = None
138  self._time_font_size = 10.0
139  self._time_font = QFont("cairo")
140  self._time_font.setPointSize(self._time_font_size)
141  self._time_font.setBold(False)
142 
143  # Defaults
144  self._default_brush = QBrush(Qt.black, Qt.SolidPattern)
145  self._default_pen = QPen(Qt.black)
146  self._default_datatype_color = QColor(0, 0, 102, 204)
148  'sensor_msgs/CameraInfo': QColor(0, 0, 77, 204),
149  'sensor_msgs/Image': QColor(0, 77, 77, 204),
150  'sensor_msgs/LaserScan': QColor(153, 0, 0, 204),
151  'pr2_msgs/LaserScannerSignal': QColor(153, 0, 0, 204),
152  'pr2_mechanism_msgs/MechanismState': QColor(0, 153, 0, 204),
153  'tf/tfMessage': QColor(0, 153, 0, 204),
154  }
155  self._default_msg_combine_px = 1.0 # minimum number of pixels allowed between two bag messages before they are combined
157 
158  # Selected Region Rendering
159  self._selected_region_color = QColor(0, 179, 0, 21)
160  self._selected_region_outline_top_color = QColor(0.0, 77, 0.0, 51)
161  self._selected_region_outline_ends_color = QColor(0.0, 77, 0.0, 102)
162  self._selecting_mode = _SelectionMode.NONE
163  self._selected_left = None
164  self._selected_right = None
166 
167  # Playhead Rendering
168  self._playhead = None # timestamp of the playhead
169  self._paused = False
172  self._playhead_color = QColor(255, 0, 0, 191)
173 
174  # Zoom
175  self._zoom_sensitivity = 0.005
176  self._min_zoom_speed = 0.5
177  self._max_zoom_speed = 2.0
178  self._min_zoom = 0.0001 # max zoom out (in px/s)
179  self._max_zoom = 50000.0 # max zoom in (in px/s)
180 
181  # Plugin management
182  self._viewer_types = {}
184  self._rendered_topics = set()
185  self.load_plugins()
186 
187  # Bag indexer for rendering the default message views on the timeline
188  self.index_cache_cv = threading.Condition()
189  self.index_cache = {}
190  self.invalidated_caches = set()
192 
193  # TODO the API interface should exist entirely at the bag_timeline level. Add a "get_draw_parameters()" at the bag_timeline level to access these
194  # Properties, work in progress API for plugins:
195 
196  # property: playhead
197  def _get_playhead(self):
198  return self._playhead
199 
200  def _set_playhead(self, playhead):
201  """
202  Sets the playhead to the new position, notifies the threads and updates the scene so it will redraw
203  :signal: emits status_bar_changed_signal if the playhead is successfully set
204  :param playhead: Time to set the playhead to, ''rospy.Time()''
205  """
206  with self.scene()._playhead_lock:
207  # do nothing if the playhead hasn't moved, or no messages were received yet
208  if playhead == self._playhead or self._stamp_right is None or self._stamp_left is None:
209  return
210 
211  self._playhead = playhead
212  if self._playhead != self._end_stamp:
213  self.scene().stick_to_end = False
214 
215  playhead_secs = playhead.to_sec()
216  if playhead_secs > self._stamp_right:
217  dstamp = playhead_secs - self._stamp_right + (self._stamp_right - self._stamp_left) * 0.75
218  if dstamp > self._end_stamp.to_sec() - self._stamp_right:
219  dstamp = self._end_stamp.to_sec() - self._stamp_right
220  self.translate_timeline(dstamp)
221 
222  elif playhead_secs < self._stamp_left:
223  dstamp = self._stamp_left - playhead_secs + (self._stamp_right - self._stamp_left) * 0.75
224  if dstamp > self._stamp_left - self._start_stamp.to_sec():
225  dstamp = self._stamp_left - self._start_stamp.to_sec()
226  self.translate_timeline(-dstamp)
227 
228  # Update the playhead positions
229  for topic in self.topics:
230  entry = self.scene().get_entry(self._playhead, topic)
231  if entry:
232  if topic in self.scene()._playhead_positions and self.scene()._playhead_positions[topic] == entry.stamp:
233  continue
234  new_playhead_position = entry.stamp
235  else:
236  new_playhead_position = (None, None)
237  with self.scene()._playhead_positions_cvs[topic]:
238  self.scene()._playhead_positions[topic] = new_playhead_position
239  self.scene()._playhead_positions_cvs[topic].notify_all() # notify all message loaders that a new message needs to be loaded
240  self.scene().update()
241  self.scene().status_bar_changed_signal.emit()
242 
243  playhead = property(_get_playhead, _set_playhead)
244 
245  # TODO add more api variables here to allow plugin access
246  @property
247  def _history_right(self):
248  return self._history_left + self._history_width
249 
250  @property
252  return self._selected_left is not None and self._selected_right is not None
253 
254  @property
255  def play_region(self):
256  if self.has_selected_region:
257  return (rospy.Time.from_sec(self._selected_left), rospy.Time.from_sec(self._selected_right))
258  else:
259  return (self._start_stamp, self._end_stamp)
260 
261  def emit_play_region(self):
262  play_region = self.play_region
263  if(play_region[0] is not None and play_region[1] is not None):
264  self.scene().selected_region_changed.emit(*play_region)
265 
266  @property
267  def start_stamp(self):
268  return self._start_stamp
269 
270  @property
271  def end_stamp(self):
272  return self._end_stamp
273 
274  # QGraphicsItem implementation
275  def boundingRect(self):
276  return QRectF(0, 0, self._history_left + self._history_width + self._margin_right, self._history_bottom + self._margin_bottom)
277 
278  def paint(self, painter, option, widget):
279  if self._start_stamp is None:
280  return
281 
282  self._layout()
283  self._draw_topic_dividers(painter)
284  self._draw_selected_region(painter)
285  self._draw_time_divisions(painter)
286  self._draw_topic_histories(painter)
287  self._draw_bag_ends(painter)
288  self._draw_topic_names(painter)
289  self._draw_history_border(painter)
290  self._draw_playhead(painter)
291  # END QGraphicsItem implementation
292 
293  # Drawing Functions
294 
295  def _qfont_width(self, name):
296  return QFontMetrics(self._topic_font).width(name)
297 
298  def _trimmed_topic_name(self, topic_name):
299  """
300  This function trims the topic name down to a reasonable percentage of the viewable scene area
301  """
302  allowed_width = self._scene_width * (self._topic_name_max_percent / 100.0)
303  allowed_width = allowed_width - self._topic_name_spacing - self._margin_left
304  trimmed_return = topic_name
305  if allowed_width < self._qfont_width(topic_name):
306  # We need to trim the topic
307  trimmed = ''
308  split_name = topic_name.split('/')
309  split_name = filter(lambda a: a != '', split_name)
310  if sys.version_info[0] > 2:
311  split_name = [n for n in split_name]
312  # Save important last element of topic name provided it is small
313  popped_last = False
314  if self._qfont_width(split_name[-1]) < .5 * allowed_width:
315  popped_last = True
316  last_item = split_name[-1]
317  split_name = split_name[:-1]
318  allowed_width = allowed_width - self._qfont_width(last_item)
319  # Shorten and add remaining items keeping lenths roughly equal
320  for item in split_name:
321  if self._qfont_width(item) > allowed_width / float(len(split_name)):
322  trimmed_item = item[:-3] + '..'
323  while self._qfont_width(trimmed_item) > allowed_width / float(len(split_name)):
324  if len(trimmed_item) >= 3:
325  trimmed_item = trimmed_item[:-3] + '..'
326  else:
327  break
328  trimmed = trimmed + '/' + trimmed_item
329  else:
330  trimmed = trimmed + '/' + item
331  if popped_last:
332  trimmed = trimmed + '/' + last_item
333  trimmed = trimmed[1:]
334  trimmed_return = trimmed
335  return trimmed_return
336 
337  def _layout(self):
338  """
339  Recalculates the layout of the of the timeline to take into account any changes that have occured
340  """
341  # Calculate history left and history width
342  self._scene_width = self.scene().views()[0].size().width()
343 
344  max_topic_name_width = -1
345  for topic in self.topics:
346  topic_width = self._qfont_width(self._trimmed_topic_name(topic))
347  if max_topic_name_width <= topic_width:
348  max_topic_name_width = topic_width
349 
350  # Calculate font height for each topic
351  self._topic_font_height = -1
352  for topic in self.topics:
353  topic_height = QFontMetrics(self._topic_font).height()
354  if self._topic_font_height <= topic_height:
355  self._topic_font_height = topic_height
356 
357  # Update the timeline boundries
358  new_history_left = self._margin_left + max_topic_name_width + self._topic_name_spacing
359  new_history_width = self._scene_width - new_history_left - self._margin_right
360  self._history_left = new_history_left
361  self._history_width = new_history_width
362 
363  # Calculate the bounds for each topic
364  self._history_bounds = {}
365  y = self._history_top
366  for topic in self.topics:
367  datatype = self.scene().get_datatype(topic)
368 
369  topic_height = None
370  if topic in self._rendered_topics:
371  renderer = self._timeline_renderers.get(datatype)
372  if renderer:
373  topic_height = renderer.get_segment_height(topic)
374  if not topic_height:
375  topic_height = self._topic_font_height + self._topic_vertical_padding
376 
377  self._history_bounds[topic] = (self._history_left, y, self._history_width, topic_height)
378 
379  y += topic_height
380 
381 # new_history_bottom = max([y + h for (x, y, w, h) in self._history_bounds.values()]) - 1
382  new_history_bottom = max([y + h for (_, y, _, h) in self._history_bounds.values()]) - 1
383  if new_history_bottom != self._history_bottom:
384  self._history_bottom = new_history_bottom
385 
386  def _draw_topic_histories(self, painter):
387  """
388  Draw all topic messages
389  :param painter: allows access to paint functions,''QPainter''
390  """
391  for topic in sorted(self._history_bounds.keys()):
392  self._draw_topic_history(painter, topic)
393 
394  def _draw_topic_history(self, painter, topic):
395  """
396  Draw boxes corrisponding to message regions on the timeline.
397  :param painter: allows access to paint functions,''QPainter''
398  :param topic: the topic for which message boxes should be drawn, ''str''
399  """
400 
401 # x, y, w, h = self._history_bounds[topic]
402  _, y, _, h = self._history_bounds[topic]
403 
404  msg_y = y + 2
405  msg_height = h - 2
406 
407  datatype = self.scene().get_datatype(topic)
408 
409  # Get the renderer and the message combine interval
410  renderer = None
411  msg_combine_interval = None
412  if topic in self._rendered_topics:
413  renderer = self._timeline_renderers.get(datatype)
414  if renderer is not None:
415  msg_combine_interval = self.map_dx_to_dstamp(renderer.msg_combine_px)
416  if msg_combine_interval is None:
417  msg_combine_interval = self.map_dx_to_dstamp(self._default_msg_combine_px)
418 
419  # Get the cache
420  if topic not in self.index_cache:
421  return
422  all_stamps = self.index_cache[topic]
423 
424 # start_index = bisect.bisect_left(all_stamps, self._stamp_left)
425  end_index = bisect.bisect_left(all_stamps, self._stamp_right)
426  # Set pen based on datatype
427  datatype_color = self._datatype_colors.get(datatype, self._default_datatype_color)
428  # Iterate through regions of connected messages
429  width_interval = self._history_width / (self._stamp_right - self._stamp_left)
430 
431  # Draw stamps
432  for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], self.map_dx_to_dstamp(self._default_msg_combine_px)):
433  if stamp_end < self._stamp_left:
434  continue
435 
436  region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
437  if region_x_start < self._history_left:
438  region_x_start = self._history_left # Clip the region
439  region_x_end = self._history_left + (stamp_end - self._stamp_left) * width_interval
440  region_width = max(1, region_x_end - region_x_start)
441 
442  painter.setBrush(QBrush(datatype_color))
443  painter.setPen(QPen(datatype_color, 1))
444  painter.drawRect(region_x_start, msg_y, region_width, msg_height)
445 
446  # Draw active message
447  if topic in self.scene()._listeners:
448  curpen = painter.pen()
449  oldwidth = curpen.width()
450  curpen.setWidth(self._active_message_line_width)
451  painter.setPen(curpen)
452  playhead_stamp = None
453  playhead_index = bisect.bisect_right(all_stamps, self.playhead.to_sec()) - 1
454 
455  if playhead_index >= 0:
456  playhead_stamp = all_stamps[playhead_index]
457  if playhead_stamp > self._stamp_left and playhead_stamp < self._stamp_right:
458  playhead_x = self._history_left + (all_stamps[playhead_index] - self._stamp_left) * width_interval
459  painter.drawLine(playhead_x, msg_y, playhead_x, msg_y + msg_height)
460  curpen.setWidth(oldwidth)
461  painter.setPen(curpen)
462 
463  # Custom renderer
464  if renderer:
465  # Iterate through regions of connected messages
466  for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], msg_combine_interval):
467  if stamp_end < self._stamp_left:
468  continue
469 
470  region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
471  region_x_end = self._history_left + (stamp_end - self._stamp_left) * width_interval
472  region_width = max(1, region_x_end - region_x_start)
473  renderer.draw_timeline_segment(painter, topic, stamp_start, stamp_end, region_x_start, msg_y, region_width, msg_height)
474 
475  painter.setBrush(self._default_brush)
476  painter.setPen(self._default_pen)
477 
478  def _draw_bag_ends(self, painter):
479  """
480  Draw markers to indicate the area the bag file represents within the current visible area.
481  :param painter: allows access to paint functions,''QPainter''
482  """
483  x_start, x_end = self.map_stamp_to_x(self._start_stamp.to_sec()), self.map_stamp_to_x(self._end_stamp.to_sec())
484  painter.setBrush(QBrush(self._bag_end_color))
485  painter.drawRect(self._history_left, self._history_top, x_start - self._history_left, self._history_bottom - self._history_top)
486  painter.drawRect(x_end, self._history_top, self._history_left + self._history_width - x_end, self._history_bottom - self._history_top)
487  painter.setBrush(self._default_brush)
488  painter.setPen(self._default_pen)
489 
490  def _draw_topic_dividers(self, painter):
491  """
492  Draws horizontal lines between each topic to visually separate the messages
493  :param painter: allows access to paint functions,''QPainter''
494  """
495  clip_left = self._history_left
496  clip_right = self._history_left + self._history_width
497 
498  row = 0
499  for topic in self.topics:
500  (x, y, w, h) = self._history_bounds[topic]
501 
502  if row % 2 == 0:
503  painter.setPen(Qt.lightGray)
504  painter.setBrush(QBrush(self._history_background_color_alternate))
505  else:
506  painter.setPen(Qt.lightGray)
507  painter.setBrush(QBrush(self._history_background_color))
508  left = max(clip_left, x)
509  painter.drawRect(left, y, min(clip_right - left, w), h)
510  row += 1
511  painter.setBrush(self._default_brush)
512  painter.setPen(self._default_pen)
513 
514  def _draw_selected_region(self, painter):
515  """
516  Draws a box around the selected region
517  :param painter: allows access to paint functions,''QPainter''
518  """
519  if self._selected_left is None:
520  return
521 
522  x_left = self.map_stamp_to_x(self._selected_left)
523  if self._selected_right is not None:
524  x_right = self.map_stamp_to_x(self._selected_right)
525  else:
526  x_right = self.map_stamp_to_x(self.playhead.to_sec())
527 
528  left = x_left
529  top = self._history_top - self._playhead_pointer_size[1] - 5 - self._time_font_size - 4
530  width = x_right - x_left
531  height = self._history_top - top
532 
533  painter.setPen(self._selected_region_color)
534  painter.setBrush(QBrush(self._selected_region_color))
535  painter.drawRect(left, top, width, height)
536 
537  painter.setPen(self._selected_region_outline_ends_color)
538  painter.setBrush(Qt.NoBrush)
539  painter.drawLine(left, top, left, top + height)
540  painter.drawLine(left + width, top, left + width, top + height)
541 
542  painter.setPen(self._selected_region_outline_top_color)
543  painter.setBrush(Qt.NoBrush)
544  painter.drawLine(left, top, left + width, top)
545 
546  painter.setPen(self._selected_region_outline_top_color)
547  painter.drawLine(left, self._history_top, left, self._history_bottom)
548  painter.drawLine(left + width, self._history_top, left + width, self._history_bottom)
549 
550  painter.setBrush(self._default_brush)
551  painter.setPen(self._default_pen)
552 
553  def _draw_playhead(self, painter):
554  """
555  Draw a line and 2 triangles to denote the current position being viewed
556  :param painter: ,''QPainter''
557  """
558  px = self.map_stamp_to_x(self.playhead.to_sec())
559  pw, ph = self._playhead_pointer_size
560 
561  # Line
562  painter.setPen(QPen(self._playhead_color))
563  painter.setBrush(QBrush(self._playhead_color))
564  painter.drawLine(px, self._history_top - 1, px, self._history_bottom + 2)
565 
566  # Upper triangle
567  py = self._history_top - ph
568  painter.drawPolygon(QPolygonF([QPointF(px, py + ph), QPointF(px + pw, py), QPointF(px - pw, py)]))
569 
570  # Lower triangle
571  py = self._history_bottom + 1
572  painter.drawPolygon(QPolygonF([QPointF(px, py), QPointF(px + pw, py + ph), QPointF(px - pw, py + ph)]))
573 
574  painter.setBrush(self._default_brush)
575  painter.setPen(self._default_pen)
576 
577  def _draw_history_border(self, painter):
578  """
579  Draw a simple black rectangle frame around the timeline view area
580  :param painter: ,''QPainter''
581  """
582  bounds_width = min(self._history_width, self.scene().width())
583  x, y, w, h = self._history_left, self._history_top, bounds_width, self._history_bottom - self._history_top
584 
585  painter.setBrush(Qt.NoBrush)
586  painter.setPen(Qt.black)
587  painter.drawRect(x, y, w, h)
588  painter.setBrush(self._default_brush)
589  painter.setPen(self._default_pen)
590 
591  def _draw_topic_names(self, painter):
592  """
593  Calculate positions of existing topic names and draw them on the left, one for each row
594  :param painter: ,''QPainter''
595  """
596  topics = self._history_bounds.keys()
597  coords = [(self._margin_left, y + (h / 2) + (self._topic_font_height / 2)) for (_, y, _, h) in self._history_bounds.values()]
598 
599  for text, coords in zip([t.lstrip('/') for t in topics], coords):
600  painter.setBrush(self._default_brush)
601  painter.setPen(self._default_pen)
602  painter.setFont(self._topic_font)
603  painter.drawText(coords[0], coords[1], self._trimmed_topic_name(text))
604 
605  def _draw_time_divisions(self, painter):
606  """
607  Draw vertical grid-lines showing major and minor time divisions.
608  :param painter: allows access to paint functions,''QPainter''
609  """
610  x_per_sec = self.map_dstamp_to_dx(1.0)
611  major_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._major_spacing]
612  if len(major_divisions) == 0:
613  major_division = max(self._sec_divisions)
614  else:
615  major_division = min(major_divisions)
616 
617  minor_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._minor_spacing and major_division % s == 0]
618  if len(minor_divisions) > 0:
619  minor_division = min(minor_divisions)
620  else:
621  minor_division = None
622 
623  start_stamp = self._start_stamp.to_sec()
624 
625  major_stamps = list(self._get_stamps(start_stamp, major_division))
626  self._draw_major_divisions(painter, major_stamps, start_stamp, major_division)
627 
628  if minor_division:
629  minor_stamps = [s for s in self._get_stamps(start_stamp, minor_division) if s not in major_stamps]
630  self._draw_minor_divisions(painter, minor_stamps, start_stamp, minor_division)
631 
632  def _draw_major_divisions(self, painter, stamps, start_stamp, division):
633  """
634  Draw black hashed vertical grid-lines showing major time divisions.
635  :param painter: allows access to paint functions,''QPainter''
636  """
637  label_y = self._history_top - self._playhead_pointer_size[1] - 5
638  for stamp in stamps:
639  x = self.map_stamp_to_x(stamp, False)
640 
641  label = self._get_label(division, stamp - start_stamp)
642  label_x = x + self._major_divisions_label_indent
643  if label_x + self._qfont_width(label) < self.scene().width():
644  painter.setBrush(self._default_brush)
645  painter.setPen(self._default_pen)
646  painter.setFont(self._time_font)
647  painter.drawText(label_x, label_y, label)
648 
649  painter.setPen(self._major_division_pen)
650  painter.drawLine(x, label_y - self._time_tick_height - self._time_font_size, x, self._history_bottom)
651 
652  painter.setBrush(self._default_brush)
653  painter.setPen(self._default_pen)
654 
655  def _draw_minor_divisions(self, painter, stamps, start_stamp, division):
656  """
657  Draw grey hashed vertical grid-lines showing minor time divisions.
658  :param painter: allows access to paint functions,''QPainter''
659  """
660  xs = [self.map_stamp_to_x(stamp) for stamp in stamps]
661  painter.setPen(self._minor_division_pen)
662  for x in xs:
663  painter.drawLine(x, self._history_top, x, self._history_bottom)
664 
665  painter.setPen(self._minor_division_tick_pen)
666  for x in xs:
667  painter.drawLine(x, self._history_top - self._time_tick_height, x, self._history_top)
668 
669  painter.setBrush(self._default_brush)
670  painter.setPen(self._default_pen)
671 
672  # Close function
673 
674  def handle_close(self):
675  for renderer in self._timeline_renderers.values():
676  renderer.close()
677  self._index_cache_thread.stop()
678 
679  # Plugin interaction functions
680 
681  def get_viewer_types(self, datatype):
682  return [RawView] + self._viewer_types.get('*', []) + self._viewer_types.get(datatype, [])
683 
684  def load_plugins(self):
685  from rqt_gui.rospkg_plugin_provider import RospkgPluginProvider
686  self.plugin_provider = RospkgPluginProvider('rqt_bag', 'rqt_bag::Plugin')
687 
688  plugin_descriptors = self.plugin_provider.discover(None)
689  for plugin_descriptor in plugin_descriptors:
690  try:
691  plugin = self.plugin_provider.load(plugin_descriptor.plugin_id(), plugin_context=None)
692  except Exception as e:
693  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to load plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
694  continue
695  try:
696  view = plugin.get_view_class()
697  except Exception as e:
698  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to get view from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
699  continue
700 
701  timeline_renderer = None
702  try:
703  timeline_renderer = plugin.get_renderer_class()
704  except AttributeError:
705  pass
706  except Exception as e:
707  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to get renderer from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
708 
709  msg_types = []
710  try:
711  msg_types = plugin.get_message_types()
712  except AttributeError:
713  pass
714  except Exception as e:
715  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to get message types from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
716  finally:
717  if not msg_types:
718  qWarning('rqt_bag.TimelineFrame.load_plugins() plugin "%s" declares no message types:\n%s' % (plugin_descriptor.plugin_id(), e))
719 
720  for msg_type in msg_types:
721  self._viewer_types.setdefault(msg_type, []).append(view)
722  if timeline_renderer:
723  self._timeline_renderers[msg_type] = timeline_renderer(self)
724 
725  qDebug('rqt_bag.TimelineFrame.load_plugins() loaded plugin "%s"' % plugin_descriptor.plugin_id())
726 
727  # Timeline renderer interaction functions
728 
729  def get_renderers(self):
730  """
731  :returns: a list of the currently loaded renderers for the plugins
732  """
733  renderers = []
734 
735  for topic in self.topics:
736  datatype = self.scene().get_datatype(topic)
737  renderer = self._timeline_renderers.get(datatype)
738  if renderer is not None:
739  renderers.append((topic, renderer))
740  return renderers
741 
742  def is_renderer_active(self, topic):
743  return topic in self._rendered_topics
744 
745  def toggle_renderers(self):
746  idle_renderers = len(self._rendered_topics) < len(self.topics)
747 
748  self.set_renderers_active(idle_renderers)
749 
750  def set_renderers_active(self, active):
751  if active:
752  for topic in self.topics:
753  self._rendered_topics.add(topic)
754  else:
755  self._rendered_topics.clear()
756  self.scene().update()
757 
758  def set_renderer_active(self, topic, active):
759  if active:
760  if topic in self._rendered_topics:
761  return
762  self._rendered_topics.add(topic)
763  else:
764  if topic not in self._rendered_topics:
765  return
766  self._rendered_topics.remove(topic)
767  self.scene().update()
768 
769  # Index Caching functions
770 
771  def _update_index_cache(self, topic):
772  """
773  Updates the cache of message timestamps for the given topic.
774  :return: number of messages added to the index cache
775  """
776  if self._start_stamp is None or self._end_stamp is None:
777  return 0
778 
779  if topic not in self.index_cache:
780  # Don't have any cache of messages in this topic
781  start_time = self._start_stamp
782  topic_cache = []
783  self.index_cache[topic] = topic_cache
784  else:
785  topic_cache = self.index_cache[topic]
786 
787  # Check if the cache has been invalidated
788  if topic not in self.invalidated_caches:
789  return 0
790 
791  if len(topic_cache) == 0:
792  start_time = self._start_stamp
793  else:
794  start_time = rospy.Time.from_sec(max(0.0, topic_cache[-1]))
795 
796  end_time = self._end_stamp
797 
798  topic_cache_len = len(topic_cache)
799 
800  for entry in self.scene().get_entries([topic], start_time, end_time):
801  topic_cache.append(entry.stamp.to_sec())
802 
803  if topic in self.invalidated_caches:
804  self.invalidated_caches.remove(topic)
805 
806  return len(topic_cache) - topic_cache_len
807 
808  def _find_regions(self, stamps, max_interval):
809  """
810  Group timestamps into regions connected by timestamps less than max_interval secs apart.
811  If no other timestamps are within the interval, then return start = end.
812  :param float[] start_stamp:
813  :param float max_interval: maximum size of each region
814  """
815  region_start, prev_stamp = None, None
816  for stamp in stamps:
817  if prev_stamp:
818  if stamp - prev_stamp > max_interval:
819  region_end = prev_stamp
820  yield (region_start, region_end)
821  region_start = stamp
822  else:
823  region_start = stamp
824 
825  prev_stamp = stamp
826 
827  if region_start and prev_stamp:
828  yield (region_start, prev_stamp)
829 
830  def _get_stamps(self, start_stamp, stamp_step):
831  """
832  Generate visible stamps every stamp_step
833  :param start_stamp: beginning of timeline stamp, ''int''
834  :param stamp_step: seconds between each division, ''int''
835  """
836  if start_stamp >= self._stamp_left:
837  stamp = start_stamp
838  else:
839  stamp = start_stamp + int((self._stamp_left - start_stamp) / stamp_step) * stamp_step + stamp_step
840 
841  while stamp < self._stamp_right:
842  yield stamp
843  stamp += stamp_step
844 
845  def _get_label(self, division, elapsed):
846  """
847  :param division: number of seconds in a division, ''int''
848  :param elapsed: seconds from the beginning, ''int''
849  :returns: relevent time elapsed string, ''str''
850  """
851  secs = int(elapsed) % 60
852 
853  mins = int(elapsed) / 60
854  hrs = mins / 60
855  days = hrs / 24
856  weeks = days / 7
857 
858  if division >= 7 * 24 * 60 * 60: # >1wk divisions: show weeks
859  return '%dw' % weeks
860  elif division >= 24 * 60 * 60: # >24h divisions: show days
861  return '%dd' % days
862  elif division >= 60 * 60: # >1h divisions: show hours
863  return '%dh' % hrs
864  elif division >= 5 * 60: # >5m divisions: show minutes
865  return '%dm' % mins
866  elif division >= 1: # >1s divisions: show minutes:seconds
867  return '%dm%02ds' % (mins, secs)
868  elif division >= 0.1: # >0.1s divisions: show seconds.0
869  return '%d.%ss' % (secs, str(int(10.0 * (elapsed - int(elapsed)))))
870  elif division >= 0.01: # >0.1s divisions: show seconds.0
871  return '%d.%02ds' % (secs, int(100.0 * (elapsed - int(elapsed))))
872  else: # show seconds.00
873  return '%d.%03ds' % (secs, int(1000.0 * (elapsed - int(elapsed))))
874 
875  # Pixel location/time conversion functions
876  def map_x_to_stamp(self, x, clamp_to_visible=True):
877  """
878  converts a pixel x value to a stamp
879  :param x: pixel value to be converted, ''int''
880  :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool''
881  :returns: timestamp, ''int''
882  """
883  fraction = float(x - self._history_left) / self._history_width
884 
885  if clamp_to_visible:
886  if fraction <= 0.0:
887  return self._stamp_left
888  elif fraction >= 1.0:
889  return self._stamp_right
890 
891  return self._stamp_left + fraction * (self._stamp_right - self._stamp_left)
892 
893  def map_dx_to_dstamp(self, dx):
894  """
895  converts a distance in pixel space to a distance in stamp space
896  :param dx: distance in pixel space to be converted, ''int''
897  :returns: distance in stamp space, ''float''
898  """
899  return float(dx) * (self._stamp_right - self._stamp_left) / self._history_width
900 
901  def map_stamp_to_x(self, stamp, clamp_to_visible=True):
902  """
903  converts a timestamp to the x value where that stamp exists in the timeline
904  :param stamp: timestamp to be converted, ''int''
905  :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool''
906  :returns: # of pixels from the left boarder, ''int''
907  """
908  if self._stamp_left is None:
909  return None
910  fraction = (stamp - self._stamp_left) / (self._stamp_right - self._stamp_left)
911 
912  if clamp_to_visible:
913  fraction = min(1.0, max(0.0, fraction))
914 
915  return self._history_left + fraction * self._history_width
916 
917  def map_dstamp_to_dx(self, dstamp):
918  return (float(dstamp) * self._history_width) / (self._stamp_right - self._stamp_left)
919 
920  def map_y_to_topic(self, y):
921  for topic in self._history_bounds:
922  x, topic_y, w, topic_h = self._history_bounds[topic]
923  if y > topic_y and y <= topic_y + topic_h:
924  return topic
925  return None
926 
927  # View port manipulation functions
928  def reset_timeline(self):
929  self.reset_zoom()
930 
931  self._selected_left = None
932  self._selected_right = None
933  self._selecting_mode = _SelectionMode.NONE
934 
935  self.emit_play_region()
936 
937  if self._stamp_left is not None:
938  self.playhead = rospy.Time.from_sec(self._stamp_left)
939 
940  def set_timeline_view(self, stamp_left, stamp_right):
941  self._stamp_left = stamp_left
942  self._stamp_right = stamp_right
943 
944  def translate_timeline(self, dstamp):
945  self.set_timeline_view(self._stamp_left + dstamp, self._stamp_right + dstamp)
946  self.scene().update()
947 
949  self.translate_timeline((self._stamp_right - self._stamp_left) * -0.05)
950 
952  self.translate_timeline((self._stamp_right - self._stamp_left) * 0.05)
953 
954  # Zoom functions
955  def reset_zoom(self):
956  start_stamp, end_stamp = self._start_stamp, self._end_stamp
957  if start_stamp is None:
958  return
959 
960  # if you just want the timeline to grow dynamically, leave this out
961 # if (end_stamp - start_stamp) < rospy.Duration.from_sec(5.0):
962 # end_stamp = start_stamp + rospy.Duration.from_sec(5.0)
963  # make sure at least that the difference is non-zero
964  if end_stamp == start_stamp:
965  end_stamp = start_stamp + rospy.Duration.from_sec(1.0)
966 
967  self.set_timeline_view(start_stamp.to_sec(), end_stamp.to_sec())
968  self.scene().update()
969 
970  def zoom_in(self):
971  self.zoom_timeline(0.5)
972 
973  def zoom_out(self):
974  self.zoom_timeline(2.0)
975 
976  def can_zoom_in(self):
977  return self.can_zoom(0.5)
978 
979  def can_zoom_out(self):
980  return self.can_zoom(2.0)
981 
982  def can_zoom(self, desired_zoom):
983  if not self._stamp_left or not self.playhead:
984  return False
985 
986  new_interval = self.get_zoom_interval(desired_zoom)
987  if not new_interval:
988  return False
989 
990  new_range = new_interval[1] - new_interval[0]
991  curr_range = self._stamp_right - self._stamp_left
992  actual_zoom = new_range / curr_range
993 
994  if desired_zoom < 1.0:
995  return actual_zoom < 0.95
996  else:
997  return actual_zoom > 1.05
998 
999  def zoom_timeline(self, zoom, center=None):
1000  interval = self.get_zoom_interval(zoom, center)
1001  if not interval:
1002  return
1003 
1004  self._stamp_left, self._stamp_right = interval
1005 
1006  self.scene().update()
1007 
1008  def get_zoom_interval(self, zoom, center=None):
1009  """
1010  @rtype: tuple
1011  @requires: left & right zoom interval sizes.
1012  """
1013  if self._stamp_left is None:
1014  return None
1015 
1016  stamp_interval = self._stamp_right - self._stamp_left
1017  if center is None:
1018  center = self.playhead.to_sec()
1019  center_frac = (center - self._stamp_left) / stamp_interval
1020 
1021  new_stamp_interval = zoom * stamp_interval
1022  if new_stamp_interval == 0:
1023  return None
1024  # Enforce zoom limits
1025  px_per_sec = self._history_width / new_stamp_interval
1026  if px_per_sec < self._min_zoom:
1027  new_stamp_interval = self._history_width / self._min_zoom
1028  elif px_per_sec > self._max_zoom:
1029  new_stamp_interval = self._history_width / self._max_zoom
1030 
1031  left = center - center_frac * new_stamp_interval
1032  right = left + new_stamp_interval
1033 
1034  return (left, right)
1035 
1036  def pause(self):
1037  self._paused = True
1038 
1039  def resume(self):
1040  self._paused = False
1041  self._dynamic_timeline.resume()
1042 
1043  # Mouse event handlers
1044  def on_middle_down(self, event):
1045  self._clicked_pos = self._dragged_pos = event.pos()
1046  self.pause()
1047 
1048  def on_left_down(self, event):
1049  if self.playhead is None:
1050  return
1051 
1052  self._clicked_pos = self._dragged_pos = event.pos()
1053 
1054  self.pause()
1055 
1056  if event.modifiers() == Qt.ShiftModifier:
1057  return
1058 
1059  x = self._clicked_pos.x()
1060  y = self._clicked_pos.y()
1061  if x >= self._history_left and x <= self._history_right:
1062  if y >= self._history_top and y <= self._history_bottom:
1063  # Clicked within timeline - set playhead
1064  playhead_secs = self.map_x_to_stamp(x)
1065  if playhead_secs <= 0.0:
1066  self.playhead = rospy.Time(0, 1)
1067  else:
1068  self.playhead = rospy.Time.from_sec(playhead_secs)
1069  self.scene().update()
1070 
1071  elif y <= self._history_top:
1072  # Clicked above timeline
1073  if self._selecting_mode == _SelectionMode.NONE:
1074  self._selected_left = None
1075  self._selected_right = None
1076  self._selecting_mode = _SelectionMode.LEFT_MARKED
1077  self.scene().update()
1078  self.emit_play_region()
1079 
1080  elif self._selecting_mode == _SelectionMode.MARKED:
1081  left_x = self.map_stamp_to_x(self._selected_left)
1082  right_x = self.map_stamp_to_x(self._selected_right)
1083  if x < left_x - self._selection_handle_width or x > right_x + self._selection_handle_width:
1084  self._selected_left = None
1085  self._selected_right = None
1086  self._selecting_mode = _SelectionMode.LEFT_MARKED
1087  self.scene().update()
1088  self.emit_play_region()
1089  elif self._selecting_mode == _SelectionMode.SHIFTING:
1090  self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1091 
1092  def on_mouse_up(self, event):
1093  self.resume()
1094 
1095  if self._selecting_mode in [_SelectionMode.LEFT_MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1096  if self._selected_left is None:
1097  self._selecting_mode = _SelectionMode.NONE
1098  else:
1099  self._selecting_mode = _SelectionMode.MARKED
1100  self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1101  self.scene().update()
1102 
1103  def on_mousewheel(self, event):
1104  dz = event.delta() / 120.0
1105  self.zoom_timeline(1.0 - dz * 0.2)
1106 
1107  def on_mouse_move(self, event):
1108  if not self._history_left: # TODO: need a better notion of initialized
1109  return
1110 
1111  x = event.pos().x()
1112  y = event.pos().y()
1113 
1114  if event.buttons() == Qt.NoButton:
1115  # Mouse moving
1116  if self._selecting_mode in [_SelectionMode.MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1117  if y <= self._history_top and self._selected_left is not None:
1118  left_x = self.map_stamp_to_x(self._selected_left)
1119  right_x = self.map_stamp_to_x(self._selected_right)
1120 
1121  if abs(x - left_x) <= self._selection_handle_width:
1122  self._selecting_mode = _SelectionMode.MOVE_LEFT
1123  self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1124  return
1125  elif abs(x - right_x) <= self._selection_handle_width:
1126  self._selecting_mode = _SelectionMode.MOVE_RIGHT
1127  self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1128  return
1129  elif x > left_x and x < right_x:
1130  self._selecting_mode = _SelectionMode.SHIFTING
1131  self.scene().views()[0].setCursor(QCursor(Qt.OpenHandCursor))
1132  return
1133  else:
1134  self._selecting_mode = _SelectionMode.MARKED
1135  self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1136  else:
1137  # Mouse dragging
1138  if event.buttons() == Qt.MidButton or event.modifiers() == Qt.ShiftModifier:
1139  # Middle or shift: zoom and pan
1140  dx_drag, dy_drag = x - self._dragged_pos.x(), y - self._dragged_pos.y()
1141 
1142  if dx_drag != 0:
1143  self.translate_timeline(-self.map_dx_to_dstamp(dx_drag))
1144  if (dx_drag == 0 and abs(dy_drag) > 0) or (dx_drag != 0 and abs(float(dy_drag) / dx_drag) > 0.2 and abs(dy_drag) > 1):
1145  zoom = min(self._max_zoom_speed, max(self._min_zoom_speed, 1.0 + self._zoom_sensitivity * dy_drag))
1146  self.zoom_timeline(zoom, self.map_x_to_stamp(x))
1147 
1148  self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1149  elif event.buttons() == Qt.LeftButton:
1150  # Left: move selected region and move selected region boundry
1151  clicked_x = self._clicked_pos.x()
1152  clicked_y = self._clicked_pos.y()
1153 
1154  x_stamp = self.map_x_to_stamp(x)
1155 
1156  if y <= self._history_top:
1157  if self._selecting_mode == _SelectionMode.LEFT_MARKED:
1158  # Left and selecting: change selection region
1159  clicked_x_stamp = self.map_x_to_stamp(clicked_x)
1160 
1161  self._selected_left = min(clicked_x_stamp, x_stamp)
1162  self._selected_right = max(clicked_x_stamp, x_stamp)
1163  self.scene().update()
1164 
1165  elif self._selecting_mode == _SelectionMode.MOVE_LEFT:
1166  self._selected_left = x_stamp
1167  self.scene().update()
1168 
1169  elif self._selecting_mode == _SelectionMode.MOVE_RIGHT:
1170  self._selected_right = x_stamp
1171  self.scene().update()
1172 
1173  elif self._selecting_mode == _SelectionMode.SHIFTING:
1174  dx_drag = x - self._dragged_pos.x()
1175  dstamp = self.map_dx_to_dstamp(dx_drag)
1176 
1177  self._selected_left = max(self._start_stamp.to_sec(), min(self._end_stamp.to_sec(), self._selected_left + dstamp))
1178  self._selected_right = max(self._start_stamp.to_sec(), min(self._end_stamp.to_sec(), self._selected_right + dstamp))
1179  self.scene().update()
1180  self.emit_play_region()
1181 
1182  elif clicked_x >= self._history_left and clicked_x <= self._history_right and clicked_y >= self._history_top and clicked_y <= self._history_bottom:
1183  # Left and clicked within timeline: change playhead
1184  if x_stamp <= 0.0:
1185  self.playhead = rospy.Time(0, 1)
1186  else:
1187  self.playhead = rospy.Time.from_sec(x_stamp)
1188  self.scene().update()
1189  self._dragged_pos = event.pos()
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_vertical_padding
_topic_vertical_padding
Definition: dynamic_timeline_frame.py:132
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.start_stamp
def start_stamp(self)
Definition: dynamic_timeline_frame.py:267
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selecting_mode
_selecting_mode
Definition: dynamic_timeline_frame.py:162
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._scene_width
_scene_width
Definition: dynamic_timeline_frame.py:342
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._bag_end_color
_bag_end_color
Definition: dynamic_timeline_frame.py:99
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._zoom_sensitivity
_zoom_sensitivity
Definition: dynamic_timeline_frame.py:175
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_major_divisions
def _draw_major_divisions(self, painter, stamps, start_stamp, division)
Definition: dynamic_timeline_frame.py:632
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._default_datatype_color
_default_datatype_color
Definition: dynamic_timeline_frame.py:146
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._margin_right
_margin_right
Definition: dynamic_timeline_frame.py:94
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selected_right
_selected_right
Definition: dynamic_timeline_frame.py:164
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._default_msg_combine_px
_default_msg_combine_px
Definition: dynamic_timeline_frame.py:155
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.play_region
def play_region(self)
Definition: dynamic_timeline_frame.py:255
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.zoom_out
def zoom_out(self)
Definition: dynamic_timeline_frame.py:973
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._playhead_pointer_size
_playhead_pointer_size
Definition: dynamic_timeline_frame.py:170
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.reset_timeline
def reset_timeline(self)
Definition: dynamic_timeline_frame.py:928
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.emit_play_region
def emit_play_region(self)
Definition: dynamic_timeline_frame.py:261
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._playhead_line_width
_playhead_line_width
Definition: dynamic_timeline_frame.py:171
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.translate_timeline_right
def translate_timeline_right(self)
Definition: dynamic_timeline_frame.py:951
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.resume
def resume(self)
Definition: dynamic_timeline_frame.py:1039
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._min_zoom
_min_zoom
Definition: dynamic_timeline_frame.py:178
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_font
_topic_font
Definition: dynamic_timeline_frame.py:129
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.set_renderers_active
def set_renderers_active(self, active)
Definition: dynamic_timeline_frame.py:750
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._default_brush
_default_brush
Definition: dynamic_timeline_frame.py:144
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_playhead
def _draw_playhead(self, painter)
Definition: dynamic_timeline_frame.py:553
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._stamp_right
_stamp_right
Definition: dynamic_timeline_frame.py:84
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.map_dstamp_to_dx
def map_dstamp_to_dx(self, dstamp)
Definition: dynamic_timeline_frame.py:917
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.get_renderers
def get_renderers(self)
Definition: dynamic_timeline_frame.py:729
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.plugin_provider
plugin_provider
Definition: dynamic_timeline_frame.py:686
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._set_playhead
def _set_playhead(self, playhead)
Definition: dynamic_timeline_frame.py:200
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.translate_timeline_left
def translate_timeline_left(self)
Definition: dynamic_timeline_frame.py:948
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._major_division_pen
_major_division_pen
Definition: dynamic_timeline_frame.py:118
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selected_left
_selected_left
Definition: dynamic_timeline_frame.py:163
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_name_spacing
_topic_name_spacing
Definition: dynamic_timeline_frame.py:127
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._trimmed_topic_name
def _trimmed_topic_name(self, topic_name)
Definition: dynamic_timeline_frame.py:298
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_bounds
_history_bounds
Definition: dynamic_timeline_frame.py:92
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.is_renderer_active
def is_renderer_active(self, topic)
Definition: dynamic_timeline_frame.py:742
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_minor_divisions
def _draw_minor_divisions(self, painter, stamps, start_stamp, division)
Definition: dynamic_timeline_frame.py:655
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._end_stamp
_end_stamp
Definition: dynamic_timeline_frame.py:82
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._index_cache_thread
_index_cache_thread
Definition: dynamic_timeline_frame.py:191
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.pause
def pause(self)
Definition: dynamic_timeline_frame.py:1036
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.playhead
playhead
Definition: dynamic_timeline_frame.py:243
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._clicked_pos
_clicked_pos
Definition: dynamic_timeline_frame.py:77
rqt_gui::rospkg_plugin_provider
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._sec_divisions
_sec_divisions
Definition: dynamic_timeline_frame.py:110
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._playhead
_playhead
Definition: dynamic_timeline_frame.py:168
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._major_divisions_label_indent
_major_divisions_label_indent
Definition: dynamic_timeline_frame.py:117
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._start_stamp
_start_stamp
Definition: dynamic_timeline_frame.py:81
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._margin_left
_margin_left
Definition: dynamic_timeline_frame.py:93
rqt_py_trees.dynamic_timeline_frame._SelectionMode
Definition: dynamic_timeline_frame.py:50
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.boundingRect
def boundingRect(self)
Definition: dynamic_timeline_frame.py:275
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.__init__
def __init__(self, dynamic_timeline)
Definition: dynamic_timeline_frame.py:74
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.map_y_to_topic
def map_y_to_topic(self, y)
Definition: dynamic_timeline_frame.py:920
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._max_zoom
_max_zoom
Definition: dynamic_timeline_frame.py:179
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.load_plugins
def load_plugins(self)
Definition: dynamic_timeline_frame.py:684
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_selected_region
def _draw_selected_region(self, painter)
Definition: dynamic_timeline_frame.py:514
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._minor_spacing
_minor_spacing
Definition: dynamic_timeline_frame.py:115
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_name_sizes
_topic_name_sizes
Definition: dynamic_timeline_frame.py:126
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_topic_dividers
def _draw_topic_dividers(self, painter)
Definition: dynamic_timeline_frame.py:490
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_background_color
_history_background_color
Definition: dynamic_timeline_frame.py:101
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.on_mousewheel
def on_mousewheel(self, event)
Definition: dynamic_timeline_frame.py:1103
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._get_stamps
def _get_stamps(self, start_stamp, stamp_step)
Definition: dynamic_timeline_frame.py:830
rqt_bag::index_cache_thread::IndexCacheThread
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._time_font_height
_time_font_height
Definition: dynamic_timeline_frame.py:137
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._get_label
def _get_label(self, division, elapsed)
Definition: dynamic_timeline_frame.py:845
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_right
def _history_right(self)
Definition: dynamic_timeline_frame.py:247
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_font_size
_topic_font_size
Definition: dynamic_timeline_frame.py:128
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.end_stamp
def end_stamp(self)
Definition: dynamic_timeline_frame.py:271
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._major_spacing
_major_spacing
Definition: dynamic_timeline_frame.py:116
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_width
_history_width
Definition: dynamic_timeline_frame.py:88
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_font_height
_topic_font_height
Definition: dynamic_timeline_frame.py:125
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_topic_histories
def _draw_topic_histories(self, painter)
Definition: dynamic_timeline_frame.py:386
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.map_dx_to_dstamp
def map_dx_to_dstamp(self, dx)
Definition: dynamic_timeline_frame.py:893
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.translate_timeline
def translate_timeline(self, dstamp)
Definition: dynamic_timeline_frame.py:944
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.index_cache
index_cache
Definition: dynamic_timeline_frame.py:189
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selected_region_outline_top_color
_selected_region_outline_top_color
Definition: dynamic_timeline_frame.py:160
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._max_zoom_speed
_max_zoom_speed
Definition: dynamic_timeline_frame.py:177
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.on_mouse_up
def on_mouse_up(self, event)
Definition: dynamic_timeline_frame.py:1092
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._viewer_types
_viewer_types
Definition: dynamic_timeline_frame.py:182
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.toggle_renderers
def toggle_renderers(self)
Definition: dynamic_timeline_frame.py:745
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_history_border
def _draw_history_border(self, painter)
Definition: dynamic_timeline_frame.py:577
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selected_region_outline_ends_color
_selected_region_outline_ends_color
Definition: dynamic_timeline_frame.py:161
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.topics
topics
Definition: dynamic_timeline_frame.py:123
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_top
_history_top
Definition: dynamic_timeline_frame.py:85
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_left
_history_left
Definition: dynamic_timeline_frame.py:86
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._find_regions
def _find_regions(self, stamps, max_interval)
Definition: dynamic_timeline_frame.py:808
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selection_handle_width
_selection_handle_width
Definition: dynamic_timeline_frame.py:165
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_time_divisions
def _draw_time_divisions(self, painter)
Definition: dynamic_timeline_frame.py:605
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._min_zoom_speed
_min_zoom_speed
Definition: dynamic_timeline_frame.py:176
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._timeline_renderers
_timeline_renderers
Definition: dynamic_timeline_frame.py:183
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._active_message_line_width
_active_message_line_width
Definition: dynamic_timeline_frame.py:156
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.can_zoom_in
def can_zoom_in(self)
Definition: dynamic_timeline_frame.py:976
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._layout
def _layout(self)
Definition: dynamic_timeline_frame.py:337
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._time_tick_height
_time_tick_height
Definition: dynamic_timeline_frame.py:136
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.map_stamp_to_x
def map_stamp_to_x(self, stamp, clamp_to_visible=True)
Definition: dynamic_timeline_frame.py:901
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._qfont_width
def _qfont_width(self, name)
Definition: dynamic_timeline_frame.py:295
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._paused
_paused
Definition: dynamic_timeline_frame.py:169
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._update_index_cache
def _update_index_cache(self, topic)
Definition: dynamic_timeline_frame.py:771
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.can_zoom
def can_zoom(self, desired_zoom)
Definition: dynamic_timeline_frame.py:982
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._time_font_size
_time_font_size
Definition: dynamic_timeline_frame.py:138
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.has_selected_region
def has_selected_region(self)
Definition: dynamic_timeline_frame.py:251
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.on_middle_down
def on_middle_down(self, event)
Definition: dynamic_timeline_frame.py:1044
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_topic_history
def _draw_topic_history(self, painter, topic)
Definition: dynamic_timeline_frame.py:394
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._selected_region_color
_selected_region_color
Definition: dynamic_timeline_frame.py:159
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._get_playhead
def _get_playhead(self)
Definition: dynamic_timeline_frame.py:197
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.index_cache_cv
index_cache_cv
Definition: dynamic_timeline_frame.py:188
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_topic_names
def _draw_topic_names(self, painter)
Definition: dynamic_timeline_frame.py:591
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.paint
def paint(self, painter, option, widget)
Definition: dynamic_timeline_frame.py:278
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.invalidated_caches
invalidated_caches
Definition: dynamic_timeline_frame.py:190
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.get_viewer_types
def get_viewer_types(self, datatype)
Definition: dynamic_timeline_frame.py:681
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._dragged_pos
_dragged_pos
Definition: dynamic_timeline_frame.py:78
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_bottom
_history_bottom
Definition: dynamic_timeline_frame.py:91
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.handle_close
def handle_close(self)
Definition: dynamic_timeline_frame.py:674
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.set_renderer_active
def set_renderer_active(self, topic, active)
Definition: dynamic_timeline_frame.py:758
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.reset_zoom
def reset_zoom(self)
Definition: dynamic_timeline_frame.py:955
rqt_bag::index_cache_thread
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.get_zoom_interval
def get_zoom_interval(self, zoom, center=None)
Definition: dynamic_timeline_frame.py:1008
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame
Definition: dynamic_timeline_frame.py:68
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.on_mouse_move
def on_mouse_move(self, event)
Definition: dynamic_timeline_frame.py:1107
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topic_name_max_percent
_topic_name_max_percent
Definition: dynamic_timeline_frame.py:133
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._playhead_color
_playhead_color
Definition: dynamic_timeline_frame.py:172
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.can_zoom_out
def can_zoom_out(self)
Definition: dynamic_timeline_frame.py:979
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._margin_bottom
_margin_bottom
Definition: dynamic_timeline_frame.py:95
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._dynamic_timeline
_dynamic_timeline
Definition: dynamic_timeline_frame.py:76
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.zoom_timeline
def zoom_timeline(self, zoom, center=None)
Definition: dynamic_timeline_frame.py:999
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._minor_division_pen
_minor_division_pen
Definition: dynamic_timeline_frame.py:119
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._datatype_colors
_datatype_colors
Definition: dynamic_timeline_frame.py:147
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._stamp_left
_stamp_left
Definition: dynamic_timeline_frame.py:83
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.set_timeline_view
def set_timeline_view(self, stamp_left, stamp_right)
Definition: dynamic_timeline_frame.py:940
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._draw_bag_ends
def _draw_bag_ends(self, painter)
Definition: dynamic_timeline_frame.py:478
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.on_left_down
def on_left_down(self, event)
Definition: dynamic_timeline_frame.py:1048
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._topics_by_datatype
_topics_by_datatype
Definition: dynamic_timeline_frame.py:124
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.map_x_to_stamp
def map_x_to_stamp(self, x, clamp_to_visible=True)
Definition: dynamic_timeline_frame.py:876
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._time_font
_time_font
Definition: dynamic_timeline_frame.py:139
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._rendered_topics
_rendered_topics
Definition: dynamic_timeline_frame.py:184
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._minor_division_tick_pen
_minor_division_tick_pen
Definition: dynamic_timeline_frame.py:120
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._default_pen
_default_pen
Definition: dynamic_timeline_frame.py:145
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame.zoom_in
def zoom_in(self)
Definition: dynamic_timeline_frame.py:970
rqt_py_trees.dynamic_timeline_frame.DynamicTimelineFrame._history_background_color_alternate
_history_background_color_alternate
Definition: dynamic_timeline_frame.py:100


rqt_py_trees
Author(s): Thibault Kruse, Michal Staniaszek, Daniel Stonier, Naveed Usmani
autogenerated on Wed Mar 2 2022 00:59:03