timeline_view.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, Austin Hendrix
00034 
00035 from math import floor
00036 import rospy
00037 
00038 from python_qt_binding.QtCore import QPointF, Signal, Slot
00039 from python_qt_binding.QtGui import (QColor, QGraphicsPixmapItem,
00040                                      QGraphicsView, QIcon, QGraphicsScene)
00041 
00042 import util_robot_monitor as util
00043 
00044 
00045 class TimelineView(QGraphicsView):
00046     """
00047     This class draws a graphical representation of a timeline.
00048 
00049     This is ONLY the bar and colored boxes.
00050 
00051     When you instantiate this class, do NOT forget to call set_init_data to
00052     set necessary data.
00053     """
00054 
00055     redraw = Signal()
00056 
00057     def __init__(self, parent):
00058         """Cannot take args other than parent due to loadUi limitation."""
00059 
00060         super(TimelineView, self).__init__()
00061         self._parent = parent
00062         self._timeline_marker = QIcon.fromTheme('system-search')
00063 
00064         self._min = 0
00065         self._max = 0
00066         self._xpos_marker = 5
00067 
00068         self._timeline_marker_width = 15
00069         self._timeline_marker_height = 15
00070         self._last_marker_at = 2
00071 
00072         self.redraw.connect(self._slot_redraw)
00073 
00074         self._timeline = None
00075 
00076         self.setUpdatesEnabled(True)
00077         self._scene = QGraphicsScene(self)
00078         self.setScene(self._scene)
00079 
00080     def set_timeline(self, timeline, name=None):
00081         assert(self._timeline is None)
00082         self._name = name
00083         self._timeline = timeline
00084         self._timeline.message_updated.connect(self._updated)
00085 
00086     @Slot()
00087     def _updated(self):
00088         """
00089         Update the widget whenever we receive a new message
00090         """
00091         # update the limits
00092         self._min = 0
00093         self._max = len(self._timeline)-1
00094 
00095         # update the marker position
00096         self._xpos_marker = self._timeline.get_position()
00097 
00098         # redraw
00099         self.redraw.emit()
00100 
00101     def mouseReleaseEvent(self, event):
00102         """
00103         :type event: QMouseEvent
00104         """
00105         xpos = self.pos_from_x(event.x())
00106         self.set_marker_pos(xpos)
00107 
00108     def mousePressEvent(self, event):
00109         """
00110         :type event: QMouseEvent
00111         """
00112         assert(self._timeline is not None)
00113         # Pause the timeline
00114         self._timeline.set_paused(True)
00115 
00116         xpos = self.pos_from_x(event.x())
00117         self.set_marker_pos(xpos)
00118 
00119     def mouseMoveEvent(self, event):
00120         """
00121         :type event: QMouseEvent
00122         """
00123         xpos = self.pos_from_x(event.x())
00124         self.set_marker_pos(xpos)
00125 
00126     def pos_from_x(self, x):
00127         """
00128         Get the index in the timeline from the mouse click position
00129 
00130         :param x: Position relative to self widget.
00131         :return: Index
00132         """
00133         width = self.size().width()
00134         # determine value from mouse click
00135         width_cell = width / float(len(self._timeline))
00136         return int(floor(x / width_cell))
00137 
00138     def set_marker_pos(self, xpos):
00139         """
00140         Set marker position from index
00141 
00142         :param xpos: Marker index
00143         """
00144         assert(self._timeline is not None)
00145         self._xpos_marker = self._clamp(xpos, self._min, self._max)
00146 
00147         if self._xpos_marker == self._last_marker_at:
00148             # Clicked the same pos as last time.
00149             return
00150         elif self._xpos_marker >= len(self._timeline):
00151             # When clicked out-of-region
00152             return
00153 
00154         self._last_marker_at = self._xpos_marker
00155 
00156         # Set timeline position. This broadcasts the message at that position
00157         # to all of the other viewers
00158         self._timeline.set_position(self._xpos_marker)
00159 
00160         # redraw
00161         self.redraw.emit()
00162 
00163     def _clamp(self, val, min, max):
00164         """
00165         Judge if val is within the range given by min & max.
00166         If not, return either min or max.
00167 
00168         :type val: any number format
00169         :type min: any number format
00170         :type max: any number format
00171         :rtype: int
00172         """
00173         if (val < min):
00174             return min
00175         if (val > max):
00176             return max
00177         return val
00178 
00179     @Slot()
00180     def _slot_redraw(self):
00181         """
00182         Gets called either when new msg comes in or when marker is moved by
00183         user.
00184         """
00185         self._scene.clear()
00186 
00187         qsize = self.size()
00188         width_tl = qsize.width()
00189 
00190         w = width_tl / float(max(len(self._timeline), 1))
00191         is_enabled = self.isEnabled()
00192 
00193         if self._timeline is not None:
00194             for i, m in enumerate(self._timeline):
00195                 h = self.viewport().height()
00196 
00197                 # Figure out each cell's color.
00198                 qcolor = QColor('grey')
00199                 if is_enabled:
00200                     qcolor = self._get_color_for_value(m)
00201 
00202 #  TODO Use this code for adding gradation to the cell color.
00203 #                end_color = QColor(0.5 * QColor('red').value(),
00204 #                                   0.5 * QColor('green').value(),
00205 #                                   0.5 * QColor('blue').value())
00206 
00207                 self._scene.addRect(w * i, 0, w, h, QColor('white'), qcolor)
00208 
00209         # Setting marker.
00210         xpos_marker = (self._xpos_marker * w +
00211                        (w / 2.0) - (self._timeline_marker_width / 2.0))
00212         pos_marker = QPointF(xpos_marker, 0)
00213 
00214         # Need to instantiate marker everytime since it gets deleted
00215         # in every loop by scene.clear()
00216         timeline_marker = self._instantiate_tl_icon()
00217         timeline_marker.setPos(pos_marker)
00218         self._scene.addItem(timeline_marker)
00219 
00220     def _instantiate_tl_icon(self):
00221         timeline_marker_icon = QIcon.fromTheme('system-search')
00222         timeline_marker_icon_pixmap = timeline_marker_icon.pixmap(
00223                                                 self._timeline_marker_width,
00224                                                 self._timeline_marker_height)
00225         return QGraphicsPixmapItem(timeline_marker_icon_pixmap)
00226 
00227     def _get_color_for_value(self, msg):
00228         """
00229         :type msg: DiagnosticArray
00230         """
00231 
00232         if self._name is not None:
00233             # look up name in msg; return grey if not found
00234             status = util.get_status_by_name(msg, self._name)
00235             if status is not None:
00236                 return util.level_to_color(status.level)
00237             else:
00238                 return QColor('grey')
00239         return util.get_color_for_message(msg)


rqt_robot_monitor
Author(s): Austin Hendrix, Isaac Saito, Ze'ev Klapow, Kevin Watts, Josh Faust
autogenerated on Fri Aug 28 2015 12:50:48