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
38 from python_qt_binding.QtGui
import QGraphicsItem
40 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]
131 self._topic_font.setBold(
False)
141 self._time_font.setBold(
False)
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()
218 if dstamp > self._end_stamp.to_sec() - self.
_stamp_right:
224 if dstamp > self.
_stamp_left - self._start_stamp.to_sec():
225 dstamp = self.
_stamp_left - self._start_stamp.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)
312 if self.
_qfont_width(split_name[-1]) < .5 * allowed_width:
314 last_item = split_name[-1]
315 split_name = split_name[:-1]
316 allowed_width = allowed_width - self.
_qfont_width(last_item)
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] +
'..' 326 trimmed = trimmed +
'/' + trimmed_item
328 trimmed = trimmed +
'/' + item
330 trimmed = trimmed +
'/' + last_item
331 trimmed = trimmed[1:]
332 trimmed_return = trimmed
333 return trimmed_return
337 Recalculates the layout of the of the timeline to take into account any changes that have occured 342 max_topic_name_width = -1
345 if max_topic_name_width <= topic_width:
346 max_topic_name_width = topic_width
351 topic_height = QFontMetrics(self.
_topic_font).height()
365 datatype = self.scene().get_datatype(topic)
369 renderer = self._timeline_renderers.get(datatype)
371 topic_height = renderer.get_segment_height(topic)
380 new_history_bottom = max([y + h
for (_, y, _, h)
in self._history_bounds.values()]) - 1
386 Draw all topic messages 387 :param painter: allows access to paint functions,''QPainter'' 389 for topic
in sorted(self._history_bounds.keys()):
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'' 405 datatype = self.scene().get_datatype(topic)
409 msg_combine_interval =
None 411 renderer = self._timeline_renderers.get(datatype)
412 if renderer
is not None:
414 if msg_combine_interval
is None:
423 end_index = bisect.bisect_left(all_stamps, self.
_stamp_right)
438 region_width = max(1, region_x_end - region_x_start)
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)
445 if topic
in self.scene()._listeners:
446 curpen = painter.pen()
447 oldwidth = curpen.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]
456 painter.drawLine(playhead_x, msg_y, playhead_x, msg_y + msg_height)
457 curpen.setWidth(oldwidth)
458 painter.setPen(curpen)
463 for (stamp_start, stamp_end)
in self.
_find_regions(all_stamps[:end_index], msg_combine_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)
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'' 489 Draws horizontal lines between each topic to visually separate the messages 490 :param painter: allows access to paint functions,''QPainter'' 500 painter.setPen(Qt.lightGray)
503 painter.setPen(Qt.lightGray)
505 left = max(clip_left, x)
506 painter.drawRect(left, y, min(clip_right - left, w), h)
513 Draws a box around the selected region 514 :param painter: allows access to paint functions,''QPainter'' 527 width = x_right - x_left
532 painter.drawRect(left, top, width, height)
535 painter.setBrush(Qt.NoBrush)
536 painter.drawLine(left, top, left, top + height)
537 painter.drawLine(left + width, top, left + width, top + height)
540 painter.setBrush(Qt.NoBrush)
541 painter.drawLine(left, top, left + width, top)
552 Draw a line and 2 triangles to denote the current position being viewed 553 :param painter: ,''QPainter'' 565 painter.drawPolygon(QPolygonF([QPointF(px, py + ph), QPointF(px + pw, py), QPointF(px - pw, py)]))
569 painter.drawPolygon(QPolygonF([QPointF(px, py), QPointF(px + pw, py + ph), QPointF(px - pw, py + ph)]))
576 Draw a simple black rectangle frame around the timeline view area 577 :param painter: ,''QPainter'' 582 painter.setBrush(Qt.NoBrush)
583 painter.setPen(Qt.black)
584 painter.drawRect(x, y, w, h)
590 Calculate positions of existing topic names and draw them on the left, one for each row 591 :param painter: ,''QPainter'' 593 topics = self._history_bounds.keys()
596 for text, coords
in zip([t.lstrip(
'/')
for t
in topics], coords):
604 Draw vertical grid-lines showing major and minor time divisions. 605 :param painter: allows access to paint functions,''QPainter'' 609 if len(major_divisions) == 0:
612 major_division = min(major_divisions)
615 if len(minor_divisions) > 0:
616 minor_division = min(minor_divisions)
618 minor_division =
None 620 start_stamp = self._start_stamp.to_sec()
622 major_stamps = list(self.
_get_stamps(start_stamp, major_division))
626 minor_stamps = [s
for s
in self.
_get_stamps(start_stamp, minor_division)
if s
not in major_stamps]
631 Draw black hashed vertical grid-lines showing major time divisions. 632 :param painter: allows access to paint functions,''QPainter'' 638 label = self.
_get_label(division, stamp - start_stamp)
640 if label_x + self.
_qfont_width(label) < self.scene().width():
644 painter.drawText(label_x, label_y, label)
654 Draw grey hashed vertical grid-lines showing minor time divisions. 655 :param painter: allows access to paint functions,''QPainter'' 672 for renderer
in self._timeline_renderers.values():
674 self._index_cache_thread.stop()
679 return [RawView] + self._viewer_types.get(
'*', []) + self._viewer_types.get(datatype, [])
685 plugin_descriptors = self.plugin_provider.discover(
None)
686 for plugin_descriptor
in plugin_descriptors:
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))
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))
698 timeline_renderer =
None 700 timeline_renderer = plugin.get_renderer_class()
701 except AttributeError:
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))
708 msg_types = plugin.get_message_types()
709 except AttributeError:
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))
715 qWarning(
'rqt_bag.TimelineFrame.load_plugins() plugin "%s" declares no message types:\n%s' % (plugin_descriptor.plugin_id(), e))
717 for msg_type
in msg_types:
718 self._viewer_types.setdefault(msg_type, []).append(view)
719 if timeline_renderer:
722 qDebug(
'rqt_bag.TimelineFrame.load_plugins() loaded plugin "%s"' % plugin_descriptor.plugin_id())
728 :returns: a list of the currently loaded renderers for the plugins 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))
750 self._rendered_topics.add(topic)
752 self._rendered_topics.clear()
753 self.scene().update()
759 self._rendered_topics.add(topic)
763 self._rendered_topics.remove(topic)
764 self.scene().update()
770 Updates the cache of message timestamps for the given topic. 771 :return: number of messages added to the index cache 788 if len(topic_cache) == 0:
791 start_time = rospy.Time.from_sec(max(0.0, topic_cache[-1]))
795 topic_cache_len = len(topic_cache)
797 for entry
in self.scene().get_entries([topic], start_time, end_time):
798 topic_cache.append(entry.stamp.to_sec())
801 self.invalidated_caches.remove(topic)
803 return len(topic_cache) - topic_cache_len
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 812 region_start, prev_stamp =
None,
None 815 if stamp - prev_stamp > max_interval:
816 region_end = prev_stamp
817 yield (region_start, region_end)
824 if region_start
and prev_stamp:
825 yield (region_start, prev_stamp)
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'' 836 stamp = start_stamp + int((self.
_stamp_left - start_stamp) / stamp_step) * stamp_step + stamp_step
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'' 848 secs = int(elapsed) % 60
850 mins = int(elapsed) / 60
855 if division >= 7 * 24 * 60 * 60:
857 elif division >= 24 * 60 * 60:
859 elif division >= 60 * 60:
861 elif division >= 5 * 60:
864 return '%dm%02ds' % (mins, secs)
865 elif division >= 0.1:
866 return '%d.%ss' % (secs, str(int(10.0 * (elapsed - int(elapsed)))))
867 elif division >= 0.01:
868 return '%d.%02ds' % (secs, int(100.0 * (elapsed - int(elapsed))))
870 return '%d.%03ds' % (secs, int(1000.0 * (elapsed - int(elapsed))))
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'' 885 elif fraction >= 1.0:
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'' 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'' 910 fraction = min(1.0, max(0.0, fraction))
920 if y > topic_y
and y <= topic_y + topic_h:
943 self.scene().update()
954 if start_stamp
is None:
961 if end_stamp == start_stamp:
962 end_stamp = start_stamp + rospy.Duration.from_sec(1.0)
965 self.scene().update()
987 new_range = new_interval[1] - new_interval[0]
989 actual_zoom = new_range / curr_range
991 if desired_zoom < 1.0:
992 return actual_zoom < 0.95
994 return actual_zoom > 1.05
1003 self.scene().update()
1008 @requires: left & right zoom interval sizes. 1015 center = self.playhead.to_sec()
1016 center_frac = (center - self.
_stamp_left) / stamp_interval
1018 new_stamp_interval = zoom * stamp_interval
1019 if new_stamp_interval == 0:
1028 left = center - center_frac * new_stamp_interval
1029 right = left + new_stamp_interval
1031 return (left, right)
1038 self._dynamic_timeline.resume()
1053 if event.modifiers() == Qt.ShiftModifier:
1056 x = self._clicked_pos.x()
1057 y = self._clicked_pos.y()
1062 if playhead_secs <= 0.0:
1065 self.
playhead = rospy.Time.from_sec(playhead_secs)
1066 self.scene().update()
1074 self.scene().update()
1084 self.scene().update()
1087 self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1092 if self.
_selecting_mode in [_SelectionMode.LEFT_MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1097 self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1098 self.scene().update()
1101 dz = event.delta() / 120.0
1111 if event.buttons() == Qt.NoButton:
1113 if self.
_selecting_mode in [_SelectionMode.MARKED, _SelectionMode.MOVE_LEFT, _SelectionMode.MOVE_RIGHT, _SelectionMode.SHIFTING]:
1120 self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1124 self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
1126 elif x > left_x
and x < right_x:
1128 self.scene().views()[0].setCursor(QCursor(Qt.OpenHandCursor))
1132 self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
1135 if event.buttons() == Qt.MidButton
or event.modifiers() == Qt.ShiftModifier:
1137 dx_drag, dy_drag = x - self._dragged_pos.x(), y - self._dragged_pos.y()
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):
1145 self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
1146 elif event.buttons() == Qt.LeftButton:
1148 clicked_x = self._clicked_pos.x()
1149 clicked_y = self._clicked_pos.y()
1160 self.scene().update()
1164 self.scene().update()
1168 self.scene().update()
1171 dx_drag = x - self._dragged_pos.x()
1176 self.scene().update()
1184 self.
playhead = rospy.Time.from_sec(x_stamp)
1185 self.scene().update()
_selected_region_outline_ends_color
def _draw_playhead(self, painter)
def _draw_minor_divisions(self, painter, stamps, start_stamp, division)
def _draw_major_divisions(self, painter, stamps, start_stamp, division)
def map_x_to_stamp(self, x, clamp_to_visible=True)
def _draw_selected_region(self, painter)
def _draw_topic_history(self, painter, topic)
def on_middle_down(self, event)
def translate_timeline(self, dstamp)
def on_left_down(self, event)
def set_timeline_view(self, stamp_left, stamp_right)
def can_zoom(self, desired_zoom)
def get_zoom_interval(self, zoom, center=None)
def on_mouse_move(self, event)
def _get_stamps(self, start_stamp, stamp_step)
def __init__(self, dynamic_timeline)
def map_y_to_topic(self, y)
def get_viewer_types(self, datatype)
def translate_timeline_left(self)
def is_renderer_active(self, topic)
def map_stamp_to_x(self, stamp, clamp_to_visible=True)
def set_renderers_active(self, active)
def _update_index_cache(self, topic)
def paint(self, painter, option, widget)
def _draw_topic_names(self, painter)
def _trimmed_topic_name(self, topic_name)
def on_mouse_up(self, event)
def _draw_topic_histories(self, painter)
def _draw_history_border(self, painter)
_history_background_color_alternate
_active_message_line_width
def translate_timeline_right(self)
def _find_regions(self, stamps, max_interval)
def _get_label(self, division, elapsed)
def emit_play_region(self)
def has_selected_region(self)
def _draw_topic_dividers(self, painter)
_selected_region_outline_top_color
def map_dx_to_dstamp(self, dx)
def set_renderer_active(self, topic, active)
def map_dstamp_to_dx(self, dstamp)
_history_background_color
_major_divisions_label_indent
def _set_playhead(self, playhead)
def _draw_bag_ends(self, painter)
def _qfont_width(self, name)
def _draw_time_divisions(self, painter)
def on_mousewheel(self, event)
def zoom_timeline(self, zoom, center=None)
def toggle_renderers(self)