_update_functions.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 # -*- coding: utf-8 -*-
00034 
00035 """ diagnostic_updater for Python.
00036 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
00037 """
00038 
00039 import rospy
00040 from ._diagnostic_updater import *
00041 
00042 
00043 class FrequencyStatusParam:
00044     """A structure that holds the constructor parameters for the FrequencyStatus
00045     class.
00046 
00047     Implementation note: the min_freq and max_freq parameters in the C += 1 code
00048     are stored as pointers, so that if they are updated, the new values are used.
00049     To emulate this behavior, we here use a dictionary to hold them: {'min','max'}
00050 
00051     freq_bound is a dictionary with keys 'min' and 'max', containing the min
00052     and max acceptable frequencies.
00053 
00054     tolerance is the tolerance with which bounds must be satisfied. Acceptable
00055     values are from freq_bound['min'] * (1 - torelance) to
00056     freq_bound['max'] * (1 + tolerance). Common use cases are to set
00057     tolerance to zero, or to assign the same value to freq_bound['min'] and
00058     freq_bound['max']
00059 
00060     window_size is the number of events to consider in the statistics.
00061     """
00062 
00063     def __init__(self, freq_bound, tolerance = 0.1, window_size = 5):
00064         """Creates a filled-out FrequencyStatusParam."""
00065         self.freq_bound = freq_bound
00066         self.tolerance = tolerance
00067         self.window_size = window_size
00068 
00069 
00070 class FrequencyStatus(DiagnosticTask):
00071     """A diagnostic task that monitors the frequency of an event.
00072 
00073     This diagnostic task monitors the frequency of calls to its tick method,
00074     and creates corresponding diagnostics. It will report a warning if the
00075     frequency is outside acceptable bounds, and report an error if there have
00076     been no events in the latest window.
00077     """
00078 
00079     def __init__(self, params, name = "FrequencyStatus"):
00080         """Constructs a FrequencyStatus class with the given parameters."""
00081         DiagnosticTask.__init__(self, name)
00082         self.params = params
00083         self.lock = threading.Lock()
00084         self.clear()
00085 
00086     def clear(self):
00087         """Resets the statistics."""
00088         with self.lock:
00089             self.count = 0
00090             curtime = rospy.Time.now()
00091             self.times = [curtime for i in range(self.params.window_size)]
00092             self.seq_nums = [0 for i in range(self.params.window_size)]
00093             self.hist_indx = 0
00094 
00095     def tick(self):
00096         """Signals that an event has occurred."""
00097         with self.lock:
00098             self.count += 1
00099 
00100     def run(self, stat):
00101         with self.lock:
00102             curtime = rospy.Time.now()
00103             curseq = self.count
00104             events = curseq - self.seq_nums[self.hist_indx]
00105             window = (curtime - self.times[self.hist_indx]).to_sec()
00106             freq = events / window
00107             self.seq_nums[self.hist_indx] = curseq
00108             self.times[self.hist_indx] = curtime
00109             self.hist_indx = (self.hist_indx + 1) % self.params.window_size
00110 
00111             if events == 0:
00112                 stat.summary(2, "No events recorded.")
00113             elif freq < self.params.freq_bound['min'] * (1 - self.params.tolerance):
00114                 stat.summary(1, "Frequency too low.")
00115             elif self.params.freq_bound.has_key('max') and freq > self.params.freq_bound['max'] * (1 + self.params.tolerance):
00116                 stat.summary(1, "Frequency too high.")
00117             else:
00118                 stat.summary(0, "Desired frequency met")
00119 
00120             stat.add("Events in window", "%d" % events)
00121             stat.add("Events since startup", "%d" % self.count)
00122             stat.add("Duration of window (s)", "%f" % window)
00123             stat.add("Actual frequency (Hz)", "%f" % freq)
00124             if self.params.freq_bound.has_key('max') and self.params.freq_bound['min'] == self.params.freq_bound['max']:
00125                 stat.add("Target frequency (Hz)", "%f" % self.params.freq_bound['min'])
00126             if self.params.freq_bound['min'] > 0:
00127                 stat.add("Minimum acceptable frequency (Hz)", "%f" % (self.params.freq_bound['min'] * (1 - self.params.tolerance)))
00128             if self.params.freq_bound.has_key('max'):
00129                 stat.add("Maximum acceptable frequency (Hz)", "%f" % (self.params.freq_bound['max'] * (1 + self.params.tolerance)))
00130 
00131         return stat
00132 
00133 
00134 class TimeStampStatusParam:
00135     """A structure that holds the constructor parameters for the TimeStampStatus class.
00136 
00137     max_acceptable: maximum acceptable difference between two timestamps.
00138     min_acceptable: minimum acceptable difference between two timestamps.
00139     """
00140 
00141     def __init__(self, min_acceptable = -1, max_acceptable = 5):
00142         """Creates a filled-out TimeStampStatusParam."""
00143         self.max_acceptable = max_acceptable
00144         self.min_acceptable = min_acceptable
00145 
00146 
00147 class TimeStampStatus(DiagnosticTask):
00148     """Diagnostic task to monitor the interval between events.
00149 
00150     This diagnostic task monitors the difference between consecutive events,
00151     and creates corresponding diagnostics. An error occurs if the interval
00152     between consecutive events is too large or too small. An error condition
00153     will only be reported during a single diagnostic report unless it
00154     persists. Tallies of errors are also maintained to keep track of errors
00155     in a more persistent way.
00156     """
00157 
00158     def __init__(self, params = TimeStampStatusParam(), name = "Timestamp Status"):
00159         """Constructs the TimeStampStatus with the given parameters."""
00160         DiagnosticTask.__init__(self, name)
00161         self.params = params
00162         self.lock = threading.Lock()
00163         self.early_count = 0
00164         self.late_count = 0
00165         self.zero_count = 0
00166         self.zero_seen = False
00167         self.max_delta = 0
00168         self.min_delta = 0
00169         self.deltas_valid = False
00170 
00171     def tick(self, stamp):
00172         """Signals an event.
00173         @param stamp The timestamp of the event that will be used in computing
00174         intervals. Can be either a double or a ros::Time.
00175         """
00176         if not isinstance(stamp, float):
00177             stamp = stamp.to_sec()
00178 
00179         with self.lock:
00180             if stamp == 0:
00181                 self.zero_seen = True
00182             else:
00183                 delta = rospy.Time.now().to_sec() - stamp
00184                 if not self.deltas_valid or delta > self.max_delta:
00185                     self.max_delta = delta
00186                 if not self.deltas_valid or delta < self.min_delta:
00187                     self.min_delta = delta
00188                 self.deltas_valid = True
00189 
00190     def run(self, stat):
00191         with self.lock:
00192 
00193             stat.summary(0, "Timestamps are reasonable.")
00194             if not self.deltas_valid:
00195                 stat.summary(1, "No data since last update.")
00196             else:
00197                 if self.min_delta < self.params.min_acceptable:
00198                     stat.summary(2, "Timestamps too far in future seen.")
00199                     self.early_count += 1
00200                 if self.max_delta > self.params.max_acceptable:
00201                     stat.summary(2, "Timestamps too far in past seen.")
00202                     self.late_count += 1
00203                 if self.zero_seen:
00204                     stat.summary(2, "Zero timestamp seen.")
00205                     self.zero_count += 1
00206 
00207             stat.add("Earliest timestamp delay:", "%f" % self.min_delta)
00208             stat.add("Latest timestamp delay:", "%f" % self.max_delta)
00209             stat.add("Earliest acceptable timestamp delay:", "%f" % self.params.min_acceptable)
00210             stat.add("Latest acceptable timestamp delay:", "%f" % self.params.max_acceptable)
00211             stat.add("Late diagnostic update count:", "%i" % self.late_count)
00212             stat.add("Early diagnostic update count:", "%i" % self.early_count)
00213             stat.add("Zero seen diagnostic update count:", "%i" % self.zero_count)
00214 
00215             self.deltas_valid = False
00216             self.min_delta = 0
00217             self.max_delta = 0
00218             self.zero_seen = False
00219 
00220         return stat
00221 
00222 
00223 class Heartbeat(DiagnosticTask):
00224     """Diagnostic task to monitor whether a node is alive
00225 
00226     This diagnostic task always reports as OK and 'Alive' when it runs
00227     """
00228 
00229     def __init__(self):
00230         """Constructs a HeartBeat"""
00231         DiagnosticTask.__init__(self, "Heartbeat")
00232 
00233     def run(self, stat):
00234         stat.summary(0, "Alive")
00235         return stat


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Tue Mar 26 2019 03:09:44