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 
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 try: # indigo
38  from python_qt_binding.QtGui import QGraphicsItem
39 except ImportError: # kinetic+ (pyqt5)
40  from python_qt_binding.QtWidgets import QGraphicsItem
41 
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  # Save important last element of topic name provided it is small
311  popped_last = False
312  if self._qfont_width(split_name[-1]) < .5 * allowed_width:
313  popped_last = True
314  last_item = split_name[-1]
315  split_name = split_name[:-1]
316  allowed_width = allowed_width - self._qfont_width(last_item)
317  # Shorten and add remaining items keeping lenths roughly equal
318  for item in split_name:
319  if self._qfont_width(item) > allowed_width / float(len(split_name)):
320  trimmed_item = item[:-3] + '..'
321  while self._qfont_width(trimmed_item) > allowed_width / float(len(split_name)):
322  if len(trimmed_item) >= 3:
323  trimmed_item = trimmed_item[:-3] + '..'
324  else:
325  break
326  trimmed = trimmed + '/' + trimmed_item
327  else:
328  trimmed = trimmed + '/' + item
329  if popped_last:
330  trimmed = trimmed + '/' + last_item
331  trimmed = trimmed[1:]
332  trimmed_return = trimmed
333  return trimmed_return
334 
335  def _layout(self):
336  """
337  Recalculates the layout of the of the timeline to take into account any changes that have occured
338  """
339  # Calculate history left and history width
340  self._scene_width = self.scene().views()[0].size().width()
341 
342  max_topic_name_width = -1
343  for topic in self.topics:
344  topic_width = self._qfont_width(self._trimmed_topic_name(topic))
345  if max_topic_name_width <= topic_width:
346  max_topic_name_width = topic_width
347 
348  # Calculate font height for each topic
349  self._topic_font_height = -1
350  for topic in self.topics:
351  topic_height = QFontMetrics(self._topic_font).height()
352  if self._topic_font_height <= topic_height:
353  self._topic_font_height = topic_height
354 
355  # Update the timeline boundries
356  new_history_left = self._margin_left + max_topic_name_width + self._topic_name_spacing
357  new_history_width = self._scene_width - new_history_left - self._margin_right
358  self._history_left = new_history_left
359  self._history_width = new_history_width
360 
361  # Calculate the bounds for each topic
362  self._history_bounds = {}
363  y = self._history_top
364  for topic in self.topics:
365  datatype = self.scene().get_datatype(topic)
366 
367  topic_height = None
368  if topic in self._rendered_topics:
369  renderer = self._timeline_renderers.get(datatype)
370  if renderer:
371  topic_height = renderer.get_segment_height(topic)
372  if not topic_height:
373  topic_height = self._topic_font_height + self._topic_vertical_padding
374 
375  self._history_bounds[topic] = (self._history_left, y, self._history_width, topic_height)
376 
377  y += topic_height
378 
379 # new_history_bottom = max([y + h for (x, y, w, h) in self._history_bounds.values()]) - 1
380  new_history_bottom = max([y + h for (_, y, _, h) in self._history_bounds.values()]) - 1
381  if new_history_bottom != self._history_bottom:
382  self._history_bottom = new_history_bottom
383 
384  def _draw_topic_histories(self, painter):
385  """
386  Draw all topic messages
387  :param painter: allows access to paint functions,''QPainter''
388  """
389  for topic in sorted(self._history_bounds.keys()):
390  self._draw_topic_history(painter, topic)
391 
392  def _draw_topic_history(self, painter, topic):
393  """
394  Draw boxes corrisponding to message regions on the timeline.
395  :param painter: allows access to paint functions,''QPainter''
396  :param topic: the topic for which message boxes should be drawn, ''str''
397  """
398 
399 # x, y, w, h = self._history_bounds[topic]
400  _, y, _, h = self._history_bounds[topic]
401 
402  msg_y = y + 2
403  msg_height = h - 2
404 
405  datatype = self.scene().get_datatype(topic)
406 
407  # Get the renderer and the message combine interval
408  renderer = None
409  msg_combine_interval = None
410  if topic in self._rendered_topics:
411  renderer = self._timeline_renderers.get(datatype)
412  if renderer is not None:
413  msg_combine_interval = self.map_dx_to_dstamp(renderer.msg_combine_px)
414  if msg_combine_interval is None:
415  msg_combine_interval = self.map_dx_to_dstamp(self._default_msg_combine_px)
416 
417  # Get the cache
418  if topic not in self.index_cache:
419  return
420  all_stamps = self.index_cache[topic]
421 
422 # start_index = bisect.bisect_left(all_stamps, self._stamp_left)
423  end_index = bisect.bisect_left(all_stamps, self._stamp_right)
424  # Set pen based on datatype
425  datatype_color = self._datatype_colors.get(datatype, self._default_datatype_color)
426  # Iterate through regions of connected messages
427  width_interval = self._history_width / (self._stamp_right - self._stamp_left)
428 
429  # Draw stamps
430  for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], self.map_dx_to_dstamp(self._default_msg_combine_px)):
431  if stamp_end < self._stamp_left:
432  continue
433 
434  region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
435  if region_x_start < self._history_left:
436  region_x_start = self._history_left # Clip the region
437  region_x_end = self._history_left + (stamp_end - self._stamp_left) * width_interval
438  region_width = max(1, region_x_end - region_x_start)
439 
440  painter.setBrush(QBrush(datatype_color))
441  painter.setPen(QPen(datatype_color, 1))
442  painter.drawRect(region_x_start, msg_y, region_width, msg_height)
443 
444  # Draw active message
445  if topic in self.scene()._listeners:
446  curpen = painter.pen()
447  oldwidth = curpen.width()
448  curpen.setWidth(self._active_message_line_width)
449  painter.setPen(curpen)
450  playhead_stamp = None
451  playhead_index = bisect.bisect_right(all_stamps, self.playhead.to_sec()) - 1
452  if playhead_index >= 0:
453  playhead_stamp = all_stamps[playhead_index]
454  if playhead_stamp > self._stamp_left and playhead_stamp < self._stamp_right:
455  playhead_x = self._history_left + (all_stamps[playhead_index] - self._stamp_left) * width_interval
456  painter.drawLine(playhead_x, msg_y, playhead_x, msg_y + msg_height)
457  curpen.setWidth(oldwidth)
458  painter.setPen(curpen)
459 
460  # Custom renderer
461  if renderer:
462  # Iterate through regions of connected messages
463  for (stamp_start, stamp_end) in self._find_regions(all_stamps[:end_index], msg_combine_interval):
464  if stamp_end < self._stamp_left:
465  continue
466 
467  region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
468  region_x_end = self._history_left + (stamp_end - self._stamp_left) * width_interval
469  region_width = max(1, region_x_end - region_x_start)
470  renderer.draw_timeline_segment(painter, topic, stamp_start, stamp_end, region_x_start, msg_y, region_width, msg_height)
471 
472  painter.setBrush(self._default_brush)
473  painter.setPen(self._default_pen)
474 
475  def _draw_bag_ends(self, painter):
476  """
477  Draw markers to indicate the area the bag file represents within the current visible area.
478  :param painter: allows access to paint functions,''QPainter''
479  """
480  x_start, x_end = self.map_stamp_to_x(self._start_stamp.to_sec()), self.map_stamp_to_x(self._end_stamp.to_sec())
481  painter.setBrush(QBrush(self._bag_end_color))
482  painter.drawRect(self._history_left, self._history_top, x_start - self._history_left, self._history_bottom - self._history_top)
483  painter.drawRect(x_end, self._history_top, self._history_left + self._history_width - x_end, self._history_bottom - self._history_top)
484  painter.setBrush(self._default_brush)
485  painter.setPen(self._default_pen)
486 
487  def _draw_topic_dividers(self, painter):
488  """
489  Draws horizontal lines between each topic to visually separate the messages
490  :param painter: allows access to paint functions,''QPainter''
491  """
492  clip_left = self._history_left
493  clip_right = self._history_left + self._history_width
494 
495  row = 0
496  for topic in self.topics:
497  (x, y, w, h) = self._history_bounds[topic]
498 
499  if row % 2 == 0:
500  painter.setPen(Qt.lightGray)
501  painter.setBrush(QBrush(self._history_background_color_alternate))
502  else:
503  painter.setPen(Qt.lightGray)
504  painter.setBrush(QBrush(self._history_background_color))
505  left = max(clip_left, x)
506  painter.drawRect(left, y, min(clip_right - left, w), h)
507  row += 1
508  painter.setBrush(self._default_brush)
509  painter.setPen(self._default_pen)
510 
511  def _draw_selected_region(self, painter):
512  """
513  Draws a box around the selected region
514  :param painter: allows access to paint functions,''QPainter''
515  """
516  if self._selected_left is None:
517  return
518 
519  x_left = self.map_stamp_to_x(self._selected_left)
520  if self._selected_right is not None:
521  x_right = self.map_stamp_to_x(self._selected_right)
522  else:
523  x_right = self.map_stamp_to_x(self.playhead.to_sec())
524 
525  left = x_left
526  top = self._history_top - self._playhead_pointer_size[1] - 5 - self._time_font_size - 4
527  width = x_right - x_left
528  height = self._history_top - top
529 
530  painter.setPen(self._selected_region_color)
531  painter.setBrush(QBrush(self._selected_region_color))
532  painter.drawRect(left, top, width, height)
533 
534  painter.setPen(self._selected_region_outline_ends_color)
535  painter.setBrush(Qt.NoBrush)
536  painter.drawLine(left, top, left, top + height)
537  painter.drawLine(left + width, top, left + width, top + height)
538 
539  painter.setPen(self._selected_region_outline_top_color)
540  painter.setBrush(Qt.NoBrush)
541  painter.drawLine(left, top, left + width, top)
542 
543  painter.setPen(self._selected_region_outline_top_color)
544  painter.drawLine(left, self._history_top, left, self._history_bottom)
545  painter.drawLine(left + width, self._history_top, left + width, self._history_bottom)
546 
547  painter.setBrush(self._default_brush)
548  painter.setPen(self._default_pen)
549 
550  def _draw_playhead(self, painter):
551  """
552  Draw a line and 2 triangles to denote the current position being viewed
553  :param painter: ,''QPainter''
554  """
555  px = self.map_stamp_to_x(self.playhead.to_sec())
556  pw, ph = self._playhead_pointer_size
557 
558  # Line
559  painter.setPen(QPen(self._playhead_color))
560  painter.setBrush(QBrush(self._playhead_color))
561  painter.drawLine(px, self._history_top - 1, px, self._history_bottom + 2)
562 
563  # Upper triangle
564  py = self._history_top - ph
565  painter.drawPolygon(QPolygonF([QPointF(px, py + ph), QPointF(px + pw, py), QPointF(px - pw, py)]))
566 
567  # Lower triangle
568  py = self._history_bottom + 1
569  painter.drawPolygon(QPolygonF([QPointF(px, py), QPointF(px + pw, py + ph), QPointF(px - pw, py + ph)]))
570 
571  painter.setBrush(self._default_brush)
572  painter.setPen(self._default_pen)
573 
574  def _draw_history_border(self, painter):
575  """
576  Draw a simple black rectangle frame around the timeline view area
577  :param painter: ,''QPainter''
578  """
579  bounds_width = min(self._history_width, self.scene().width())
580  x, y, w, h = self._history_left, self._history_top, bounds_width, self._history_bottom - self._history_top
581 
582  painter.setBrush(Qt.NoBrush)
583  painter.setPen(Qt.black)
584  painter.drawRect(x, y, w, h)
585  painter.setBrush(self._default_brush)
586  painter.setPen(self._default_pen)
587 
588  def _draw_topic_names(self, painter):
589  """
590  Calculate positions of existing topic names and draw them on the left, one for each row
591  :param painter: ,''QPainter''
592  """
593  topics = self._history_bounds.keys()
594  coords = [(self._margin_left, y + (h / 2) + (self._topic_font_height / 2)) for (_, y, _, h) in self._history_bounds.values()]
595 
596  for text, coords in zip([t.lstrip('/') for t in topics], coords):
597  painter.setBrush(self._default_brush)
598  painter.setPen(self._default_pen)
599  painter.setFont(self._topic_font)
600  painter.drawText(coords[0], coords[1], self._trimmed_topic_name(text))
601 
602  def _draw_time_divisions(self, painter):
603  """
604  Draw vertical grid-lines showing major and minor time divisions.
605  :param painter: allows access to paint functions,''QPainter''
606  """
607  x_per_sec = self.map_dstamp_to_dx(1.0)
608  major_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._major_spacing]
609  if len(major_divisions) == 0:
610  major_division = max(self._sec_divisions)
611  else:
612  major_division = min(major_divisions)
613 
614  minor_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._minor_spacing and major_division % s == 0]
615  if len(minor_divisions) > 0:
616  minor_division = min(minor_divisions)
617  else:
618  minor_division = None
619 
620  start_stamp = self._start_stamp.to_sec()
621 
622  major_stamps = list(self._get_stamps(start_stamp, major_division))
623  self._draw_major_divisions(painter, major_stamps, start_stamp, major_division)
624 
625  if minor_division:
626  minor_stamps = [s for s in self._get_stamps(start_stamp, minor_division) if s not in major_stamps]
627  self._draw_minor_divisions(painter, minor_stamps, start_stamp, minor_division)
628 
629  def _draw_major_divisions(self, painter, stamps, start_stamp, division):
630  """
631  Draw black hashed vertical grid-lines showing major time divisions.
632  :param painter: allows access to paint functions,''QPainter''
633  """
634  label_y = self._history_top - self._playhead_pointer_size[1] - 5
635  for stamp in stamps:
636  x = self.map_stamp_to_x(stamp, False)
637 
638  label = self._get_label(division, stamp - start_stamp)
639  label_x = x + self._major_divisions_label_indent
640  if label_x + self._qfont_width(label) < self.scene().width():
641  painter.setBrush(self._default_brush)
642  painter.setPen(self._default_pen)
643  painter.setFont(self._time_font)
644  painter.drawText(label_x, label_y, label)
645 
646  painter.setPen(self._major_division_pen)
647  painter.drawLine(x, label_y - self._time_tick_height - self._time_font_size, x, self._history_bottom)
648 
649  painter.setBrush(self._default_brush)
650  painter.setPen(self._default_pen)
651 
652  def _draw_minor_divisions(self, painter, stamps, start_stamp, division):
653  """
654  Draw grey hashed vertical grid-lines showing minor time divisions.
655  :param painter: allows access to paint functions,''QPainter''
656  """
657  xs = [self.map_stamp_to_x(stamp) for stamp in stamps]
658  painter.setPen(self._minor_division_pen)
659  for x in xs:
660  painter.drawLine(x, self._history_top, x, self._history_bottom)
661 
662  painter.setPen(self._minor_division_tick_pen)
663  for x in xs:
664  painter.drawLine(x, self._history_top - self._time_tick_height, x, self._history_top)
665 
666  painter.setBrush(self._default_brush)
667  painter.setPen(self._default_pen)
668 
669  # Close function
670 
671  def handle_close(self):
672  for renderer in self._timeline_renderers.values():
673  renderer.close()
674  self._index_cache_thread.stop()
675 
676  # Plugin interaction functions
677 
678  def get_viewer_types(self, datatype):
679  return [RawView] + self._viewer_types.get('*', []) + self._viewer_types.get(datatype, [])
680 
681  def load_plugins(self):
682  from rqt_gui.rospkg_plugin_provider import RospkgPluginProvider
683  self.plugin_provider = RospkgPluginProvider('rqt_bag', 'rqt_bag::Plugin')
684 
685  plugin_descriptors = self.plugin_provider.discover(None)
686  for plugin_descriptor in plugin_descriptors:
687  try:
688  plugin = self.plugin_provider.load(plugin_descriptor.plugin_id(), plugin_context=None)
689  except Exception as e:
690  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to load plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
691  continue
692  try:
693  view = plugin.get_view_class()
694  except Exception as e:
695  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to get view from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
696  continue
697 
698  timeline_renderer = None
699  try:
700  timeline_renderer = plugin.get_renderer_class()
701  except AttributeError:
702  pass
703  except Exception as e:
704  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to get renderer from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
705 
706  msg_types = []
707  try:
708  msg_types = plugin.get_message_types()
709  except AttributeError:
710  pass
711  except Exception as e:
712  qWarning('rqt_bag.TimelineFrame.load_plugins() failed to get message types from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
713  finally:
714  if not msg_types:
715  qWarning('rqt_bag.TimelineFrame.load_plugins() plugin "%s" declares no message types:\n%s' % (plugin_descriptor.plugin_id(), e))
716 
717  for msg_type in msg_types:
718  self._viewer_types.setdefault(msg_type, []).append(view)
719  if timeline_renderer:
720  self._timeline_renderers[msg_type] = timeline_renderer(self)
721 
722  qDebug('rqt_bag.TimelineFrame.load_plugins() loaded plugin "%s"' % plugin_descriptor.plugin_id())
723 
724  # Timeline renderer interaction functions
725 
726  def get_renderers(self):
727  """
728  :returns: a list of the currently loaded renderers for the plugins
729  """
730  renderers = []
731 
732  for topic in self.topics:
733  datatype = self.scene().get_datatype(topic)
734  renderer = self._timeline_renderers.get(datatype)
735  if renderer is not None:
736  renderers.append((topic, renderer))
737  return renderers
738 
739  def is_renderer_active(self, topic):
740  return topic in self._rendered_topics
741 
742  def toggle_renderers(self):
743  idle_renderers = len(self._rendered_topics) < len(self.topics)
744 
745  self.set_renderers_active(idle_renderers)
746 
747  def set_renderers_active(self, active):
748  if active:
749  for topic in self.topics:
750  self._rendered_topics.add(topic)
751  else:
752  self._rendered_topics.clear()
753  self.scene().update()
754 
755  def set_renderer_active(self, topic, active):
756  if active:
757  if topic in self._rendered_topics:
758  return
759  self._rendered_topics.add(topic)
760  else:
761  if not topic in self._rendered_topics:
762  return
763  self._rendered_topics.remove(topic)
764  self.scene().update()
765 
766  # Index Caching functions
767 
768  def _update_index_cache(self, topic):
769  """
770  Updates the cache of message timestamps for the given topic.
771  :return: number of messages added to the index cache
772  """
773  if self._start_stamp is None or self._end_stamp is None:
774  return 0
775 
776  if topic not in self.index_cache:
777  # Don't have any cache of messages in this topic
778  start_time = self._start_stamp
779  topic_cache = []
780  self.index_cache[topic] = topic_cache
781  else:
782  topic_cache = self.index_cache[topic]
783 
784  # Check if the cache has been invalidated
785  if topic not in self.invalidated_caches:
786  return 0
787 
788  if len(topic_cache) == 0:
789  start_time = self._start_stamp
790  else:
791  start_time = rospy.Time.from_sec(max(0.0, topic_cache[-1]))
792 
793  end_time = self._end_stamp
794 
795  topic_cache_len = len(topic_cache)
796 
797  for entry in self.scene().get_entries([topic], start_time, end_time):
798  topic_cache.append(entry.stamp.to_sec())
799 
800  if topic in self.invalidated_caches:
801  self.invalidated_caches.remove(topic)
802 
803  return len(topic_cache) - topic_cache_len
804 
805  def _find_regions(self, stamps, max_interval):
806  """
807  Group timestamps into regions connected by timestamps less than max_interval secs apart.
808  If no other timestamps are within the interval, then return start = end.
809  :param float[] start_stamp:
810  :param float max_interval: maximum size of each region
811  """
812  region_start, prev_stamp = None, None
813  for stamp in stamps:
814  if prev_stamp:
815  if stamp - prev_stamp > max_interval:
816  region_end = prev_stamp
817  yield (region_start, region_end)
818  region_start = stamp
819  else:
820  region_start = stamp
821 
822  prev_stamp = stamp
823 
824  if region_start and prev_stamp:
825  yield (region_start, prev_stamp)
826 
827  def _get_stamps(self, start_stamp, stamp_step):
828  """
829  Generate visible stamps every stamp_step
830  :param start_stamp: beginning of timeline stamp, ''int''
831  :param stamp_step: seconds between each division, ''int''
832  """
833  if start_stamp >= self._stamp_left:
834  stamp = start_stamp
835  else:
836  stamp = start_stamp + int((self._stamp_left - start_stamp) / stamp_step) * stamp_step + stamp_step
837 
838  while stamp < self._stamp_right:
839  yield stamp
840  stamp += stamp_step
841 
842  def _get_label(self, division, elapsed):
843  """
844  :param division: number of seconds in a division, ''int''
845  :param elapsed: seconds from the beginning, ''int''
846  :returns: relevent time elapsed string, ''str''
847  """
848  secs = int(elapsed) % 60
849 
850  mins = int(elapsed) / 60
851  hrs = mins / 60
852  days = hrs / 24
853  weeks = days / 7
854 
855  if division >= 7 * 24 * 60 * 60: # >1wk divisions: show weeks
856  return '%dw' % weeks
857  elif division >= 24 * 60 * 60: # >24h divisions: show days
858  return '%dd' % days
859  elif division >= 60 * 60: # >1h divisions: show hours
860  return '%dh' % hrs
861  elif division >= 5 * 60: # >5m divisions: show minutes
862  return '%dm' % mins
863  elif division >= 1: # >1s divisions: show minutes:seconds
864  return '%dm%02ds' % (mins, secs)
865  elif division >= 0.1: # >0.1s divisions: show seconds.0
866  return '%d.%ss' % (secs, str(int(10.0 * (elapsed - int(elapsed)))))
867  elif division >= 0.01: # >0.1s divisions: show seconds.0
868  return '%d.%02ds' % (secs, int(100.0 * (elapsed - int(elapsed))))
869  else: # show seconds.00
870  return '%d.%03ds' % (secs, int(1000.0 * (elapsed - int(elapsed))))
871 
872  # Pixel location/time conversion functions
873  def map_x_to_stamp(self, x, clamp_to_visible=True):
874  """
875  converts a pixel x value to a stamp
876  :param x: pixel value to be converted, ''int''
877  :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool''
878  :returns: timestamp, ''int''
879  """
880  fraction = float(x - self._history_left) / self._history_width
881 
882  if clamp_to_visible:
883  if fraction <= 0.0:
884  return self._stamp_left
885  elif fraction >= 1.0:
886  return self._stamp_right
887 
888  return self._stamp_left + fraction * (self._stamp_right - self._stamp_left)
889 
890  def map_dx_to_dstamp(self, dx):
891  """
892  converts a distance in pixel space to a distance in stamp space
893  :param dx: distance in pixel space to be converted, ''int''
894  :returns: distance in stamp space, ''float''
895  """
896  return float(dx) * (self._stamp_right - self._stamp_left) / self._history_width
897 
898  def map_stamp_to_x(self, stamp, clamp_to_visible=True):
899  """
900  converts a timestamp to the x value where that stamp exists in the timeline
901  :param stamp: timestamp to be converted, ''int''
902  :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool''
903  :returns: # of pixels from the left boarder, ''int''
904  """
905  if self._stamp_left is None:
906  return None
907  fraction = (stamp - self._stamp_left) / (self._stamp_right - self._stamp_left)
908 
909  if clamp_to_visible:
910  fraction = min(1.0, max(0.0, fraction))
911 
912  return self._history_left + fraction * self._history_width
913 
914  def map_dstamp_to_dx(self, dstamp):
915  return (float(dstamp) * self._history_width) / (self._stamp_right - self._stamp_left)
916 
917  def map_y_to_topic(self, y):
918  for topic in self._history_bounds:
919  x, topic_y, w, topic_h = self._history_bounds[topic]
920  if y > topic_y and y <= topic_y + topic_h:
921  return topic
922  return None
923 
924  # View port manipulation functions
925  def reset_timeline(self):
926  self.reset_zoom()
927 
928  self._selected_left = None
929  self._selected_right = None
930  self._selecting_mode = _SelectionMode.NONE
931 
932  self.emit_play_region()
933 
934  if self._stamp_left is not None:
935  self.playhead = rospy.Time.from_sec(self._stamp_left)
936 
937  def set_timeline_view(self, stamp_left, stamp_right):
938  self._stamp_left = stamp_left
939  self._stamp_right = stamp_right
940 
941  def translate_timeline(self, dstamp):
942  self.set_timeline_view(self._stamp_left + dstamp, self._stamp_right + dstamp)
943  self.scene().update()
944 
946  self.translate_timeline((self._stamp_right - self._stamp_left) * -0.05)
947 
949  self.translate_timeline((self._stamp_right - self._stamp_left) * 0.05)
950 
951  # Zoom functions
952  def reset_zoom(self):
953  start_stamp, end_stamp = self._start_stamp, self._end_stamp
954  if start_stamp is None:
955  return
956 
957  # if you just want the timeline to grow dynamically, leave this out
958 # if (end_stamp - start_stamp) < rospy.Duration.from_sec(5.0):
959 # end_stamp = start_stamp + rospy.Duration.from_sec(5.0)
960  # make sure at least that the difference is non-zero
961  if end_stamp == start_stamp:
962  end_stamp = start_stamp + rospy.Duration.from_sec(1.0)
963 
964  self.set_timeline_view(start_stamp.to_sec(), end_stamp.to_sec())
965  self.scene().update()
966 
967  def zoom_in(self):
968  self.zoom_timeline(0.5)
969 
970  def zoom_out(self):
971  self.zoom_timeline(2.0)
972 
973  def can_zoom_in(self):
974  return self.can_zoom(0.5)
975 
976  def can_zoom_out(self):
977  return self.can_zoom(2.0)
978 
979  def can_zoom(self, desired_zoom):
980  if not self._stamp_left or not self.playhead:
981  return False
982 
983  new_interval = self.get_zoom_interval(desired_zoom)
984  if not new_interval:
985  return False
986 
987  new_range = new_interval[1] - new_interval[0]
988  curr_range = self._stamp_right - self._stamp_left
989  actual_zoom = new_range / curr_range
990 
991  if desired_zoom < 1.0:
992  return actual_zoom < 0.95
993  else:
994  return actual_zoom > 1.05
995 
996  def zoom_timeline(self, zoom, center=None):
997  interval = self.get_zoom_interval(zoom, center)
998  if not interval:
999  return
1000 
1001  self._stamp_left, self._stamp_right = interval
1002 
1003  self.scene().update()
1004 
1005  def get_zoom_interval(self, zoom, center=None):
1006  """
1007  @rtype: tuple
1008  @requires: left & right zoom interval sizes.
1009  """
1010  if self._stamp_left is None:
1011  return None
1012 
1013  stamp_interval = self._stamp_right - self._stamp_left
1014  if center is None:
1015  center = self.playhead.to_sec()
1016  center_frac = (center - self._stamp_left) / stamp_interval
1017 
1018  new_stamp_interval = zoom * stamp_interval
1019  if new_stamp_interval == 0:
1020  return None
1021  # Enforce zoom limits
1022  px_per_sec = self._history_width / new_stamp_interval
1023  if px_per_sec < self._min_zoom:
1024  new_stamp_interval = self._history_width / self._min_zoom
1025  elif px_per_sec > self._max_zoom:
1026  new_stamp_interval = self._history_width / self._max_zoom
1027 
1028  left = center - center_frac * new_stamp_interval
1029  right = left + new_stamp_interval
1030 
1031  return (left, right)
1032 
1033  def pause(self):
1034  self._paused = True
1035 
1036  def resume(self):
1037  self._paused = False
1038  self._dynamic_timeline.resume()
1039 
1040  # Mouse event handlers
1041  def on_middle_down(self, event):
1042  self._clicked_pos = self._dragged_pos = event.pos()
1043  self.pause()
1044 
1045  def on_left_down(self, event):
1046  if self.playhead is None:
1047  return
1048 
1049  self._clicked_pos = self._dragged_pos = event.pos()
1050 
1051  self.pause()
1052 
1053  if event.modifiers() == Qt.ShiftModifier:
1054  return
1055 
1056  x = self._clicked_pos.x()
1057  y = self._clicked_pos.y()
1058  if x >= self._history_left and x <= self._history_right:
1059  if y >= self._history_top and y <= self._history_bottom:
1060  # Clicked within timeline - set playhead
1061  playhead_secs = self.map_x_to_stamp(x)
1062  if playhead_secs <= 0.0:
1063  self.playhead = rospy.Time(0, 1)
1064  else:
1065  self.playhead = rospy.Time.from_sec(playhead_secs)
1066  self.scene().update()
1067 
1068  elif y <= self._history_top:
1069  # Clicked above timeline
1070  if self._selecting_mode == _SelectionMode.NONE:
1071  self._selected_left = None
1072  self._selected_right = None
1073  self._selecting_mode = _SelectionMode.LEFT_MARKED
1074  self.scene().update()
1075  self.emit_play_region()
1076 
1077  elif self._selecting_mode == _SelectionMode.MARKED:
1078  left_x = self.map_stamp_to_x(self._selected_left)
1079  right_x = self.map_stamp_to_x(self._selected_right)
1080  if x < left_x - self._selection_handle_width or x > right_x + self._selection_handle_width:
1081  self._selected_left = None
1082  self._selected_right = None
1083  self._selecting_mode = _SelectionMode.LEFT_MARKED
1084  self.scene().update()
1085  self.emit_play_region()
1086  elif self._selecting_mode == _SelectionMode.SHIFTING:
1087  self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1088 
1089  def on_mouse_up(self, event):
1090  self.resume()
1091 
1092  if self._selecting_mode in [_SelectionMode.LEFT_MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1093  if self._selected_left is None:
1094  self._selecting_mode = _SelectionMode.NONE
1095  else:
1096  self._selecting_mode = _SelectionMode.MARKED
1097  self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1098  self.scene().update()
1099 
1100  def on_mousewheel(self, event):
1101  dz = event.delta() / 120.0
1102  self.zoom_timeline(1.0 - dz * 0.2)
1103 
1104  def on_mouse_move(self, event):
1105  if not self._history_left: # TODO: need a better notion of initialized
1106  return
1107 
1108  x = event.pos().x()
1109  y = event.pos().y()
1110 
1111  if event.buttons() == Qt.NoButton:
1112  # Mouse moving
1113  if self._selecting_mode in [_SelectionMode.MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1114  if y <= self._history_top and self._selected_left is not None:
1115  left_x = self.map_stamp_to_x(self._selected_left)
1116  right_x = self.map_stamp_to_x(self._selected_right)
1117 
1118  if abs(x - left_x) <= self._selection_handle_width:
1119  self._selecting_mode = _SelectionMode.MOVE_LEFT
1120  self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1121  return
1122  elif abs(x - right_x) <= self._selection_handle_width:
1123  self._selecting_mode = _SelectionMode.MOVE_RIGHT
1124  self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1125  return
1126  elif x > left_x and x < right_x:
1127  self._selecting_mode = _SelectionMode.SHIFTING
1128  self.scene().views()[0].setCursor(QCursor(Qt.OpenHandCursor))
1129  return
1130  else:
1131  self._selecting_mode = _SelectionMode.MARKED
1132  self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1133  else:
1134  # Mouse dragging
1135  if event.buttons() == Qt.MidButton or event.modifiers() == Qt.ShiftModifier:
1136  # Middle or shift: zoom and pan
1137  dx_drag, dy_drag = x - self._dragged_pos.x(), y - self._dragged_pos.y()
1138 
1139  if dx_drag != 0:
1140  self.translate_timeline(-self.map_dx_to_dstamp(dx_drag))
1141  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):
1142  zoom = min(self._max_zoom_speed, max(self._min_zoom_speed, 1.0 + self._zoom_sensitivity * dy_drag))
1143  self.zoom_timeline(zoom, self.map_x_to_stamp(x))
1144 
1145  self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1146  elif event.buttons() == Qt.LeftButton:
1147  # Left: move selected region and move selected region boundry
1148  clicked_x = self._clicked_pos.x()
1149  clicked_y = self._clicked_pos.y()
1150 
1151  x_stamp = self.map_x_to_stamp(x)
1152 
1153  if y <= self._history_top:
1154  if self._selecting_mode == _SelectionMode.LEFT_MARKED:
1155  # Left and selecting: change selection region
1156  clicked_x_stamp = self.map_x_to_stamp(clicked_x)
1157 
1158  self._selected_left = min(clicked_x_stamp, x_stamp)
1159  self._selected_right = max(clicked_x_stamp, x_stamp)
1160  self.scene().update()
1161 
1162  elif self._selecting_mode == _SelectionMode.MOVE_LEFT:
1163  self._selected_left = x_stamp
1164  self.scene().update()
1165 
1166  elif self._selecting_mode == _SelectionMode.MOVE_RIGHT:
1167  self._selected_right = x_stamp
1168  self.scene().update()
1169 
1170  elif self._selecting_mode == _SelectionMode.SHIFTING:
1171  dx_drag = x - self._dragged_pos.x()
1172  dstamp = self.map_dx_to_dstamp(dx_drag)
1173 
1174  self._selected_left = max(self._start_stamp.to_sec(), min(self._end_stamp.to_sec(), self._selected_left + dstamp))
1175  self._selected_right = max(self._start_stamp.to_sec(), min(self._end_stamp.to_sec(), self._selected_right + dstamp))
1176  self.scene().update()
1177  self.emit_play_region()
1178 
1179  elif clicked_x >= self._history_left and clicked_x <= self._history_right and clicked_y >= self._history_top and clicked_y <= self._history_bottom:
1180  # Left and clicked within timeline: change playhead
1181  if x_stamp <= 0.0:
1182  self.playhead = rospy.Time(0, 1)
1183  else:
1184  self.playhead = rospy.Time.from_sec(x_stamp)
1185  self.scene().update()
1186  self._dragged_pos = event.pos()
def _draw_minor_divisions(self, painter, stamps, start_stamp, division)
def _draw_major_divisions(self, painter, stamps, start_stamp, division)


rqt_py_trees
Author(s): Thibault Kruse, Michal Staniaszek, Daniel Stonier, Naveed Usmani
autogenerated on Mon Jun 10 2019 14:55:56