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
00035 import rospy
00036
00037 from python_qt_binding.QtCore import QPointF, Signal
00038 from python_qt_binding.QtGui import (QColor, QGraphicsPixmapItem,
00039 QGraphicsView, QIcon)
00040
00041
00042 class TimelineView(QGraphicsView):
00043 """
00044 When you instantiate this class, do NOT forget to call set_init_data to
00045 set necessary data.
00046 """
00047
00048 _sig_update = Signal()
00049
00050 def __init__(self, parent):
00051 """Cannot take args other than parent due to loadUi limitation."""
00052
00053 super(TimelineView, self).__init__()
00054 self._parent = parent
00055 self._timeline_marker = QIcon.fromTheme('system-search')
00056
00057 self._min_num_seconds = 0
00058 self._max_num_seconds = 0
00059 self._xpos_marker = 0
00060
00061 self._timeline_marker_width = 15
00062 self._timeline_marker_height = 15
00063
00064 self._sig_update.connect(self.slot_redraw)
00065 self._color_callback = None
00066
00067 self.setUpdatesEnabled(True)
00068
00069 def set_init_data(self, min_xpos_marker, max_num_seconds,
00070 xpos_marker, color_callback):
00071 """
00072 This function needs to be called right after the class is instantiated,
00073 in order to pass necessary values. _color_callback
00074
00075 This function is to compensate the functional limitation of
00076 python_qt_binding.loadUi that doesn't allow you to pass arguments in
00077 the custom classes you use in .ui.
00078 """
00079 self._min_num_seconds = min_xpos_marker
00080 self._max_num_seconds = max_num_seconds
00081 self._xpos_marker = xpos_marker
00082 self._color_callback = color_callback
00083
00084
00085
00086
00087
00088
00089
00090
00091
00092 def set_range(self, min_val, max_val):
00093 """
00094 :param min_val: Smallest second on timeline.
00095 :param max_val: Largest second on timeline.
00096 """
00097 self._min_num_seconds = min_val
00098 self._max_num_seconds = max_val
00099 rospy.logdebug(' TimelineView set_range _min_num_seconds=%s max=%s',
00100 self._min_num_seconds,
00101 self._max_num_seconds)
00102 self.set_xpos_marker(max_val)
00103
00104 def set_xpos_marker(self, len_queue):
00105 """
00106 Compare the given length with the current min & max possible pos on
00107 timeline and sets the minimum/largest possible value.
00108
00109 :type len_queue: int
00110 """
00111
00112 self._xpos_marker = self._clamp(int(len_queue),
00113 self._min_num_seconds,
00114 self._max_num_seconds)
00115 rospy.logdebug('TLView set_xpos_marker len_queue=%s xpos_marker=%s',
00116 len_queue, self._xpos_marker)
00117
00118 def get_xpos_marker(self):
00119 return self._xpos_marker
00120
00121 def mouseReleaseEvent(self, event):
00122 """
00123 :type event: QMouseEvent
00124 """
00125
00126 self._parent.mouse_release(event)
00127 self.set_val_from_x(event.pos().x())
00128
00129
00130
00131
00132
00133
00134 def mousePressEvent(self, evt):
00135 """
00136 :type event: QMouseEvent
00137 """
00138 self.set_val_from_x(evt.pos().x())
00139
00140
00141
00142
00143
00144
00145 self._parent.on_slider_scroll(evt)
00146
00147 def set_val_from_x(self, x):
00148 """
00149 Called when marker is moved by user.
00150
00151 :param x: Position relative to self widget.
00152 """
00153 qsize = self.size()
00154 width = qsize.width()
00155
00156 length_tl_in_second = self._max_num_seconds + 1 - self._min_num_seconds
00157 width_cell = width / float(length_tl_in_second)
00158 x_marker_float = x / width_cell + 1
00159 self.set_marker_pos(x_marker_float)
00160 rospy.logdebug('TimelineView set_val_from_x x=%s width_cell=%s ' +
00161 'length_tl_in_second=%s set_marker_pos=%s',
00162 x, width_cell, length_tl_in_second, self._xpos_marker)
00163
00164 def set_marker_pos(self, val):
00165 self._xpos_marker = self._clamp(int(val),
00166 self._min_num_seconds,
00167 self._max_num_seconds)
00168
00169 self._sig_update.emit()
00170
00171 def _clamp(self, val, min, max):
00172 """
00173 Judge if val is within the range given by min & max.
00174 If not, return either min or max.
00175
00176 :type val: any number format
00177 :type min: any number format
00178 :type max: any number format
00179 :rtype: int
00180 """
00181 rospy.logdebug(' TimelineView _clamp val=%s min=%s max=%s',
00182 val, min, max)
00183 if (val < min):
00184 return min
00185 if (val > max):
00186 return max
00187 return val
00188
00189 def slot_redraw(self):
00190 """
00191 Gets called either when new msg comes in or when marker is moved by
00192 user.
00193 """
00194
00195 self._parent._scene.clear()
00196
00197 qsize = self.size()
00198 width_tl = qsize.width()
00199
00200 length_tl = ((self._max_num_seconds + 1) -
00201 self._min_num_seconds)
00202
00203 len_queue = length_tl
00204 w = width_tl / float(len_queue)
00205 is_enabled = self.isEnabled()
00206
00207 for i, m in enumerate(self._parent.get_diagnostic_queue()):
00208 h = self.viewport().height()
00209
00210
00211 qcolor = None
00212 color_index = i + self._min_num_seconds
00213 if (is_enabled):
00214 qcolor = self._color_callback(
00215 self._parent.get_diagnostic_queue(),
00216 color_index)
00217 else:
00218 qcolor = QColor('grey')
00219
00220
00221
00222
00223
00224
00225 self._parent._scene.addRect(w * i, 0, w, h,
00226 QColor('white'), qcolor)
00227 rospy.logdebug('slot_redraw #%d th loop w=%s width_tl=%s',
00228 i, w, width_tl)
00229
00230
00231 xpos_marker = ((self._xpos_marker - 1) * w +
00232 (w / 2.0) - (self._timeline_marker_width / 2.0))
00233 pos_marker = QPointF(xpos_marker, 0)
00234
00235
00236
00237 timeline_marker = self._instantiate_tl_icon()
00238 timeline_marker.setPos(pos_marker)
00239 self._parent._scene.addItem(timeline_marker)
00240 rospy.logdebug(' slot_redraw xpos_marker(int)=%s length_tl=%s',
00241 int(xpos_marker), length_tl)
00242
00243 def _instantiate_tl_icon(self):
00244 timeline_marker_icon = QIcon.fromTheme('system-search')
00245 timeline_marker_icon_pixmap = timeline_marker_icon.pixmap(
00246 self._timeline_marker_width,
00247 self._timeline_marker_height)
00248 return QGraphicsPixmapItem(timeline_marker_icon_pixmap)