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


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Sun Oct 5 2014 23:27:19