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


rqt_robot_monitor
Author(s): Austin Hendrix, Isaac Saito, Ze'ev Klapow, Kevin Watts, Josh Faust
autogenerated on Thu May 16 2019 03:10:09