_update_functions.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage, Inc. 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 # -*- coding: utf-8 -*-
34 
35 """ diagnostic_updater for Python.
36 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
37 """
38 
39 import rospy
40 from ._diagnostic_updater import *
41 
42 
44  """A structure that holds the constructor parameters for the FrequencyStatus
45  class.
46 
47  Implementation note: the min_freq and max_freq parameters in the C += 1 code
48  are stored as pointers, so that if they are updated, the new values are used.
49  To emulate this behavior, we here use a dictionary to hold them: {'min','max'}
50 
51  freq_bound is a dictionary with keys 'min' and 'max', containing the min
52  and max acceptable frequencies.
53 
54  tolerance is the tolerance with which bounds must be satisfied. Acceptable
55  values are from freq_bound['min'] * (1 - torelance) to
56  freq_bound['max'] * (1 + tolerance). Common use cases are to set
57  tolerance to zero, or to assign the same value to freq_bound['min'] and
58  freq_bound['max']
59 
60  window_size is the number of events to consider in the statistics.
61  """
62 
63  def __init__(self, freq_bound, tolerance = 0.1, window_size = 5):
64  """Creates a filled-out FrequencyStatusParam."""
65  self.freq_bound = freq_bound
66  self.tolerance = tolerance
67  self.window_size = window_size
68 
69 
71  """A diagnostic task that monitors the frequency of an event.
72 
73  This diagnostic task monitors the frequency of calls to its tick method,
74  and creates corresponding diagnostics. It will report a warning if the
75  frequency is outside acceptable bounds, and report an error if there have
76  been no events in the latest window.
77  """
78 
79  def __init__(self, params, name = "FrequencyStatus"):
80  """Constructs a FrequencyStatus class with the given parameters."""
81  DiagnosticTask.__init__(self, name)
82  self.params = params
83  self.lock = threading.Lock()
84  self.clear()
85 
86  def clear(self):
87  """Resets the statistics."""
88  with self.lock:
89  self.count = 0
90  curtime = rospy.Time.now()
91  self.times = [curtime for i in range(self.params.window_size)]
92  self.seq_nums = [0 for i in range(self.params.window_size)]
93  self.hist_indx = 0
94 
95  def tick(self):
96  """Signals that an event has occurred."""
97  with self.lock:
98  self.count += 1
99 
100  def run(self, stat):
101  with self.lock:
102  curtime = rospy.Time.now()
103  curseq = self.count
104  events = curseq - self.seq_nums[self.hist_indx]
105  window = (curtime - self.times[self.hist_indx]).to_sec()
106  freq = events / window
107  self.seq_nums[self.hist_indx] = curseq
108  self.times[self.hist_indx] = curtime
109  self.hist_indx = (self.hist_indx + 1) % self.params.window_size
110 
111  if events == 0:
112  stat.summary(2, "No events recorded.")
113  elif freq < self.params.freq_bound['min'] * (1 - self.params.tolerance):
114  stat.summary(1, "Frequency too low.")
115  elif self.params.freq_bound.has_key('max') and freq > self.params.freq_bound['max'] * (1 + self.params.tolerance):
116  stat.summary(1, "Frequency too high.")
117  else:
118  stat.summary(0, "Desired frequency met")
119 
120  stat.add("Events in window", "%d" % events)
121  stat.add("Events since startup", "%d" % self.count)
122  stat.add("Duration of window (s)", "%f" % window)
123  stat.add("Actual frequency (Hz)", "%f" % freq)
124  if self.params.freq_bound.has_key('max') and self.params.freq_bound['min'] == self.params.freq_bound['max']:
125  stat.add("Target frequency (Hz)", "%f" % self.params.freq_bound['min'])
126  if self.params.freq_bound['min'] > 0:
127  stat.add("Minimum acceptable frequency (Hz)", "%f" % (self.params.freq_bound['min'] * (1 - self.params.tolerance)))
128  if self.params.freq_bound.has_key('max'):
129  stat.add("Maximum acceptable frequency (Hz)", "%f" % (self.params.freq_bound['max'] * (1 + self.params.tolerance)))
130 
131  return stat
132 
133 
135  """A structure that holds the constructor parameters for the TimeStampStatus class.
136 
137  max_acceptable: maximum acceptable difference between two timestamps.
138  min_acceptable: minimum acceptable difference between two timestamps.
139  """
140 
141  def __init__(self, min_acceptable = -1, max_acceptable = 5):
142  """Creates a filled-out TimeStampStatusParam."""
143  self.max_acceptable = max_acceptable
144  self.min_acceptable = min_acceptable
145 
146 
148  """Diagnostic task to monitor the interval between events.
149 
150  This diagnostic task monitors the difference between consecutive events,
151  and creates corresponding diagnostics. An error occurs if the interval
152  between consecutive events is too large or too small. An error condition
153  will only be reported during a single diagnostic report unless it
154  persists. Tallies of errors are also maintained to keep track of errors
155  in a more persistent way.
156  """
157 
158  def __init__(self, params = TimeStampStatusParam(), name = "Timestamp Status"):
159  """Constructs the TimeStampStatus with the given parameters."""
160  DiagnosticTask.__init__(self, name)
161  self.params = params
162  self.lock = threading.Lock()
163  self.early_count = 0
164  self.late_count = 0
165  self.zero_count = 0
166  self.zero_seen = False
167  self.max_delta = 0
168  self.min_delta = 0
169  self.deltas_valid = False
170 
171  def tick(self, stamp):
172  """Signals an event.
173  @param stamp The timestamp of the event that will be used in computing
174  intervals. Can be either a double or a ros::Time.
175  """
176  if not isinstance(stamp, float):
177  stamp = stamp.to_sec()
178 
179  with self.lock:
180  if stamp == 0:
181  self.zero_seen = True
182  else:
183  delta = rospy.Time.now().to_sec() - stamp
184  if not self.deltas_valid or delta > self.max_delta:
185  self.max_delta = delta
186  if not self.deltas_valid or delta < self.min_delta:
187  self.min_delta = delta
188  self.deltas_valid = True
189 
190  def run(self, stat):
191  with self.lock:
192 
193  stat.summary(0, "Timestamps are reasonable.")
194  if not self.deltas_valid:
195  stat.summary(1, "No data since last update.")
196  else:
197  if self.min_delta < self.params.min_acceptable:
198  stat.summary(2, "Timestamps too far in future seen.")
199  self.early_count += 1
200  if self.max_delta > self.params.max_acceptable:
201  stat.summary(2, "Timestamps too far in past seen.")
202  self.late_count += 1
203  if self.zero_seen:
204  stat.summary(2, "Zero timestamp seen.")
205  self.zero_count += 1
206 
207  stat.add("Earliest timestamp delay:", "%f" % self.min_delta)
208  stat.add("Latest timestamp delay:", "%f" % self.max_delta)
209  stat.add("Earliest acceptable timestamp delay:", "%f" % self.params.min_acceptable)
210  stat.add("Latest acceptable timestamp delay:", "%f" % self.params.max_acceptable)
211  stat.add("Late diagnostic update count:", "%i" % self.late_count)
212  stat.add("Early diagnostic update count:", "%i" % self.early_count)
213  stat.add("Zero seen diagnostic update count:", "%i" % self.zero_count)
214 
215  self.deltas_valid = False
216  self.min_delta = 0
217  self.max_delta = 0
218  self.zero_seen = False
219 
220  return stat
221 
222 
224  """Diagnostic task to monitor whether a node is alive
225 
226  This diagnostic task always reports as OK and 'Alive' when it runs
227  """
228 
229  def __init__(self):
230  """Constructs a HeartBeat"""
231  DiagnosticTask.__init__(self, "Heartbeat")
232 
233  def run(self, stat):
234  stat.summary(0, "Alive")
235  return stat
def __init__(self, params=TimeStampStatusParam(), name="Timestamp Status")
def __init__(self, params, name="FrequencyStatus")
def __init__(self, min_acceptable=-1, max_acceptable=5)
def __init__(self, freq_bound, tolerance=0.1, window_size=5)


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Thu Oct 8 2020 03:19:34