00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 from python_qt_binding.QtCore import qDebug, QPointF, QRectF, Qt, qWarning, Signal
00035 from python_qt_binding.QtGui import QBrush, QCursor, QColor, QFont, \
00036 QFontMetrics, QPen, QPolygonF
00037 from python_qt_binding.QtWidgets import QGraphicsItem
00038 import rospy
00039
00040 import bisect
00041 import threading
00042
00043 from .index_cache_thread import IndexCacheThread
00044 from .plugins.raw_view import RawView
00045
00046
00047 class _SelectionMode(object):
00048
00049 """
00050 SelectionMode states consolidated for readability
00051 NONE = no region marked or started
00052 LEFT_MARKED = one end of the region has been marked
00053 MARKED = both ends of the region have been marked
00054 SHIFTING = region is marked; currently dragging the region
00055 MOVE_LEFT = region is marked; currently changing the left boundry of the selected region
00056 MOVE_RIGHT = region is marked; currently changing the right boundry of the selected region
00057 """
00058 NONE = 'none'
00059 LEFT_MARKED = 'left marked'
00060 MARKED = 'marked'
00061 SHIFTING = 'shifting'
00062 MOVE_LEFT = 'move left'
00063 MOVE_RIGHT = 'move right'
00064
00065
00066 class TimelineFrame(QGraphicsItem):
00067
00068 """
00069 TimelineFrame Draws the framing elements for the bag messages
00070 (time delimiters, labels, topic names and backgrounds).
00071 Also handles mouse callbacks since they interact closely with the drawn elements
00072 """
00073
00074 def __init__(self, bag_timeline):
00075 super(TimelineFrame, self).__init__()
00076 self._bag_timeline = bag_timeline
00077 self._clicked_pos = None
00078 self._dragged_pos = None
00079
00080
00081 self._start_stamp = None
00082 self._end_stamp = None
00083 self._stamp_left = None
00084 self._stamp_right = None
00085 self._history_top = 30
00086 self._history_left = 0
00087 self._history_width = 0
00088 self._history_bottom = 0
00089 self._history_bounds = {}
00090 self._margin_left = 4
00091 self._margin_right = 20
00092 self._margin_bottom = 20
00093 self._history_top = 30
00094
00095
00096
00097 self._bag_end_color = QColor(0, 0, 0, 25)
00098 self._history_background_color_alternate = QColor(179, 179, 179, 25)
00099 self._history_background_color = QColor(204, 204, 204, 102)
00100
00101
00102
00103
00104
00105
00106
00107
00108 self._sec_divisions = [0.001, 0.005, 0.01, 0.05, 0.1, 0.5,
00109 1, 5, 15, 30,
00110 1 * 60, 2 * 60, 5 * 60, 10 * 60, 15 * 60, 30 * 60,
00111 1 * 60 * 60, 2 * 60 * 60, 3 * 60 * 60, 6 * 60 * 60, 12 * 60 * 60,
00112 1 * 60 * 60 * 24, 7 * 60 * 60 * 24]
00113 self._minor_spacing = 15
00114 self._major_spacing = 50
00115 self._major_divisions_label_indent = 3
00116 self._major_division_pen = QPen(QBrush(Qt.black), 0, Qt.DashLine)
00117 self._minor_division_pen = QPen(QBrush(QColor(153, 153, 153, 128)), 0, Qt.DashLine)
00118 self._minor_division_tick_pen = QPen(QBrush(QColor(128, 128, 128, 128)), 0)
00119
00120
00121 self.topics = []
00122 self._topics_by_datatype = {}
00123 self._topic_font_height = None
00124 self._topic_name_sizes = None
00125
00126 self._topic_name_spacing = 3
00127 self._topic_font_size = 10.0
00128 self._topic_font = QFont("cairo")
00129 self._topic_font.setPointSize(self._topic_font_size)
00130 self._topic_font.setBold(False)
00131 self._topic_vertical_padding = 4
00132
00133 self._topic_name_max_percent = 25.0
00134
00135
00136 self._time_tick_height = 5
00137 self._time_font_height = None
00138 self._time_font_size = 10.0
00139 self._time_font = QFont("cairo")
00140 self._time_font.setPointSize(self._time_font_size)
00141 self._time_font.setBold(False)
00142
00143
00144 self._default_brush = QBrush(Qt.black, Qt.SolidPattern)
00145 self._default_pen = QPen(Qt.black)
00146 self._default_datatype_color = QColor(0, 0, 102, 204)
00147 self._datatype_colors = {
00148 'sensor_msgs/CameraInfo': QColor(0, 0, 77, 204),
00149 'sensor_msgs/Image': QColor(0, 77, 77, 204),
00150 'sensor_msgs/LaserScan': QColor(153, 0, 0, 204),
00151 'pr2_msgs/LaserScannerSignal': QColor(153, 0, 0, 204),
00152 'pr2_mechanism_msgs/MechanismState': QColor(0, 153, 0, 204),
00153 'tf/tfMessage': QColor(0, 153, 0, 204),
00154 }
00155
00156 self._default_msg_combine_px = 1.0
00157 self._active_message_line_width = 3
00158
00159
00160 self._selected_region_color = QColor(0, 179, 0, 21)
00161 self._selected_region_outline_top_color = QColor(0.0, 77, 0.0, 51)
00162 self._selected_region_outline_ends_color = QColor(0.0, 77, 0.0, 102)
00163 self._selecting_mode = _SelectionMode.NONE
00164 self._selected_left = None
00165 self._selected_right = None
00166 self._selection_handle_width = 3.0
00167
00168
00169 self._playhead = None
00170 self._paused = False
00171 self._playhead_pointer_size = (6, 6)
00172 self._playhead_line_width = 1
00173 self._playhead_color = QColor(255, 0, 0, 191)
00174
00175
00176 self._zoom_sensitivity = 0.005
00177 self._min_zoom_speed = 0.5
00178 self._max_zoom_speed = 2.0
00179 self._min_zoom = 0.0001
00180 self._max_zoom = 50000.0
00181
00182
00183 self._viewer_types = {}
00184 self._timeline_renderers = {}
00185 self._rendered_topics = set()
00186 self.load_plugins()
00187
00188
00189 self.index_cache_cv = threading.Condition()
00190 self.index_cache = {}
00191 self.invalidated_caches = set()
00192 self._index_cache_thread = IndexCacheThread(self)
00193
00194
00195
00196
00197
00198
00199 def _get_playhead(self):
00200 return self._playhead
00201
00202 def _set_playhead(self, playhead):
00203 """
00204 Sets the playhead to the new position, notifies the threads and updates the scene
00205 so it will redraw
00206 :signal: emits status_bar_changed_signal if the playhead is successfully set
00207 :param playhead: Time to set the playhead to, ''rospy.Time()''
00208 """
00209 with self.scene()._playhead_lock:
00210 if playhead == self._playhead:
00211 return
00212
00213 self._playhead = playhead
00214 if self._playhead != self._end_stamp:
00215 self.scene().stick_to_end = False
00216
00217 playhead_secs = playhead.to_sec()
00218 if playhead_secs > self._stamp_right:
00219 dstamp = playhead_secs - self._stamp_right + \
00220 (self._stamp_right - self._stamp_left) * 0.75
00221 if dstamp > self._end_stamp.to_sec() - self._stamp_right:
00222 dstamp = self._end_stamp.to_sec() - self._stamp_right
00223 self.translate_timeline(dstamp)
00224
00225 elif playhead_secs < self._stamp_left:
00226 dstamp = self._stamp_left - playhead_secs + \
00227 (self._stamp_right - self._stamp_left) * 0.75
00228 if dstamp > self._stamp_left - self._start_stamp.to_sec():
00229 dstamp = self._stamp_left - self._start_stamp.to_sec()
00230 self.translate_timeline(-dstamp)
00231
00232
00233 for topic in self.topics:
00234 bag, entry = self.scene().get_entry(self._playhead, topic)
00235 if entry:
00236 if topic in self.scene()._playhead_positions and \
00237 self.scene()._playhead_positions[topic] == (bag, entry.position):
00238 continue
00239 new_playhead_position = (bag, entry.position)
00240 else:
00241 new_playhead_position = (None, None)
00242 with self.scene()._playhead_positions_cvs[topic]:
00243 self.scene()._playhead_positions[topic] = new_playhead_position
00244
00245 self.scene()._playhead_positions_cvs[topic].notify_all()
00246 self.scene().update()
00247 self.scene().status_bar_changed_signal.emit()
00248
00249 playhead = property(_get_playhead, _set_playhead)
00250
00251
00252 @property
00253 def _history_right(self):
00254 return self._history_left + self._history_width
00255
00256 @property
00257 def has_selected_region(self):
00258 return self._selected_left is not None and self._selected_right is not None
00259
00260 @property
00261 def play_region(self):
00262 if self.has_selected_region:
00263 return (
00264 rospy.Time.from_sec(self._selected_left), rospy.Time.from_sec(self._selected_right))
00265 else:
00266 return (self._start_stamp, self._end_stamp)
00267
00268 def emit_play_region(self):
00269 play_region = self.play_region
00270 if(play_region[0] is not None and play_region[1] is not None):
00271 self.scene().selected_region_changed.emit(*play_region)
00272
00273 @property
00274 def start_stamp(self):
00275 return self._start_stamp
00276
00277 @property
00278 def end_stamp(self):
00279 return self._end_stamp
00280
00281
00282 def boundingRect(self):
00283 return QRectF(
00284 0, 0,
00285 self._history_left + self._history_width + self._margin_right,
00286 self._history_bottom + self._margin_bottom)
00287
00288 def paint(self, painter, option, widget):
00289 if self._start_stamp is None:
00290 return
00291
00292 self._layout()
00293 self._draw_topic_dividers(painter)
00294 self._draw_selected_region(painter)
00295 self._draw_time_divisions(painter)
00296 self._draw_topic_histories(painter)
00297 self._draw_bag_ends(painter)
00298 self._draw_topic_names(painter)
00299 self._draw_history_border(painter)
00300 self._draw_playhead(painter)
00301
00302
00303
00304
00305 def _qfont_width(self, name):
00306 return QFontMetrics(self._topic_font).width(name)
00307
00308 def _trimmed_topic_name(self, topic_name):
00309 """
00310 This function trims the topic name down to a reasonable percentage of the viewable scene
00311 area
00312 """
00313 allowed_width = self._scene_width * (self._topic_name_max_percent / 100.0)
00314 allowed_width = allowed_width - self._topic_name_spacing - self._margin_left
00315 trimmed_return = topic_name
00316 if allowed_width < self._qfont_width(topic_name):
00317
00318 trimmed = ''
00319 split_name = topic_name.split('/')
00320 split_name = filter(lambda a: a != '', split_name)
00321
00322 popped_last = False
00323 if self._qfont_width(split_name[-1]) < .5 * allowed_width:
00324 popped_last = True
00325 last_item = split_name[-1]
00326 split_name = split_name[:-1]
00327 allowed_width = allowed_width - self._qfont_width(last_item)
00328
00329 for item in split_name:
00330 if self._qfont_width(item) > allowed_width / float(len(split_name)):
00331 trimmed_item = item[:-3] + '..'
00332 while self._qfont_width(trimmed_item) > allowed_width / float(len(split_name)):
00333 if len(trimmed_item) >= 3:
00334 trimmed_item = trimmed_item[:-3] + '..'
00335 else:
00336 break
00337 trimmed = trimmed + '/' + trimmed_item
00338 else:
00339 trimmed = trimmed + '/' + item
00340 if popped_last:
00341 trimmed = trimmed + '/' + last_item
00342 trimmed = trimmed[1:]
00343 trimmed_return = trimmed
00344 return trimmed_return
00345
00346 def _layout(self):
00347 """
00348 Recalculates the layout of the of the timeline to take into account any changes that have
00349 occured
00350 """
00351
00352 self._scene_width = self.scene().views()[0].size().width()
00353
00354 max_topic_name_width = -1
00355 for topic in self.topics:
00356 topic_width = self._qfont_width(self._trimmed_topic_name(topic))
00357 if max_topic_name_width <= topic_width:
00358 max_topic_name_width = topic_width
00359
00360
00361 self._topic_font_height = -1
00362 for topic in self.topics:
00363 topic_height = QFontMetrics(self._topic_font).height()
00364 if self._topic_font_height <= topic_height:
00365 self._topic_font_height = topic_height
00366
00367
00368 new_history_left = self._margin_left + max_topic_name_width + self._topic_name_spacing
00369 new_history_width = self._scene_width - new_history_left - self._margin_right
00370 self._history_left = new_history_left
00371 self._history_width = new_history_width
00372
00373
00374 self._history_bounds = {}
00375 y = self._history_top
00376 for topic in self.topics:
00377 datatype = self.scene().get_datatype(topic)
00378
00379 topic_height = None
00380 if topic in self._rendered_topics:
00381 renderer = self._timeline_renderers.get(datatype)
00382 if renderer:
00383 topic_height = renderer.get_segment_height(topic)
00384 if not topic_height:
00385 topic_height = self._topic_font_height + self._topic_vertical_padding
00386
00387 self._history_bounds[topic] = (self._history_left, y, self._history_width, topic_height)
00388
00389 y += topic_height
00390
00391
00392 new_history_bottom = max([y + h for (_, y, _, h) in self._history_bounds.values()]) - 1
00393 if new_history_bottom != self._history_bottom:
00394 self._history_bottom = new_history_bottom
00395
00396 def _draw_topic_histories(self, painter):
00397 """
00398 Draw all topic messages
00399 :param painter: allows access to paint functions,''QPainter''
00400 """
00401 for topic in sorted(self._history_bounds.keys()):
00402 self._draw_topic_history(painter, topic)
00403
00404 def _draw_topic_history(self, painter, topic):
00405 """
00406 Draw boxes corrisponding to message regions on the timeline.
00407 :param painter: allows access to paint functions,''QPainter''
00408 :param topic: the topic for which message boxes should be drawn, ''str''
00409 """
00410
00411
00412 _, y, _, h = self._history_bounds[topic]
00413
00414 msg_y = y + 2
00415 msg_height = h - 2
00416
00417 datatype = self.scene().get_datatype(topic)
00418
00419
00420 renderer = None
00421 msg_combine_interval = None
00422 if topic in self._rendered_topics:
00423 renderer = self._timeline_renderers.get(datatype)
00424 if not renderer is None:
00425 msg_combine_interval = self.map_dx_to_dstamp(renderer.msg_combine_px)
00426 if msg_combine_interval is None:
00427 msg_combine_interval = self.map_dx_to_dstamp(self._default_msg_combine_px)
00428
00429
00430 if topic not in self.index_cache:
00431 return
00432 all_stamps = self.index_cache[topic]
00433
00434
00435 end_index = bisect.bisect_left(all_stamps, self._stamp_right)
00436
00437 datatype_color = self._datatype_colors.get(datatype, self._default_datatype_color)
00438
00439 width_interval = self._history_width / (self._stamp_right - self._stamp_left)
00440
00441
00442 for (stamp_start, stamp_end) in \
00443 self._find_regions(
00444 all_stamps[:end_index],
00445 self.map_dx_to_dstamp(self._default_msg_combine_px)):
00446 if stamp_end < self._stamp_left:
00447 continue
00448
00449 region_x_start = self._history_left + (stamp_start - self._stamp_left) * width_interval
00450 if region_x_start < self._history_left:
00451 region_x_start = self._history_left
00452 region_x_end = self._history_left + (stamp_end - self._stamp_left) * width_interval
00453 region_width = max(1, region_x_end - region_x_start)
00454
00455 painter.setBrush(QBrush(datatype_color))
00456 painter.setPen(QPen(datatype_color, 1))
00457 painter.drawRect(region_x_start, msg_y, region_width, msg_height)
00458
00459
00460 if topic in self.scene()._listeners:
00461 curpen = painter.pen()
00462 oldwidth = curpen.width()
00463 curpen.setWidth(self._active_message_line_width)
00464 painter.setPen(curpen)
00465 playhead_stamp = None
00466 playhead_index = bisect.bisect_right(all_stamps, self.playhead.to_sec()) - 1
00467 if playhead_index >= 0:
00468 playhead_stamp = all_stamps[playhead_index]
00469 if playhead_stamp > self._stamp_left and playhead_stamp < self._stamp_right:
00470 playhead_x = self._history_left + \
00471 (all_stamps[playhead_index] - self._stamp_left) * width_interval
00472 painter.drawLine(playhead_x, msg_y, playhead_x, msg_y + msg_height)
00473 curpen.setWidth(oldwidth)
00474 painter.setPen(curpen)
00475
00476
00477 if renderer:
00478
00479 for (stamp_start, stamp_end) in \
00480 self._find_regions(all_stamps[:end_index], msg_combine_interval):
00481 if stamp_end < self._stamp_left:
00482 continue
00483
00484 region_x_start = self._history_left + \
00485 (stamp_start - self._stamp_left) * width_interval
00486 region_x_end = self._history_left + (stamp_end - self._stamp_left) * width_interval
00487 region_width = max(1, region_x_end - region_x_start)
00488 renderer.draw_timeline_segment(
00489 painter, topic, stamp_start, stamp_end,
00490 region_x_start, msg_y, region_width, msg_height)
00491
00492 painter.setBrush(self._default_brush)
00493 painter.setPen(self._default_pen)
00494
00495 def _draw_bag_ends(self, painter):
00496 """
00497 Draw markers to indicate the area the bag file represents within the current visible area.
00498 :param painter: allows access to paint functions,''QPainter''
00499 """
00500 x_start, x_end = self.map_stamp_to_x(
00501 self._start_stamp.to_sec()), self.map_stamp_to_x(self._end_stamp.to_sec())
00502 painter.setBrush(QBrush(self._bag_end_color))
00503 painter.drawRect(self._history_left, self._history_top, x_start -
00504 self._history_left, self._history_bottom - self._history_top)
00505 painter.drawRect(x_end, self._history_top, self._history_left +
00506 self._history_width - x_end, self._history_bottom - self._history_top)
00507 painter.setBrush(self._default_brush)
00508 painter.setPen(self._default_pen)
00509
00510 def _draw_topic_dividers(self, painter):
00511 """
00512 Draws horizontal lines between each topic to visually separate the messages
00513 :param painter: allows access to paint functions,''QPainter''
00514 """
00515 clip_left = self._history_left
00516 clip_right = self._history_left + self._history_width
00517
00518 row = 0
00519 for topic in self.topics:
00520 (x, y, w, h) = self._history_bounds[topic]
00521
00522 if row % 2 == 0:
00523 painter.setPen(Qt.lightGray)
00524 painter.setBrush(QBrush(self._history_background_color_alternate))
00525 else:
00526 painter.setPen(Qt.lightGray)
00527 painter.setBrush(QBrush(self._history_background_color))
00528 left = max(clip_left, x)
00529 painter.drawRect(left, y, min(clip_right - left, w), h)
00530 row += 1
00531 painter.setBrush(self._default_brush)
00532 painter.setPen(self._default_pen)
00533
00534 def _draw_selected_region(self, painter):
00535 """
00536 Draws a box around the selected region
00537 :param painter: allows access to paint functions,''QPainter''
00538 """
00539 if self._selected_left is None:
00540 return
00541
00542 x_left = self.map_stamp_to_x(self._selected_left)
00543 if self._selected_right is not None:
00544 x_right = self.map_stamp_to_x(self._selected_right)
00545 else:
00546 x_right = self.map_stamp_to_x(self.playhead.to_sec())
00547
00548 left = x_left
00549 top = self._history_top - self._playhead_pointer_size[1] - 5 - self._time_font_size - 4
00550 width = x_right - x_left
00551 height = self._history_top - top
00552
00553 painter.setPen(self._selected_region_color)
00554 painter.setBrush(QBrush(self._selected_region_color))
00555 painter.drawRect(left, top, width, height)
00556
00557 painter.setPen(self._selected_region_outline_ends_color)
00558 painter.setBrush(Qt.NoBrush)
00559 painter.drawLine(left, top, left, top + height)
00560 painter.drawLine(left + width, top, left + width, top + height)
00561
00562 painter.setPen(self._selected_region_outline_top_color)
00563 painter.setBrush(Qt.NoBrush)
00564 painter.drawLine(left, top, left + width, top)
00565
00566 painter.setPen(self._selected_region_outline_top_color)
00567 painter.drawLine(left, self._history_top, left, self._history_bottom)
00568 painter.drawLine(left + width, self._history_top, left + width, self._history_bottom)
00569
00570 painter.setBrush(self._default_brush)
00571 painter.setPen(self._default_pen)
00572
00573 def _draw_playhead(self, painter):
00574 """
00575 Draw a line and 2 triangles to denote the current position being viewed
00576 :param painter: ,''QPainter''
00577 """
00578 px = self.map_stamp_to_x(self.playhead.to_sec())
00579 pw, ph = self._playhead_pointer_size
00580
00581
00582 painter.setPen(QPen(self._playhead_color))
00583 painter.setBrush(QBrush(self._playhead_color))
00584 painter.drawLine(px, self._history_top - 1, px, self._history_bottom + 2)
00585
00586
00587 py = self._history_top - ph
00588 painter.drawPolygon(
00589 QPolygonF([QPointF(px, py + ph), QPointF(px + pw, py), QPointF(px - pw, py)]))
00590
00591
00592 py = self._history_bottom + 1
00593 painter.drawPolygon(
00594 QPolygonF([QPointF(px, py), QPointF(px + pw, py + ph), QPointF(px - pw, py + ph)]))
00595
00596 painter.setBrush(self._default_brush)
00597 painter.setPen(self._default_pen)
00598
00599 def _draw_history_border(self, painter):
00600 """
00601 Draw a simple black rectangle frame around the timeline view area
00602 :param painter: ,''QPainter''
00603 """
00604 bounds_width = min(self._history_width, self.scene().width())
00605 x, y, w, h = self._history_left, self._history_top, bounds_width, self._history_bottom - \
00606 self._history_top
00607
00608 painter.setBrush(Qt.NoBrush)
00609 painter.setPen(Qt.black)
00610 painter.drawRect(x, y, w, h)
00611 painter.setBrush(self._default_brush)
00612 painter.setPen(self._default_pen)
00613
00614 def _draw_topic_names(self, painter):
00615 """
00616 Calculate positions of existing topic names and draw them on the left, one for each row
00617 :param painter: ,''QPainter''
00618 """
00619 topics = self._history_bounds.keys()
00620 coords = [(self._margin_left, y + (h / 2) + (self._topic_font_height / 2))
00621 for (_, y, _, h) in self._history_bounds.values()]
00622
00623 for text, coords in zip([t.lstrip('/') for t in topics], coords):
00624 painter.setBrush(self._default_brush)
00625 painter.setPen(self._default_pen)
00626 painter.setFont(self._topic_font)
00627 painter.drawText(coords[0], coords[1], self._trimmed_topic_name(text))
00628
00629 def _draw_time_divisions(self, painter):
00630 """
00631 Draw vertical grid-lines showing major and minor time divisions.
00632 :param painter: allows access to paint functions,''QPainter''
00633 """
00634 x_per_sec = self.map_dstamp_to_dx(1.0)
00635 major_divisions = [s for s in self._sec_divisions if x_per_sec * s >= self._major_spacing]
00636 if len(major_divisions) == 0:
00637 major_division = max(self._sec_divisions)
00638 else:
00639 major_division = min(major_divisions)
00640
00641 minor_divisions = [s for s in self._sec_divisions
00642 if x_per_sec * s >= self._minor_spacing and major_division % s == 0]
00643 if len(minor_divisions) > 0:
00644 minor_division = min(minor_divisions)
00645 else:
00646 minor_division = None
00647
00648 start_stamp = self._start_stamp.to_sec()
00649
00650 major_stamps = list(self._get_stamps(start_stamp, major_division))
00651 self._draw_major_divisions(painter, major_stamps, start_stamp, major_division)
00652
00653 if minor_division:
00654 minor_stamps = [
00655 s for s in self._get_stamps(start_stamp, minor_division) if s not in major_stamps]
00656 self._draw_minor_divisions(painter, minor_stamps, start_stamp, minor_division)
00657
00658 def _draw_major_divisions(self, painter, stamps, start_stamp, division):
00659 """
00660 Draw black hashed vertical grid-lines showing major time divisions.
00661 :param painter: allows access to paint functions,''QPainter''
00662 """
00663 label_y = self._history_top - self._playhead_pointer_size[1] - 5
00664 for stamp in stamps:
00665 x = self.map_stamp_to_x(stamp, False)
00666
00667 label = self._get_label(division, stamp - start_stamp)
00668 label_x = x + self._major_divisions_label_indent
00669 if label_x + self._qfont_width(label) < self.scene().width():
00670 painter.setBrush(self._default_brush)
00671 painter.setPen(self._default_pen)
00672 painter.setFont(self._time_font)
00673 painter.drawText(label_x, label_y, label)
00674
00675 painter.setPen(self._major_division_pen)
00676 painter.drawLine(
00677 x, label_y - self._time_tick_height - self._time_font_size, x, self._history_bottom)
00678
00679 painter.setBrush(self._default_brush)
00680 painter.setPen(self._default_pen)
00681
00682 def _draw_minor_divisions(self, painter, stamps, start_stamp, division):
00683 """
00684 Draw grey hashed vertical grid-lines showing minor time divisions.
00685 :param painter: allows access to paint functions,''QPainter''
00686 """
00687 xs = [self.map_stamp_to_x(stamp) for stamp in stamps]
00688 painter.setPen(self._minor_division_pen)
00689 for x in xs:
00690 painter.drawLine(x, self._history_top, x, self._history_bottom)
00691
00692 painter.setPen(self._minor_division_tick_pen)
00693 for x in xs:
00694 painter.drawLine(x, self._history_top - self._time_tick_height, x, self._history_top)
00695
00696 painter.setBrush(self._default_brush)
00697 painter.setPen(self._default_pen)
00698
00699
00700
00701 def handle_close(self):
00702 for renderer in self._timeline_renderers.values():
00703 renderer.close()
00704 self._index_cache_thread.stop()
00705
00706
00707
00708 def get_viewer_types(self, datatype):
00709 return [RawView] + self._viewer_types.get('*', []) + self._viewer_types.get(datatype, [])
00710
00711 def load_plugins(self):
00712 from rqt_gui.rospkg_plugin_provider import RospkgPluginProvider
00713 self.plugin_provider = RospkgPluginProvider('rqt_bag', 'rqt_bag::Plugin')
00714
00715 plugin_descriptors = self.plugin_provider.discover(None)
00716 for plugin_descriptor in plugin_descriptors:
00717 try:
00718 plugin = self.plugin_provider.load(
00719 plugin_descriptor.plugin_id(), plugin_context=None)
00720 except Exception as e:
00721 qWarning('rqt_bag.TimelineFrame.load_plugins() failed to load plugin "%s":\n%s' %
00722 (plugin_descriptor.plugin_id(), e))
00723 continue
00724 try:
00725 view = plugin.get_view_class()
00726 except Exception as e:
00727 qWarning(
00728 'rqt_bag.TimelineFrame.load_plugins() failed to get view '
00729 'from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
00730 continue
00731
00732 timeline_renderer = None
00733 try:
00734 timeline_renderer = plugin.get_renderer_class()
00735 except AttributeError:
00736 pass
00737 except Exception as e:
00738 qWarning(
00739 'rqt_bag.TimelineFrame.load_plugins() failed to get renderer '
00740 'from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
00741
00742 msg_types = []
00743 try:
00744 msg_types = plugin.get_message_types()
00745 except AttributeError:
00746 pass
00747 except Exception as e:
00748 qWarning(
00749 'rqt_bag.TimelineFrame.load_plugins() failed to get message types '
00750 'from plugin "%s":\n%s' % (plugin_descriptor.plugin_id(), e))
00751 finally:
00752 if not msg_types:
00753 qWarning(
00754 'rqt_bag.TimelineFrame.load_plugins() plugin "%s" declares '
00755 'no message types.' % (plugin_descriptor.plugin_id()))
00756
00757 for msg_type in msg_types:
00758 self._viewer_types.setdefault(msg_type, []).append(view)
00759 if timeline_renderer:
00760 self._timeline_renderers[msg_type] = timeline_renderer(self)
00761
00762 qDebug('rqt_bag.TimelineFrame.load_plugins() loaded plugin "%s"' %
00763 plugin_descriptor.plugin_id())
00764
00765
00766
00767 def get_renderers(self):
00768 """
00769 :returns: a list of the currently loaded renderers for the plugins
00770 """
00771 renderers = []
00772
00773 for topic in self.topics:
00774 datatype = self.scene().get_datatype(topic)
00775 renderer = self._timeline_renderers.get(datatype)
00776 if renderer is not None:
00777 renderers.append((topic, renderer))
00778 return renderers
00779
00780 def is_renderer_active(self, topic):
00781 return topic in self._rendered_topics
00782
00783 def toggle_renderers(self):
00784 idle_renderers = len(self._rendered_topics) < len(self.topics)
00785
00786 self.set_renderers_active(idle_renderers)
00787
00788 def set_renderers_active(self, active):
00789 if active:
00790 for topic in self.topics:
00791 self._rendered_topics.add(topic)
00792 else:
00793 self._rendered_topics.clear()
00794 self.scene().update()
00795
00796 def set_renderer_active(self, topic, active):
00797 if active:
00798 if topic in self._rendered_topics:
00799 return
00800 self._rendered_topics.add(topic)
00801 else:
00802 if not topic in self._rendered_topics:
00803 return
00804 self._rendered_topics.remove(topic)
00805 self.scene().update()
00806
00807
00808
00809 def _update_index_cache(self, topic):
00810 """
00811 Updates the cache of message timestamps for the given topic.
00812 :return: number of messages added to the index cache
00813 """
00814 if self._start_stamp is None or self._end_stamp is None:
00815 return 0
00816
00817 if topic not in self.index_cache:
00818
00819 start_time = self._start_stamp
00820 topic_cache = []
00821 self.index_cache[topic] = topic_cache
00822 else:
00823 topic_cache = self.index_cache[topic]
00824
00825
00826 if topic not in self.invalidated_caches:
00827 return 0
00828
00829 if len(topic_cache) == 0:
00830 start_time = self._start_stamp
00831 else:
00832 start_time = rospy.Time.from_sec(max(0.0, topic_cache[-1]))
00833
00834 end_time = self._end_stamp
00835
00836 topic_cache_len = len(topic_cache)
00837
00838 for entry in self.scene().get_entries(topic, start_time, end_time):
00839 topic_cache.append(entry.time.to_sec())
00840
00841 if topic in self.invalidated_caches:
00842 self.invalidated_caches.remove(topic)
00843
00844 return len(topic_cache) - topic_cache_len
00845
00846 def _find_regions(self, stamps, max_interval):
00847 """
00848 Group timestamps into regions connected by timestamps less than max_interval secs apart
00849 :param start_stamp: a list of stamps, ''list''
00850 :param stamp_step: seconds between each division, ''int''
00851 """
00852 region_start, prev_stamp = None, None
00853 for stamp in stamps:
00854 if prev_stamp:
00855 if stamp - prev_stamp > max_interval:
00856 region_end = prev_stamp
00857 yield (region_start, region_end)
00858 region_start = stamp
00859 else:
00860 region_start = stamp
00861
00862 prev_stamp = stamp
00863
00864 if region_start and prev_stamp:
00865 yield (region_start, prev_stamp)
00866
00867 def _get_stamps(self, start_stamp, stamp_step):
00868 """
00869 Generate visible stamps every stamp_step
00870 :param start_stamp: beginning of timeline stamp, ''int''
00871 :param stamp_step: seconds between each division, ''int''
00872 """
00873 if start_stamp >= self._stamp_left:
00874 stamp = start_stamp
00875 else:
00876 stamp = start_stamp + \
00877 int((self._stamp_left - start_stamp) / stamp_step) * stamp_step + stamp_step
00878
00879 while stamp < self._stamp_right:
00880 yield stamp
00881 stamp += stamp_step
00882
00883 def _get_label(self, division, elapsed):
00884 """
00885 :param division: number of seconds in a division, ''int''
00886 :param elapsed: seconds from the beginning, ''int''
00887 :returns: relevent time elapsed string, ''str''
00888 """
00889 secs = int(elapsed) % 60
00890
00891 mins = int(elapsed) / 60
00892 hrs = mins / 60
00893 days = hrs / 24
00894 weeks = days / 7
00895
00896 if division >= 7 * 24 * 60 * 60:
00897 return '%dw' % weeks
00898 elif division >= 24 * 60 * 60:
00899 return '%dd' % days
00900 elif division >= 60 * 60:
00901 return '%dh' % hrs
00902 elif division >= 5 * 60:
00903 return '%dm' % mins
00904 elif division >= 1:
00905 return '%dm%02ds' % (mins, secs)
00906 elif division >= 0.1:
00907 return '%d.%ss' % (secs, str(int(10.0 * (elapsed - int(elapsed)))))
00908 elif division >= 0.01:
00909 return '%d.%02ds' % (secs, int(100.0 * (elapsed - int(elapsed))))
00910 else:
00911 return '%d.%03ds' % (secs, int(1000.0 * (elapsed - int(elapsed))))
00912
00913
00914 def map_x_to_stamp(self, x, clamp_to_visible=True):
00915 """
00916 converts a pixel x value to a stamp
00917 :param x: pixel value to be converted, ''int''
00918 :param clamp_to_visible:
00919 disallow values that are greater than the current timeline bounds,''bool''
00920 :returns: timestamp, ''int''
00921 """
00922 fraction = float(x - self._history_left) / self._history_width
00923
00924 if clamp_to_visible:
00925 if fraction <= 0.0:
00926 return self._stamp_left
00927 elif fraction >= 1.0:
00928 return self._stamp_right
00929
00930 return self._stamp_left + fraction * (self._stamp_right - self._stamp_left)
00931
00932 def map_dx_to_dstamp(self, dx):
00933 """
00934 converts a distance in pixel space to a distance in stamp space
00935 :param dx: distance in pixel space to be converted, ''int''
00936 :returns: distance in stamp space, ''float''
00937 """
00938 return float(dx) * (self._stamp_right - self._stamp_left) / self._history_width
00939
00940 def map_stamp_to_x(self, stamp, clamp_to_visible=True):
00941 """
00942 converts a timestamp to the x value where that stamp exists in the timeline
00943 :param stamp: timestamp to be converted, ''int''
00944 :param clamp_to_visible:
00945 disallow values that are greater than the current timeline bounds,''bool''
00946 :returns: # of pixels from the left boarder, ''int''
00947 """
00948 if self._stamp_left is None:
00949 return None
00950 fraction = (stamp - self._stamp_left) / (self._stamp_right - self._stamp_left)
00951
00952 if clamp_to_visible:
00953 fraction = min(1.0, max(0.0, fraction))
00954
00955 return self._history_left + fraction * self._history_width
00956
00957 def map_dstamp_to_dx(self, dstamp):
00958 return (float(dstamp) * self._history_width) / (self._stamp_right - self._stamp_left)
00959
00960 def map_y_to_topic(self, y):
00961 for topic in self._history_bounds:
00962 x, topic_y, w, topic_h = self._history_bounds[topic]
00963 if y > topic_y and y <= topic_y + topic_h:
00964 return topic
00965 return None
00966
00967
00968 def reset_timeline(self):
00969 self.reset_zoom()
00970
00971 self._selected_left = None
00972 self._selected_right = None
00973 self._selecting_mode = _SelectionMode.NONE
00974
00975 self.emit_play_region()
00976
00977 if self._stamp_left is not None:
00978 self.playhead = rospy.Time.from_sec(self._stamp_left)
00979
00980 def set_timeline_view(self, stamp_left, stamp_right):
00981 self._stamp_left = stamp_left
00982 self._stamp_right = stamp_right
00983
00984 def translate_timeline(self, dstamp):
00985 self.set_timeline_view(self._stamp_left + dstamp, self._stamp_right + dstamp)
00986 self.scene().update()
00987
00988 def translate_timeline_left(self):
00989 self.translate_timeline((self._stamp_right - self._stamp_left) * -0.05)
00990
00991 def translate_timeline_right(self):
00992 self.translate_timeline((self._stamp_right - self._stamp_left) * 0.05)
00993
00994
00995 def reset_zoom(self):
00996 start_stamp, end_stamp = self._start_stamp, self._end_stamp
00997 if start_stamp is None:
00998 return
00999
01000 if (end_stamp - start_stamp) < rospy.Duration.from_sec(5.0):
01001 end_stamp = start_stamp + rospy.Duration.from_sec(5.0)
01002
01003 self.set_timeline_view(start_stamp.to_sec(), end_stamp.to_sec())
01004 self.scene().update()
01005
01006 def zoom_in(self):
01007 self.zoom_timeline(0.5)
01008
01009 def zoom_out(self):
01010 self.zoom_timeline(2.0)
01011
01012 def can_zoom_in(self):
01013 return self.can_zoom(0.5)
01014
01015 def can_zoom_out(self):
01016 return self.can_zoom(2.0)
01017
01018 def can_zoom(self, desired_zoom):
01019 if not self._stamp_left or not self.playhead:
01020 return False
01021
01022 new_interval = self.get_zoom_interval(desired_zoom)
01023 if not new_interval:
01024 return False
01025
01026 new_range = new_interval[1] - new_interval[0]
01027 curr_range = self._stamp_right - self._stamp_left
01028 actual_zoom = new_range / curr_range
01029
01030 if desired_zoom < 1.0:
01031 return actual_zoom < 0.95
01032 else:
01033 return actual_zoom > 1.05
01034
01035 def zoom_timeline(self, zoom, center=None):
01036 interval = self.get_zoom_interval(zoom, center)
01037 if not interval:
01038 return
01039
01040 self._stamp_left, self._stamp_right = interval
01041
01042 self.scene().update()
01043
01044 def get_zoom_interval(self, zoom, center=None):
01045 """
01046 @rtype: tuple
01047 @requires: left & right zoom interval sizes.
01048 """
01049 if self._stamp_left is None:
01050 return None
01051
01052 stamp_interval = self._stamp_right - self._stamp_left
01053 if center is None:
01054 center = self.playhead.to_sec()
01055 center_frac = (center - self._stamp_left) / stamp_interval
01056
01057 new_stamp_interval = zoom * stamp_interval
01058 if new_stamp_interval == 0:
01059 return None
01060
01061 px_per_sec = self._history_width / new_stamp_interval
01062 if px_per_sec < self._min_zoom:
01063 new_stamp_interval = self._history_width / self._min_zoom
01064 elif px_per_sec > self._max_zoom:
01065 new_stamp_interval = self._history_width / self._max_zoom
01066
01067 left = center - center_frac * new_stamp_interval
01068 right = left + new_stamp_interval
01069
01070 return (left, right)
01071
01072 def pause(self):
01073 self._paused = True
01074
01075 def resume(self):
01076 self._paused = False
01077 self._bag_timeline.resume()
01078
01079
01080 def on_middle_down(self, event):
01081 self._clicked_pos = self._dragged_pos = event.pos()
01082 self.pause()
01083
01084 def on_left_down(self, event):
01085 if self.playhead == None:
01086 return
01087
01088 self._clicked_pos = self._dragged_pos = event.pos()
01089
01090 self.pause()
01091
01092 if event.modifiers() == Qt.ShiftModifier:
01093 return
01094
01095 x = self._clicked_pos.x()
01096 y = self._clicked_pos.y()
01097 if x >= self._history_left and x <= self._history_right:
01098 if y >= self._history_top and y <= self._history_bottom:
01099
01100 playhead_secs = self.map_x_to_stamp(x)
01101 if playhead_secs <= 0.0:
01102 self.playhead = rospy.Time(0, 1)
01103 else:
01104 self.playhead = rospy.Time.from_sec(playhead_secs)
01105 self.scene().update()
01106
01107 elif y <= self._history_top:
01108
01109 if self._selecting_mode == _SelectionMode.NONE:
01110 self._selected_left = None
01111 self._selected_right = None
01112 self._selecting_mode = _SelectionMode.LEFT_MARKED
01113 self.scene().update()
01114 self.emit_play_region()
01115
01116 elif self._selecting_mode == _SelectionMode.MARKED:
01117 left_x = self.map_stamp_to_x(self._selected_left)
01118 right_x = self.map_stamp_to_x(self._selected_right)
01119 if x < left_x - self._selection_handle_width or \
01120 x > right_x + self._selection_handle_width:
01121 self._selected_left = None
01122 self._selected_right = None
01123 self._selecting_mode = _SelectionMode.LEFT_MARKED
01124 self.scene().update()
01125 self.emit_play_region()
01126 elif self._selecting_mode == _SelectionMode.SHIFTING:
01127 self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
01128
01129 def on_mouse_up(self, event):
01130 self.resume()
01131
01132 if self._selecting_mode in [
01133 _SelectionMode.LEFT_MARKED,
01134 _SelectionMode.MOVE_LEFT,
01135 _SelectionMode.MOVE_RIGHT,
01136 _SelectionMode.SHIFTING]:
01137 if self._selected_left is None:
01138 self._selecting_mode = _SelectionMode.NONE
01139 else:
01140 self._selecting_mode = _SelectionMode.MARKED
01141 self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
01142 self.scene().update()
01143
01144 def on_mousewheel(self, event):
01145 try:
01146 delta = event.angleDelta().y()
01147 except AttributeError:
01148 delta = event.delta()
01149 dz = delta / 120.0
01150 self.zoom_timeline(1.0 - dz * 0.2)
01151
01152 def on_mouse_move(self, event):
01153 if not self._history_left:
01154 return
01155
01156 x = event.pos().x()
01157 y = event.pos().y()
01158
01159 if event.buttons() == Qt.NoButton:
01160
01161 if self._selecting_mode in [
01162 _SelectionMode.MARKED,
01163 _SelectionMode.MOVE_LEFT,
01164 _SelectionMode.MOVE_RIGHT,
01165 _SelectionMode.SHIFTING]:
01166 if y <= self._history_top and self._selected_left is not None:
01167 left_x = self.map_stamp_to_x(self._selected_left)
01168 right_x = self.map_stamp_to_x(self._selected_right)
01169
01170 if abs(x - left_x) <= self._selection_handle_width:
01171 self._selecting_mode = _SelectionMode.MOVE_LEFT
01172 self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
01173 return
01174 elif abs(x - right_x) <= self._selection_handle_width:
01175 self._selecting_mode = _SelectionMode.MOVE_RIGHT
01176 self.scene().views()[0].setCursor(QCursor(Qt.SizeHorCursor))
01177 return
01178 elif x > left_x and x < right_x:
01179 self._selecting_mode = _SelectionMode.SHIFTING
01180 self.scene().views()[0].setCursor(QCursor(Qt.OpenHandCursor))
01181 return
01182 else:
01183 self._selecting_mode = _SelectionMode.MARKED
01184 self.scene().views()[0].setCursor(QCursor(Qt.ArrowCursor))
01185 else:
01186
01187 if event.buttons() == Qt.MidButton or event.modifiers() == Qt.ShiftModifier:
01188
01189 dx_drag, dy_drag = x - self._dragged_pos.x(), y - self._dragged_pos.y()
01190
01191 if dx_drag != 0:
01192 self.translate_timeline(-self.map_dx_to_dstamp(dx_drag))
01193 if (dx_drag == 0 and abs(dy_drag) > 0) or \
01194 (dx_drag != 0 and abs(float(dy_drag) / dx_drag) > 0.2 and abs(dy_drag) > 1):
01195 zoom = min(
01196 self._max_zoom_speed,
01197 max(self._min_zoom_speed, 1.0 + self._zoom_sensitivity * dy_drag))
01198 self.zoom_timeline(zoom, self.map_x_to_stamp(x))
01199
01200 self.scene().views()[0].setCursor(QCursor(Qt.ClosedHandCursor))
01201 elif event.buttons() == Qt.LeftButton:
01202
01203 clicked_x = self._clicked_pos.x()
01204 clicked_y = self._clicked_pos.y()
01205
01206 x_stamp = self.map_x_to_stamp(x)
01207
01208 if y <= self._history_top:
01209 if self._selecting_mode == _SelectionMode.LEFT_MARKED:
01210
01211 clicked_x_stamp = self.map_x_to_stamp(clicked_x)
01212
01213 self._selected_left = min(clicked_x_stamp, x_stamp)
01214 self._selected_right = max(clicked_x_stamp, x_stamp)
01215 self.scene().update()
01216
01217 elif self._selecting_mode == _SelectionMode.MOVE_LEFT:
01218 self._selected_left = x_stamp
01219 self.scene().update()
01220
01221 elif self._selecting_mode == _SelectionMode.MOVE_RIGHT:
01222 self._selected_right = x_stamp
01223 self.scene().update()
01224
01225 elif self._selecting_mode == _SelectionMode.SHIFTING:
01226 dx_drag = x - self._dragged_pos.x()
01227 dstamp = self.map_dx_to_dstamp(dx_drag)
01228
01229 self._selected_left = max(
01230 self._start_stamp.to_sec(),
01231 min(self._end_stamp.to_sec(), self._selected_left + dstamp))
01232 self._selected_right = max(
01233 self._start_stamp.to_sec(),
01234 min(self._end_stamp.to_sec(), self._selected_right + dstamp))
01235 self.scene().update()
01236 self.emit_play_region()
01237
01238 elif clicked_x >= self._history_left and \
01239 clicked_x <= self._history_right and \
01240 clicked_y >= self._history_top and clicked_y <= self._history_bottom:
01241
01242 if x_stamp <= 0.0:
01243 self.playhead = rospy.Time(0, 1)
01244 else:
01245 self.playhead = rospy.Time.from_sec(x_stamp)
01246 self.scene().update()
01247 self._dragged_pos = event.pos()