Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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
00055
00056
00057
00058
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
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