timeline.py
Go to the documentation of this file.
00001 # Software License Agreement (BSD License)
00002 #
00003 # Copyright (c) 2014, Austin Hendrix
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 Austin Hendrix. 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: Austin Hendrix
00034 
00035 from collections import deque
00036 from python_qt_binding.QtCore import Signal, Slot, QObject
00037 
00038 import rospy
00039 
00040 from diagnostic_msgs.msg import DiagnosticArray
00041 
00042 class Timeline(QObject):
00043     """
00044     A class which represents the status history of diagnostics
00045     It can be queried for a past history of diagnostics, and paused
00046     """
00047     message_updated = Signal(DiagnosticArray)
00048     pause_changed = Signal(bool)
00049 
00050     def __init__(self, topic, topic_type, count=30):
00051         super(Timeline, self).__init__()
00052         self._queue = deque(maxlen=count)
00053         self._count = count
00054         self._current_index = -1 # rightmost item
00055 
00056         # the paused queue is a backup copy of the queue that is updated with
00057         # new messages while the timeline is paused, so that new messages and
00058         # new history are not lost
00059         self._paused_queue = None
00060 
00061         self._have_messages = False
00062         self._last_message_time = 0
00063 
00064         self._subscriber = rospy.Subscriber(topic, topic_type, self.callback,
00065                                             queue_size=10)
00066 
00067     def shutdown(self):
00068         """
00069         Turn off this Timeline
00070         Internally, this just shuts down the subscriber
00071         """
00072         self._subscriber.unregister()
00073 
00074     @Slot(bool)
00075     def set_paused(self, pause):
00076         """
00077         Slot, to be called to change the pause status of the timeline
00078 
00079         This is generally intended to be connected to the status signal
00080         from a button or checkbox
00081         """
00082         if pause != self.paused:
00083             if pause:
00084                 self._paused_queue = deque(self._queue, self._queue.maxlen)
00085             else:
00086                 self._queue = self._paused_queue
00087                 self._paused_queue = None
00088 
00089                 # update pointer to latest message
00090                 self._current_index = -1
00091                 self.message_updated.emit(self._queue[self._current_index])
00092             self.pause_changed.emit(pause)
00093 
00094     @property
00095     def paused(self):
00096         """ True if this timeline is paused """
00097         return self._paused_queue is not None
00098 
00099     def callback(self, msg):
00100         """
00101         ROS Callback for new diagnostic messages
00102 
00103         Puts new msg into the queue, and emits a signal to let listeners know
00104         that the timeline has been updated
00105 
00106         If the timeline is paused, new messages are placed into a separate
00107         queue and swapped back in when the timeline is unpaused
00108 
00109         :type msg: Either DiagnosticArray or DiagnosticsStatus. Can be
00110                    determined by __init__'s arg "msg_callback".
00111         """
00112         self._have_messages = True
00113         self._last_message_time = rospy.get_time()
00114         if self.paused:
00115             self._paused_queue.append(msg)
00116         else:
00117             self._queue.append(msg)
00118             self.message_updated.emit(msg)
00119 
00120     @property
00121     def has_messages(self):
00122         """
00123         True if this timeline has received any messages.
00124         False if no messages have been received yet
00125         """
00126         return self._have_messages
00127 
00128     def data_age(self):
00129         """ Get the age (in seconds) of the most recent diagnostic message """
00130         current_time = rospy.get_time()
00131         time_diff = current_time - self._last_message_time
00132         return time_diff
00133 
00134     @property
00135     def is_stale(self):
00136         """ True is this timeline is stale. """
00137         return self.data_age() > 10.0
00138         
00139     def set_position(self, index):
00140         max_index = len(self._queue) - 1
00141         min_index = -len(self._queue)
00142         index = min(index, max_index)
00143         index = max(index, min_index)
00144         if index != self._current_index:
00145             self._current_index = index
00146             self.message_updated.emit(self._queue[index])
00147 
00148     def get_position(self):
00149         index = self._current_index
00150         if index < 0:
00151             index = len(self._queue) + index
00152         return index
00153 
00154     def __len__(self):
00155         return len(self._queue)
00156 
00157     def __iter__(self):
00158         for msg in self._queue:
00159             yield 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