timeline.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2014, Austin Hendrix
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Austin Hendrix. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Author: Austin Hendrix
34 
35 from collections import deque
36 from python_qt_binding.QtCore import Signal, Slot, QObject
37 
38 import rospy
39 
40 from diagnostic_msgs.msg import DiagnosticArray
41 
42 
43 class Timeline(QObject):
44  """
45  A class which represents the status history of diagnostics
46  It can be queried for a past history of diagnostics, and paused
47  """
48  message_updated = Signal(dict)
49  queue_updated = Signal()
50  pause_changed = Signal(bool)
51  position_changed = Signal(int)
52 
53  def __init__(self, topic, topic_type, count=30):
54  super(Timeline, self).__init__()
55  self._queue = deque(maxlen=count)
56  self._count = count
57  self._current_index = -1 # rightmost item
58 
59  # the paused queue is a backup copy of the queue that is updated with
60  # new messages while the timeline is paused, so that new messages and
61  # new history are not lost
62  self._paused_queue = None
63 
65 
66  self._subscriber = rospy.Subscriber(topic, topic_type, self.callback,
67  queue_size=10)
68 
69  def shutdown(self):
70  """
71  Turn off this Timeline
72  Internally, this just shuts down the subscriber
73  """
74  self._subscriber.unregister()
75 
76  @Slot(bool)
77  def set_paused(self, pause):
78  """
79  Slot, to be called to change the pause status of the timeline
80 
81  This is generally intended to be connected to the status signal
82  from a button or checkbox
83  """
84  if pause != self.paused:
85  if pause:
86  self._paused_queue = deque(self._queue, self._queue.maxlen)
87  else:
88  self._queue = self._paused_queue
89  self._paused_queue = None
90 
91  # update pointer to latest message
92  self._current_index = -1
93  self.message_updated.emit(self._queue[self.position])
94  self.pause_changed.emit(pause)
95 
96  @property
97  def paused(self):
98  """ True if this timeline is paused """
99  return self._paused_queue is not None
100 
101  def callback(self, msg):
102  """
103  ROS Callback for new diagnostic messages
104 
105  Puts new msg into the queue, and emits a signal to let listeners know
106  that the timeline has been updated
107 
108  If the timeline is paused, new messages are placed into a separate
109  queue and swapped back in when the timeline is unpaused
110 
111  :type msg: Either DiagnosticArray or DiagnosticsStatus. Can be
112  determined by __init__'s arg "msg_callback".
113  """
114  self._last_message_time = rospy.get_time()
115  dic = {status.name: status for status in msg.status}
116 
117  if self.paused:
118  self._paused_queue.append(dic)
119  else:
120  self._queue.append(dic)
121  self.queue_updated.emit()
122  if self.position == -1:
123  self.message_updated.emit(dic)
124 
125  @property
126  def has_messages(self):
127  """
128  True if this timeline has received any messages.
129  False if no messages have been received yet
130  """
131  return len(self._queue) > 0
132 
133  @property
134  def data_age(self):
135  """ Get the age (in seconds) of the most recent diagnostic message """
136  current_time = rospy.get_time()
137  time_diff = current_time - self._last_message_time
138  return time_diff
139 
140  @property
141  def is_stale(self):
142  """ True is this timeline is stale. """
143  return self.data_age > 10.0
144 
145  @property
146  def position(self):
147  index = self._current_index
148  while index < -1:
149  index = len(self._queue) + index
150  if index == len(self._queue) - 1:
151  index = -1
152  return index
153 
154  @position.setter
155  def position(self, index):
156  max_index = len(self._queue) - 1
157  min_index = -len(self._queue)
158  index = min(index, max_index)
159  index = max(index, min_index)
160  if index != self._current_index or self._current_index == -1:
161  self._current_index = index
162  self.message_updated.emit(self._queue[index])
163 
164  @Slot(int)
165  def set_position(self, position):
166  self.position = position
167  self.position_changed.emit(position)
168 
169  def get_current_status_by_name(self, name):
170  return self._queue[self.position][name]
171 
172  def get_all_status_by_name(self, name):
173  return [status[name] for status in list(self._queue)]
174 
175  def __len__(self):
176  return len(self._queue)
177 
178  def __iter__(self):
179  for msg in list(self._queue):
180  yield msg
def set_position(self, position)
Definition: timeline.py:165
def get_current_status_by_name(self, name)
Definition: timeline.py:169
def get_all_status_by_name(self, name)
Definition: timeline.py:172
def __init__(self, topic, topic_type, count=30)
Definition: timeline.py:53


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