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


rqt_bag
Author(s): Dirk Thomas , Aaron Blasdel , Austin Hendrix , Tim Field
autogenerated on Thu Mar 2 2023 03:43:15