time_pane.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 from collections import deque
00036 from math import floor
00037 import os
00038 
00039 from python_qt_binding import loadUi
00040 from python_qt_binding.QtCore import Signal
00041 from python_qt_binding.QtGui import QGraphicsScene, QWidget
00042 import rospy
00043 import rospkg
00044 
00045 from .timeline import TimelineView
00046 
00047 
00048 class TimelinePane(QWidget):
00049     """
00050     This class defines the pane where timeline and its related components
00051     are displayed.
00052     """
00053 
00054     sig_update = Signal()
00055 
00056     def __init__(self, parent):
00057         """
00058         Because this class is intended to be instantiated via Qt's .ui file,
00059         taking argument other than parent widget is not possible, which is
00060         ported to set_timeline_data method. That said, set_timeline_data must
00061         be called (soon) after an object of this is instantiated.
00062 
00063         :param color_callback: Not directly used within this class. Instead,
00064         this will be passed and used in TimelineView class.
00065         """
00066         #TODO(Isaac) pause_callback is MUST since it's used in both by
00067         #            RobotMonitorWidget & InspectorWindow.
00068 
00069         super(TimelinePane, self).__init__()
00070         self._parent = parent
00071 
00072     def set_timeline_data(self, len_timeline=None,
00073                  color_callback=None,
00074                  pause_callback=None):
00075         if len_timeline:
00076             rp = rospkg.RosPack()
00077             ui_file = os.path.join(rp.get_path('rqt_robot_monitor'),
00078                                    'resource',
00079                                    'timelinepane.ui')
00080             loadUi(ui_file, self, {'TimelineView': TimelineView})
00081 
00082             self._pause_callback = pause_callback
00083             self._timeline_view.set_init_data(1, len_timeline, 5,
00084                                               color_callback)
00085 
00086             self._scene = QGraphicsScene(self._timeline_view)
00087             self._timeline_view.setScene(self._scene)
00088             self._timeline_view.show()
00089 
00090             self._queue_diagnostic = deque()
00091             self._len_timeline = len_timeline
00092             self._paused = False
00093             self._tracking_latest = True
00094             self._last_sec_marker_at = 2
00095             self._last_msg = None
00096 
00097             self._pause_button.clicked[bool].connect(self._pause)
00098             self.sig_update.connect(self._timeline_view.slot_redraw)
00099 
00100     def mouse_release(self, event):
00101         """
00102         :type event: QMouseEvent
00103         """
00104         xpos_clicked = event.x()
00105         width_each_cell_shown = float(
00106                        self._timeline_view.viewport().width()) / len(
00107                                                    self._queue_diagnostic)
00108         i = int(floor(xpos_clicked / width_each_cell_shown))
00109         rospy.logdebug('mouse_release i=%d width_each_cell_shown=%s',
00110                        i, width_each_cell_shown)
00111 
00112         msg = self._queue_diagnostic[i]
00113         if msg:
00114             self._parent.on_pause(True, msg)
00115 
00116             if not self._pause_button.isChecked():
00117                 self._pause_button.toggle()
00118 
00119     def get_worst(self, msg):
00120         lvl = 0
00121         for status in msg.status:
00122             if status.level > lvl:
00123                 lvl = status.level
00124         return lvl
00125 
00126     def _pause(self, paused):
00127         """
00128         Should be the only interface for pausing timeline pane and timeline
00129         itself (which is not as of now..).
00130 
00131         :type paused: bool
00132         """
00133         #TODO(Isaac) Think about optimal way to call functions in parent class
00134         # (pause, _unpause). Use callback or just calling via parent instance?
00135 
00136         rospy.logdebug('TimelinePane pause isPaused?=%s', paused)
00137         if paused:
00138             self._pause_button.setDown(True)
00139             self._paused = True
00140             self._tracking_latest = False
00141             self._parent.pause(self._queue_diagnostic[-1])
00142         else:
00143             self._pause_button.setDown(False)
00144             self._paused = False
00145             self._tracking_latest = True
00146             self._parent.unpause(self._queue_diagnostic[-1])
00147             rospy.logdebug('Objs; parent=%s, parent._unpause obj=%s',
00148                            self._parent,
00149                            self._parent.unpause)
00150 
00151     def on_slider_scroll(self, evt):
00152         """
00153 
00154         :type evt: QMouseEvent
00155         """
00156 
00157         xpos_marker = self._timeline_view.get_xpos_marker() - 1
00158         rospy.logdebug('on_slider_scroll xpos_marker=%s last_sec_marker_at=%s',
00159                       xpos_marker, self._last_sec_marker_at)
00160         if (xpos_marker == self._last_sec_marker_at):
00161             # Clicked the same pos as last time.
00162             return
00163         elif (xpos_marker >= len(self._queue_diagnostic)):
00164             # When clicked out-of-region
00165             return
00166 
00167         self._last_sec_marker_at = xpos_marker
00168 
00169         self._pause(True)
00170 
00171         # Fetch corresponding previous DiagsnoticArray instance from queue,
00172         # and sig_update trees.
00173         msg = self._queue_diagnostic[xpos_marker]
00174         self._parent.new_diagnostic(msg, True)
00175 
00176     def new_diagnostic(self, msg):
00177         """
00178         Callback for new msg for TimelinePane class.
00179 
00180         Puts new msg into a queue, update the length of timeline. Also emits
00181         a signal to notify another callbacks.
00182         This ignores new msg if timeline is paused.
00183 
00184         :type msg: Either DiagnosticArray or DiagnosticsStatus. Can be
00185                    determined by __init__'s arg "msg_callback".
00186         """
00187 
00188         self._last_msg = msg    # Shouldn't this sit after self._paused return?
00189                                 # Original robot_monitor does this way.
00190 
00191         # if (self._message_receipt_callback is not None):
00192         #    self._message_receipt_callback(msg)
00193         # # This is done here in robot_monitor.
00194         # # In rqt_robot_monitor, however, it's done in RobotMonitorWidget.
00195 
00196         if (self._paused):
00197             return
00198 
00199         self._queue_diagnostic.append(msg)
00200         if (len(self._queue_diagnostic) > self._len_timeline):
00201             # Remove the msg in the record, which is older than the specified
00202             # time.
00203             self._queue_diagnostic.popleft()
00204 
00205         new_len = len(self._queue_diagnostic)
00206         self._timeline_view.set_range(1, new_len)
00207 
00208         self.sig_update.emit()
00209         rospy.logdebug(' TimelinePane new_diagnostic new_len=%d', new_len)
00210 
00211     def redraw(self):
00212         self.sig_update.emit()
00213 
00214     def get_diagnostic_queue(self):
00215         """
00216 
00217         :return: a queue that contains either DiagnosticArray or
00218                  DiagnosticsStatus. Depends on the parent class -
00219                  if RobotMonitorWidget is the parent, the former type is
00220                  returned. if InspectorWidget the latter.
00221         """
00222         return self._queue_diagnostic


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