33 from python_qt_binding.QtCore
import qDebug, QPointF, QRectF, Qt, qWarning, Signal
34 from python_qt_binding.QtGui
import QBrush, QCursor, QColor, QFont, \
35 QFontMetrics, QPen, QPolygonF
37 from python_qt_binding.QtGui
import QGraphicsItem
39 from python_qt_binding.QtWidgets
import QGraphicsItem
47 from .plugins.raw_view
import RawView
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
61 LEFT_MARKED =
'left marked'
64 MOVE_LEFT =
'move left'
65 MOVE_RIGHT =
'move right'
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
75 super(DynamicTimelineFrame, self).
__init__()
89 """Width of the history timeline in pixels."""
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]
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),
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()''
206 with self.scene()._playhead_lock:
213 self.scene().stick_to_end =
False
215 playhead_secs = playhead.to_sec()
230 entry = self.scene().get_entry(self.
_playhead, topic)
232 if topic
in self.scene()._playhead_positions
and self.scene()._playhead_positions[topic] == entry.stamp:
234 new_playhead_position = entry.stamp
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()
240 self.scene().update()
241 self.scene().status_bar_changed_signal.emit()
243 playhead = property(_get_playhead, _set_playhead)
263 if(play_region[0]
is not None and play_region[1]
is not None):
264 self.scene().selected_region_changed.emit(*play_region)
278 def paint(self, painter, option, widget):
300 This function trims the topic name down to a reasonable percentage of the viewable scene area
304 trimmed_return = topic_name
308 split_name = topic_name.split(
'/')
309 split_name = filter(
lambda a: a !=
'', split_name)
310 if sys.version_info[0] > 2:
311 split_name = [n
for n
in split_name]
314 if self.
_qfont_width(split_name[-1]) < .5 * allowed_width:
316 last_item = split_name[-1]
317 split_name = split_name[:-1]
318 allowed_width = allowed_width - self.
_qfont_width(last_item)
320 for item
in split_name:
321 if self.
_qfont_width(item) > allowed_width / float(len(split_name)):
322 trimmed_item = item[:-3] +
'..'
323 while self.
_qfont_width(trimmed_item) > allowed_width / float(len(split_name)):
324 if len(trimmed_item) >= 3:
325 trimmed_item = trimmed_item[:-3] +
'..'
328 trimmed = trimmed +
'/' + trimmed_item
330 trimmed = trimmed +
'/' + item
332 trimmed = trimmed +
'/' + last_item
333 trimmed = trimmed[1:]
334 trimmed_return = trimmed
335 return trimmed_return
339 Recalculates the layout of the of the timeline to take into account any changes that have occured
344 max_topic_name_width = -1
347 if max_topic_name_width <= topic_width:
348 max_topic_name_width = topic_width
353 topic_height = QFontMetrics(self.
_topic_font).height()
367 datatype = self.scene().get_datatype(topic)
373 topic_height = renderer.get_segment_height(topic)
382 new_history_bottom = max([y + h
for (_, y, _, h)
in self.
_history_bounds.values()]) - 1
388 Draw all topic messages
389 :param painter: allows access to paint functions,''QPainter''
396 Draw boxes corrisponding to message regions on the timeline.
397 :param painter: allows access to paint functions,''QPainter''
398 :param topic: the topic for which message boxes should be drawn, ''str''
407 datatype = self.scene().get_datatype(topic)
411 msg_combine_interval =
None
414 if renderer
is not None:
416 if msg_combine_interval
is None:
425 end_index = bisect.bisect_left(all_stamps, self.
_stamp_right)
440 region_width = max(1, region_x_end - region_x_start)
442 painter.setBrush(QBrush(datatype_color))
443 painter.setPen(QPen(datatype_color, 1))
444 painter.drawRect(region_x_start, msg_y, region_width, msg_height)
447 if topic
in self.scene()._listeners:
448 curpen = painter.pen()
449 oldwidth = curpen.width()
451 painter.setPen(curpen)
452 playhead_stamp =
None
453 playhead_index = bisect.bisect_right(all_stamps, self.
playhead.to_sec()) - 1
455 if playhead_index >= 0:
456 playhead_stamp = all_stamps[playhead_index]
459 painter.drawLine(playhead_x, msg_y, playhead_x, msg_y + msg_height)
460 curpen.setWidth(oldwidth)
461 painter.setPen(curpen)
466 for (stamp_start, stamp_end)
in self.
_find_regions(all_stamps[:end_index], msg_combine_interval):
472 region_width = max(1, region_x_end - region_x_start)
473 renderer.draw_timeline_segment(painter, topic, stamp_start, stamp_end, region_x_start, msg_y, region_width, msg_height)
480 Draw markers to indicate the area the bag file represents within the current visible area.
481 :param painter: allows access to paint functions,''QPainter''
492 Draws horizontal lines between each topic to visually separate the messages
493 :param painter: allows access to paint functions,''QPainter''
503 painter.setPen(Qt.lightGray)
506 painter.setPen(Qt.lightGray)
508 left = max(clip_left, x)
509 painter.drawRect(left, y, min(clip_right - left, w), h)
516 Draws a box around the selected region
517 :param painter: allows access to paint functions,''QPainter''
530 width = x_right - x_left
535 painter.drawRect(left, top, width, height)
538 painter.setBrush(Qt.NoBrush)
539 painter.drawLine(left, top, left, top + height)
540 painter.drawLine(left + width, top, left + width, top + height)
543 painter.setBrush(Qt.NoBrush)
544 painter.drawLine(left, top, left + width, top)
555 Draw a line and 2 triangles to denote the current position being viewed
556 :param painter: ,''QPainter''
568 painter.drawPolygon(QPolygonF([QPointF(px, py + ph), QPointF(px + pw, py), QPointF(px - pw, py)]))
572 painter.drawPolygon(QPolygonF([QPointF(px, py), QPointF(px + pw, py + ph), QPointF(px - pw, py + ph)]))
579 Draw a simple black rectangle frame around the timeline view area
580 :param painter: ,''QPainter''
585 painter.setBrush(Qt.NoBrush)
586 painter.setPen(Qt.black)
587 painter.drawRect(x, y, w, h)
593 Calculate positions of existing topic names and draw them on the left, one for each row
594 :param painter: ,''QPainter''
599 for text, coords
in zip([t.lstrip(
'/')
for t
in topics], coords):
607 Draw vertical grid-lines showing major and minor time divisions.
608 :param painter: allows access to paint functions,''QPainter''
612 if len(major_divisions) == 0:
615 major_division = min(major_divisions)
618 if len(minor_divisions) > 0:
619 minor_division = min(minor_divisions)
621 minor_division =
None
625 major_stamps = list(self.
_get_stamps(start_stamp, major_division))
629 minor_stamps = [s
for s
in self.
_get_stamps(start_stamp, minor_division)
if s
not in major_stamps]
634 Draw black hashed vertical grid-lines showing major time divisions.
635 :param painter: allows access to paint functions,''QPainter''
641 label = self.
_get_label(division, stamp - start_stamp)
643 if label_x + self.
_qfont_width(label) < self.scene().width():
647 painter.drawText(label_x, label_y, label)
657 Draw grey hashed vertical grid-lines showing minor time divisions.
658 :param painter: allows access to paint functions,''QPainter''
689 for plugin_descriptor
in plugin_descriptors:
691 plugin = self.
plugin_provider.load(plugin_descriptor.plugin_id(), plugin_context=
None)
692 except Exception
as e:
693 qWarning(
'rqt_bag.TimelineFrame.load_plugins() failed to load plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
696 view = plugin.get_view_class()
697 except Exception
as e:
698 qWarning(
'rqt_bag.TimelineFrame.load_plugins() failed to get view from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
701 timeline_renderer =
None
703 timeline_renderer = plugin.get_renderer_class()
704 except AttributeError:
706 except Exception
as e:
707 qWarning(
'rqt_bag.TimelineFrame.load_plugins() failed to get renderer from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
711 msg_types = plugin.get_message_types()
712 except AttributeError:
714 except Exception
as e:
715 qWarning(
'rqt_bag.TimelineFrame.load_plugins() failed to get message types from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
718 qWarning(
'rqt_bag.TimelineFrame.load_plugins() plugin "%s" declares no message types:\n%s' % (plugin_descriptor.plugin_id(), e))
720 for msg_type
in msg_types:
722 if timeline_renderer:
725 qDebug(
'rqt_bag.TimelineFrame.load_plugins() loaded plugin "%s"' % plugin_descriptor.plugin_id())
731 :returns: a list of the currently loaded renderers for the plugins
736 datatype = self.scene().get_datatype(topic)
738 if renderer
is not None:
739 renderers.append((topic, renderer))
756 self.scene().update()
767 self.scene().update()
773 Updates the cache of message timestamps for the given topic.
774 :return: number of messages added to the index cache
791 if len(topic_cache) == 0:
794 start_time = rospy.Time.from_sec(max(0.0, topic_cache[-1]))
798 topic_cache_len = len(topic_cache)
800 for entry
in self.scene().get_entries([topic], start_time, end_time):
801 topic_cache.append(entry.stamp.to_sec())
806 return len(topic_cache) - topic_cache_len
810 Group timestamps into regions connected by timestamps less than max_interval secs apart.
811 If no other timestamps are within the interval, then return start = end.
812 :param float[] start_stamp:
813 :param float max_interval: maximum size of each region
815 region_start, prev_stamp =
None,
None
818 if stamp - prev_stamp > max_interval:
819 region_end = prev_stamp
820 yield (region_start, region_end)
827 if region_start
and prev_stamp:
828 yield (region_start, prev_stamp)
832 Generate visible stamps every stamp_step
833 :param start_stamp: beginning of timeline stamp, ''int''
834 :param stamp_step: seconds between each division, ''int''
839 stamp = start_stamp + int((self.
_stamp_left - start_stamp) / stamp_step) * stamp_step + stamp_step
847 :param division: number of seconds in a division, ''int''
848 :param elapsed: seconds from the beginning, ''int''
849 :returns: relevent time elapsed string, ''str''
851 secs = int(elapsed) % 60
853 mins = int(elapsed) / 60
858 if division >= 7 * 24 * 60 * 60:
860 elif division >= 24 * 60 * 60:
862 elif division >= 60 * 60:
864 elif division >= 5 * 60:
867 return '%dm%02ds' % (mins, secs)
868 elif division >= 0.1:
869 return '%d.%ss' % (secs, str(int(10.0 * (elapsed - int(elapsed)))))
870 elif division >= 0.01:
871 return '%d.%02ds' % (secs, int(100.0 * (elapsed - int(elapsed))))
873 return '%d.%03ds' % (secs, int(1000.0 * (elapsed - int(elapsed))))
878 converts a pixel x value to a stamp
879 :param x: pixel value to be converted, ''int''
880 :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool''
881 :returns: timestamp, ''int''
888 elif fraction >= 1.0:
895 converts a distance in pixel space to a distance in stamp space
896 :param dx: distance in pixel space to be converted, ''int''
897 :returns: distance in stamp space, ''float''
903 converts a timestamp to the x value where that stamp exists in the timeline
904 :param stamp: timestamp to be converted, ''int''
905 :param clamp_to_visible: disallow values that are greater than the current timeline bounds,''bool''
906 :returns: # of pixels from the left boarder, ''int''
913 fraction = min(1.0, max(0.0, fraction))
923 if y > topic_y
and y <= topic_y + topic_h:
946 self.scene().update()
957 if start_stamp
is None:
964 if end_stamp == start_stamp:
965 end_stamp = start_stamp + rospy.Duration.from_sec(1.0)
968 self.scene().update()
990 new_range = new_interval[1] - new_interval[0]
992 actual_zoom = new_range / curr_range
994 if desired_zoom < 1.0:
995 return actual_zoom < 0.95
997 return actual_zoom > 1.05
1006 self.scene().update()
1011 @requires: left & right zoom interval sizes.
1019 center_frac = (center - self.
_stamp_left) / stamp_interval
1021 new_stamp_interval = zoom * stamp_interval
1022 if new_stamp_interval == 0:
1031 left = center - center_frac * new_stamp_interval
1032 right = left + new_stamp_interval
1034 return (left, right)
1056 if event.modifiers() == Qt.ShiftModifier:
1065 if playhead_secs <= 0.0:
1068 self.
playhead = rospy.Time.from_sec(playhead_secs)
1069 self.scene().update()
1077 self.scene().update()
1087 self.scene().update()
1090 self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1095 if self.
_selecting_mode in [_SelectionMode.LEFT_MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1100 self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1101 self.scene().update()
1104 dz = event.delta() / 120.0
1114 if event.buttons() == Qt.NoButton:
1116 if self.
_selecting_mode in [_SelectionMode.MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1123 self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1127 self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1129 elif x > left_x
and x < right_x:
1131 self.scene().views()[0].setCursor(QCursor(Qt.OpenHandCursor))
1135 self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1138 if event.buttons() == Qt.MidButton
or event.modifiers() == Qt.ShiftModifier:
1144 if (dx_drag == 0
and abs(dy_drag) > 0)
or (dx_drag != 0
and abs(float(dy_drag) / dx_drag) > 0.2
and abs(dy_drag) > 1):
1148 self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1149 elif event.buttons() == Qt.LeftButton:
1163 self.scene().update()
1167 self.scene().update()
1171 self.scene().update()
1179 self.scene().update()
1187 self.
playhead = rospy.Time.from_sec(x_stamp)
1188 self.scene().update()