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 roslib;roslib.load_manifest('rqt_robot_monitor')
00036 import rospy
00037 
00038 from python_qt_binding import loadUi
00039 from python_qt_binding.QtCore import QPointF, Qt, QRect, QSize, Signal
00040 from python_qt_binding.QtGui import QBrush, QColor, QGraphicsPixmapItem, QGraphicsView, QIcon, QPainter, QPen, QWidget
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     #_sig_on_marker = Signal()
00050     
00051     def __init__(self, parent):
00052         """Cannot take args other than parent due to loadUi limitation."""
00053         
00054         super(TimelineView, self).__init__()
00055         self._parent = parent
00056         self._timeline_marker = QIcon.fromTheme('system-search')
00057         
00058         self._min_num_seconds = 0
00059         self._max_num_seconds = 0
00060         self._xpos_marker = 0
00061         self._color_callback = None
00062         
00063         self._timeline_marker_width = 15
00064         self._timeline_marker_height = 15
00065         
00066         self._sig_update.connect(self.slot_redraw)
00067         # self._color_callback = parent._color_callback
00068         #self._sig_on_marker.connect(parent.on_slider_scroll)
00069         
00070         self.setUpdatesEnabled(True) #In a trial to enable update()
00071 
00072     def set_init_data(self, min_xpos_marker, max_num_seconds, 
00073                        xpos_marker, color_callback):
00074         """
00075         This function needs to be called right after the class is instantiated,
00076         in order to pass necessary values. _color_callback
00077         
00078         This function is to compensate the functional limitation of 
00079         python_qt_binding.loadUi that doesn't allow you to pass arguments in 
00080         the custom classes you use in .ui.
00081         
00082         
00083         @author: Isaac Saito 
00084         """
00085         self._min_num_seconds = min_xpos_marker
00086         self._max_num_seconds = max_num_seconds
00087         self._xpos_marker = xpos_marker
00088         self._color_callback = color_callback
00089 
00090     #def paintEvent(self, event): 
00091     ## Enabling this will collide with QGraphicsScene and ends up 
00092     ## with QGraphicsScene not being updated.
00093         # rospy.logdebug('test')
00094         # self.parent.slot_redraw()
00095         
00096     def redraw(self, event):
00097         """
00098         
00099         Draw timeline's "cells" (ie. boxes that represent seconds). 
00100                 
00101         Taken from robot_monitor.message_timeline.on_paint
00102         
00103         @deprecated: This way (using QPainter) didn't work as intended.
00104         """       
00105         
00106         #super(TimelineView, self).paintEvent(event) 
00107 
00108 
00109         # painter = QPainter(self) 
00110         ## This yields warning that says:
00111         ## "QPainter::begin: Widget painting can only begin as a result of a paintEvent"
00112 
00113         painter = QPainter()
00114         painter.begin(self.viewport())
00115         pen = QPen(Qt.black, 2)#, Qt.SolidLine, Qt.RoundCap, Qt.RoundJoin)  # Needs modified.
00116         painter.setPen(pen)
00117                 
00118         is_enabled = self.isEnabled()
00119 
00120         #(width_tl, height_tl) = self.size()
00121         qsize = self.size()
00122         width_tl = qsize.width()
00123         height_tl = qsize.height()
00124         
00125         length_tl = self._max_num_seconds + 1 - self._min_num_seconds
00126         rospy.logdebug('paintEvent is_enabled=%s length_tl=%d', 
00127                       is_enabled, length_tl)
00128         value_size = width_tl / float(length_tl)
00129         for i in xrange(0, length_tl):
00130             brush = None
00131             color_index = i + self._min_num_seconds
00132             if (is_enabled):
00133                 qcolor = self._color_callback(color_index)                
00134             else:
00135                 qcolor = QColor('grey')                
00136             end_color = QColor(0.5 * QColor('red').value(),
00137                                0.5 * QColor('green').value(),
00138                                0.5 * QColor('blue').value())
00139             #painter.setBrush(qcolor)
00140             painter.setBrush(QBrush(qcolor))
00141             start = i * value_size
00142             end = (i + 1) * value_size
00143             rect = QRect(start, 0, end, height_tl)
00144             
00145             # dc.GradientFillLinear(wx.Rect(start, 0, end, height_tl),
00146             #                       qcolor, end_color, wx.SOUTH)
00147             rospy.logdebug('paintEvent i=%d start=%s end=%s height_tl=%s',
00148                           i, start, end, height_tl)
00149             #painter.fillRect(QRect(start, end, 100, height_tl), qcolor)
00150             painter.fillRect(rect, qcolor)
00151             
00152             if (i > 0):
00153                 # dc.SetPen(wx.BLACK_PEN)
00154                 pen.setColor(Qt.black)
00155                 # dc.DrawLine(start, 0, start, height_tl)
00156                 painter.drawLine(start, 0, start, height_tl)
00157                
00158         size_marker = QSize(20, 20)
00159         marker_x = ((self._xpos_marker - 1) * value_size + 
00160                     (value_size / 2.0) - 
00161                     (self._timeline_marker.actualSize(size_marker).width() 
00162                      / 2.0))
00163         
00164         # dc.DrawBitmap(self._timeline_marker, marker_x, 0, True)
00165         qrect = QRect(marker_x, 0, size_marker.width(), size_marker.height())
00166         self._timeline_marker.paint(painter, qrect)
00167         rospy.logdebug(' paintEvent marker_x=%s', marker_x)           
00168         
00169         painter.end()
00170 
00171 #    def resizeEvent(self, event):
00172 #        self.adjustSize()  # TODO Make sure this meets my requirement.
00173 
00174     def set_range(self, min_val, max_val):
00175         """
00176         
00177         Copied from robot_monitor
00178         
00179         @param min_val: Smallest second on timeline. 
00180         @param max_val: Largest second on timeline.         
00181         """
00182         self._min_num_seconds = min_val
00183         self._max_num_seconds = max_val
00184         rospy.logdebug(' TimelineView set_range _min_num_seconds=%s max=%s',
00185                        self._min_num_seconds,
00186                        self._max_num_seconds)
00187 #        self._xpos_marker = self._clamp(self._xpos_marker, self._min_num_seconds, 
00188 #                                       self._max_num_seconds)
00189 #        #self.Refresh()
00190 #        #self.repaint() #Emits warning "QPixmap: It is not safe to use pixmaps 
00191 #                        #outside the GUI thread"
00192 #        self._sig_update.emit()
00193         
00194         #self.set_xpos_marker(self._xpos_marker)
00195         self.set_xpos_marker(max_val)
00196 
00197     def set_xpos_marker(self, len_queue):
00198         """Copied from robot_monitor"""
00199 
00200         self._xpos_marker = self._clamp(int(len_queue),
00201                                        self._min_num_seconds, 
00202                                        self._max_num_seconds)
00203         rospy.logdebug(' TimelineView set_xpos_marker len_queue=%s _xpos_marker=%s', 
00204                       len_queue, self._xpos_marker)
00205         #self._sig_update.emit()
00206         
00207     def get_xpos_marker(self):
00208         return self._xpos_marker        
00209                 
00210     def mouseReleaseEvent(self, event):
00211         '''
00212         Override.
00213         @param event: QMouseEvent
00214         '''
00215 
00216         self._parent.mouse_release(event)
00217         self.set_val_from_x(event.pos().x())
00218         
00219         # TODO Figure out what's done by this in wx.
00220         # wx.PostEvent(self.GetEventHandler(),
00221         #             wx.PyCommandEvent(wx.EVT_COMMAND_SCROLL_CHANGED.typeId,
00222         #                               self.GetId()))
00223 
00224     '''
00225     Override.
00226     @param event: QMouseEvent 
00227     '''        
00228     def mousePressEvent(self, evt):
00229         self.set_val_from_x(evt.pos().x())
00230                 
00231         # TODO Figure out what's done by this in wx.
00232         # wx.PostEvent(self.GetEventHandler(),
00233         #             wx.PyCommandEvent(wx.EVT_COMMAND_SCROLL_THUMBTRACK.typeId,
00234         #                               self.GetId()))
00235         #self._sig_on_marker.emit()
00236         self._parent.on_slider_scroll(evt)
00237         
00238     def set_val_from_x(self, x):
00239         '''
00240         Called when marker is moved by user.
00241         
00242         @param x: Position relative to self widget.
00243           
00244         Copied from robot_monitor.
00245         '''
00246         qsize = self.size()
00247         width = qsize.width()
00248         height = qsize.height()
00249         # determine value from mouse click
00250         length_tl_in_second = self._max_num_seconds + 1 - self._min_num_seconds
00251         width_cell = width / float(length_tl_in_second)
00252         x_marker_float = x / width_cell + 1
00253         self.set_marker_pos(x_marker_float)
00254         rospy.logdebug('TimelineView set_val_from_x x=%s width_cell=%s ' +
00255                       'length_tl_in_second=%s set_marker_pos=%s', 
00256                       x, width_cell, length_tl_in_second, self._xpos_marker)
00257 
00258     def set_marker_pos(self, val):
00259         '''
00260         Copied from robot_monitor. Originally called SetValue.
00261         '''
00262         self._xpos_marker = self._clamp(int(val),
00263                                        self._min_num_seconds,
00264                                        self._max_num_seconds)
00265         #self.repaint()  # # This might result in segfault.
00266         self._sig_update.emit()  
00267                                   
00268            
00269     def _clamp(self, val, min, max):
00270         """
00271         Judge if val is within the range given by min & max.
00272         If not, return either min or max.
00273         
00274         @param val: any number format
00275         @param min: any number format
00276         @param max: any number format
00277         @return: int
00278         
00279         Copied from robot_monitor.
00280         """        
00281         rospy.logdebug(' TimelineView _clamp val=%s min=%s max=%s', 
00282                        val, min, max)
00283         if (val < min):
00284             return min
00285         if (val > max):
00286             return max
00287         return val
00288                 
00289     def slot_redraw(self):
00290         """
00291         Gets called either when new msg comes in or when marker is moved by user.
00292         """      
00293                
00294         self._parent._scene.clear()
00295 
00296         is_enabled = self.isEnabled()
00297         
00298         qsize = self.size()
00299         width_tl = qsize.width()
00300         height_tl = qsize.height()
00301         
00302         length_tl = ((self._max_num_seconds + 1) - 
00303                      self._min_num_seconds)
00304 
00305         len_queue = length_tl
00306         #w = float(width_tl / len_queue) # This returns always 0 in 
00307                                          # the 1st decimal point, which causes
00308                                          # timeline not fit nicely.
00309         w = width_tl / float(len_queue)
00310  
00311         for i, m in enumerate(self._parent.get_diagnostic_queue()):            
00312             h = self.viewport().height()
00313             
00314             # Figure out each cell's color.
00315             qcolor = None
00316             color_index = i + self._min_num_seconds
00317             if (is_enabled):
00318                 qcolor = self._color_callback(self._parent.get_diagnostic_queue(),
00319                                               color_index)                
00320             else:
00321                 qcolor = QColor('grey')
00322             
00323             # TODO For adding gradation to the cell color. Not used yet.
00324             end_color = QColor(0.5 * QColor('red').value(),
00325                                0.5 * QColor('green').value(),
00326                                0.5 * QColor('blue').value())
00327 
00328             rect = self._parent._scene.addRect(w * i, 0, w, h, 
00329                                                QColor('white'), qcolor)
00330             rospy.logdebug('TimelineView.slot_redraw #%d th loop w=%s width_tl=%s',
00331                           i, w, width_tl)            
00332         
00333         # Setting marker.
00334         #xpos_marker = ((self._xpos_marker - 1) * width_cell + 
00335                        #(width_cell / 2.0) -
00336         xpos_marker = ((self._xpos_marker - 1) * w +
00337                        (w / 2.0) - (self._timeline_marker_width / 2.0))
00338         pos_marker = QPointF(xpos_marker, 0)
00339                 
00340         # Need to instantiate marker everytime since it gets deleted 
00341         # in every loop by scene.clear()
00342         timeline_marker = self._instantiate_tl_icon()
00343         timeline_marker.setPos(pos_marker)
00344         self._parent._scene.addItem(timeline_marker)
00345         # self._timeline_marker.paint(painter, qrect)
00346         rospy.logdebug(' slot_redraw xpos_marker(int)=%s length_tl=%s',
00347                       int(xpos_marker), length_tl)
00348 
00349     def _instantiate_tl_icon(self):
00350         timeline_marker_icon = QIcon.fromTheme('system-search')
00351         timeline_marker_icon_pixmap = timeline_marker_icon.pixmap(
00352                                                 self._timeline_marker_width,
00353                                                 self._timeline_marker_height)
00354         return QGraphicsPixmapItem(timeline_marker_icon_pixmap)     
00355   


rqt_robot_monitor
Author(s): Isaac Saito, Ze'ev Klapow
autogenerated on Fri Jan 3 2014 11:56:17