timeline.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2012, Willow Garage, Inc.
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions
00008 # are met:
00009 #
00010 #  * Redistributions of source code must retain the above copyright
00011 #    notice, this list of conditions and the following disclaimer.
00012 #  * Redistributions in binary form must reproduce the above
00013 #    copyright notice, this list of conditions and the following
00014 #    disclaimer in the documentation and/or other materials provided
00015 #    with the distribution.
00016 #  * Neither the name of Willow Garage, Inc. nor the names of its
00017 #    contributors may be used to endorse or promote products derived
00018 #    from this software without specific prior written permission.
00019 #
00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 # POSSIBILITY OF SUCH DAMAGE.
00032 #
00033 # Author: Isaac Saito, Ze'ev Klapow
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)  # In a trial to enable update()
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     # !!! BEGIN DO NOT DELETE. !!!
00085     # def paintEvent(self, event):
00086     ## Enabling this will collide with QGraphicsScene and ends up
00087     ## with QGraphicsScene not being updated.
00088         # rospy.logdebug('test')
00089         # self.parent.slot_redraw()
00090     # !!! END DO NOT DELETE. !!!
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         # TODO Figure out what's done by this in wx.
00130         # wx.PostEvent(self.GetEventHandler(),
00131         #             wx.PyCommandEvent(wx.EVT_COMMAND_SCROLL_CHANGED.typeId,
00132         #                               self.GetId()))
00133 
00134     def mousePressEvent(self, evt):
00135         """
00136         :type event: QMouseEvent
00137         """
00138         self.set_val_from_x(evt.pos().x())
00139 
00140         # TODO Figure out what's done by this in wx.
00141         # wx.PostEvent(self.GetEventHandler(),
00142         #             wx.PyCommandEvent(wx.EVT_COMMAND_SCROLL_THUMBTRACK.typeId
00143         #                               self.GetId()))
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         # determine value from mouse click
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         #self.repaint()  # # This might result in segfault.
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             # Figure out each cell's color.
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 #  TODO Use this code for adding gradation to the cell color.
00221 #            end_color = QColor(0.5 * QColor('red').value(),
00222 #                               0.5 * QColor('green').value(),
00223 #                               0.5 * QColor('blue').value())
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         # Setting marker.
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         # Need to instantiate marker everytime since it gets deleted
00236         # in every loop by scene.clear()
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)


rqt_robot_monitor
Author(s): Isaac Saito, Ze'ev Klapow, Kevin Watts, Josh Faust
autogenerated on Mon Oct 6 2014 07:16:09