_diagnostic_updater.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 import threading, httplib
00041 from diagnostic_msgs.msg import DiagnosticArray
00042 
00043 from ._diagnostic_status_wrapper import *
00044 
00045 class DiagnosticTask:
00046     """DiagnosticTask is an abstract base class for collecting diagnostic data.
00047 
00048     Subclasses are provided for generating common diagnostic information.
00049     A DiagnosticTask has a name, and a function that is called to cleate a
00050     DiagnosticStatusWrapper.
00051     """
00052 
00053     def __init__(self, name):
00054         """Constructs a DiagnosticTask setting its name in the process."""
00055         self.name = name
00056 
00057     def getName(self):
00058         """Returns the name of the DiagnosticTask."""
00059         return self.name
00060 
00061     def run(self, stat):
00062         """Fills out this Task's DiagnosticStatusWrapper.
00063         @param stat: the DiagnosticStatusWrapper to fill
00064         @return the filled DiagnosticStatusWrapper
00065         """
00066         return stat
00067 
00068 
00069 
00070 class FunctionDiagnosticTask(DiagnosticTask):
00071     """A DiagnosticTask based on a function.
00072 
00073     The FunctionDiagnosticTask calls the function when it updates. The
00074     function updates the DiagnosticStatusWrapper and collects data.
00075 
00076     This is useful for gathering information about a device or driver, like temperature,
00077     calibration, etc.
00078     """
00079 
00080     def __init__(self, name, fn):
00081         """Constructs a GenericFunctionDiagnosticTask based on the given name and function.
00082         @param name Name of the function.
00083         @param fn Function to be called when run is called.
00084         """
00085         DiagnosticTask.__init__(self, name)
00086         self.fn = fn
00087 
00088     def run(self, stat):
00089         return self.fn(stat)
00090 
00091 
00092 
00093 class CompositeDiagnosticTask(DiagnosticTask):
00094     """Merges CompositeDiagnosticTask into a single DiagnosticTask.
00095 
00096     The CompositeDiagnosticTask allows multiple DiagnosticTask instances to
00097     be combined into a single task that produces a single single
00098     DiagnosticStatusWrapped. The output of the combination has the max of
00099     the status levels, and a concatenation of the non-zero-level messages.
00100 
00101     For instance, this could be used to combine the calibration and offset data
00102     from an IMU driver.
00103     """
00104 
00105     def __init__(self, name):
00106         """Constructs a CompositeDiagnosticTask with the given name."""
00107         DiagnosticTask.__init__(self, name)
00108         self.tasks = []
00109 
00110     def run(self, stat):
00111         """Runs each child and merges their outputs."""
00112         combined_summary = DiagnosticStatusWrapper()
00113         original_summary = DiagnosticStatusWrapper()
00114 
00115         original_summary.summary(stat)
00116 
00117         for task in self.tasks:
00118             # Put the summary that was passed in.
00119             stat.summary(original_summary)
00120             # Let the next task add entries and put its summary.
00121             stat = task.run(stat)
00122             # Merge the new summary into the combined summary.
00123             combined_summary.mergeSummary(stat)
00124 
00125 
00126         # Copy the combined summary into the output.
00127         stat.summary(combined_summary)
00128         return stat
00129 
00130     def addTask(self, t):
00131         """Adds a child CompositeDiagnosticTask.
00132 
00133         This CompositeDiagnosticTask will be called each time this
00134         CompositeDiagnosticTask is run.
00135         """
00136         self.tasks.append(t)
00137 
00138 
00139 
00140 class DiagnosticTaskVector:
00141     """Internal use only.
00142 
00143     Base class for diagnostic_updater::Updater and self_test::Dispatcher.
00144     The class manages a collection of diagnostic updaters. It contains the
00145     common functionality used for producing diagnostic updates and for
00146     self-tests.
00147     """
00148 
00149     class DiagnosticTaskInternal:
00150         """Class used to represent a diagnostic task internally in
00151         DiagnosticTaskVector.
00152         """
00153 
00154         def __init__(self, name, fn):
00155             self.name = name
00156             self.fn = fn
00157 
00158         def run(self, stat):
00159             stat.name = self.name
00160             return self.fn(stat)
00161 
00162 
00163     def __init__(self):
00164         self.tasks = []
00165         self.lock = threading.Lock()
00166 
00167     def addedTaskCallback(self, task):
00168         """Allows an action to be taken when a task is added. The Updater class
00169         uses this to immediately publish a diagnostic that says that the node
00170         is loading.
00171         """
00172         pass
00173 
00174     def add(self, *args):
00175         """Add a task to the DiagnosticTaskVector.
00176 
00177         Usage:
00178         add(task): where task is a DiagnosticTask
00179         add(name, fn): add a DiagnosticTask embodied by a name and function
00180         """
00181         if len(args)==1:
00182             task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0].getName(), args[0].run)
00183         elif len(args)==2:
00184             task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0], args[1])
00185 
00186         with self.lock:
00187             self.tasks.append(task)
00188             self.addedTaskCallback(task)
00189 
00190     def removeByName(self, name):
00191         """Removes a task based on its name.
00192 
00193         Removes the first task that matches the specified name. (New in
00194         version 1.1.2)
00195 
00196         @param name Name of the task to remove.
00197         @return Returns true if a task matched and was removed.
00198         """
00199         found = False
00200         with self.lock:
00201             for i in range(len(self.tasks)):
00202                 if self.tasks[i].name == name:
00203                     self.tasks.pop(i)
00204                     found = True
00205                     break
00206         return found
00207 
00208 
00209 
00210 
00211 class Updater(DiagnosticTaskVector):
00212     """Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
00213 
00214     This class manages a list of diagnostic tasks. Its update function
00215     should be called frequently. At some predetermined rate, the update
00216     function will cause all the diagnostic tasks to run, and will collate
00217     and publish the resulting diagnostics. The publication rate is
00218     determined by the "~diagnostic_period" ros parameter.
00219 
00220     The class also allows an update to be forced when something significant
00221     has happened, and allows a single message to be broadcast on all the
00222     diagnostics if normal operation of the node is suspended for some
00223     reason.
00224     """
00225 
00226     def __init__(self):
00227         """Constructs an updater class."""
00228         DiagnosticTaskVector.__init__(self)
00229         self.publisher = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=10)
00230 
00231         self.last_time = rospy.Time.now()
00232         self.last_time_period_checked = self.last_time
00233         self.period = 1
00234 
00235         self.verbose = False
00236         self.hwid = ""
00237         self.warn_nohwid_done = False
00238 
00239     def update(self):
00240         """Causes the diagnostics to update if the inter-update interval
00241         has been exceeded.
00242         """
00243         self._check_diagnostic_period()
00244         if rospy.Time.now() >= self.last_time + rospy.Duration(self.period):
00245             self.force_update()
00246 
00247     def force_update(self):
00248         """Forces the diagnostics to update.
00249 
00250         Useful if the node has undergone a drastic state change that should be
00251         published immediately.
00252         """
00253         self.last_time = rospy.Time.now()
00254 
00255         warn_nohwid = len(self.hwid)==0
00256 
00257         status_vec = []
00258 
00259         with self.lock: # Make sure no adds happen while we are processing here.
00260             for task in self.tasks:
00261                 status = DiagnosticStatusWrapper()
00262                 status.name = task.name
00263                 status.level = 2
00264                 status.message = "No message was set"
00265                 status.hardware_id = self.hwid
00266 
00267                 stat = task.run(status)
00268 
00269                 status_vec.append(status)
00270 
00271                 if status.level:
00272                     warn_nohwid = False
00273 
00274                 if self.verbose and status.level:
00275                     rospy.logwarn("Non-zero diagnostic status. Name: '%s', status %i: '%s'" %
00276                                 (status.name, status.level, status.message))
00277 
00278         if warn_nohwid and not self.warn_nohwid_done:
00279             rospy.logwarn("diagnostic_updater: No HW_ID was set. This is probably a bug. Please report it. For devices that do not have a HW_ID, set this value to 'none'. This warning only occurs once all diagnostics are OK so it is okay to wait until the device is open before calling setHardwareID.");
00280             self.warn_nohwid_done = True
00281 
00282         self.publish(status_vec)
00283 
00284     def broadcast(self, lvl, msg):
00285         """Outputs a message on all the known DiagnosticStatus.
00286 
00287         Useful if something drastic is happening such as shutdown or a self-test.
00288 
00289         @param lvl Level of the diagnostic being output.
00290         @param msg Status message to output.
00291         """
00292 
00293         status_vec = []
00294 
00295         for task in self.tasks:
00296             status = DiagnosticStatusWrapper()
00297             status.name = task.name
00298             status.summary(lvl, msg)
00299             status_vec.append(status)
00300 
00301         self.publish(status_vec)
00302 
00303     def setHardwareID(self, hwid):
00304         self.hwid = hwid
00305 
00306     def _check_diagnostic_period(self):
00307         """Recheck the diagnostic_period on the parameter server."""
00308 
00309         # This was getParamCached() call in the cpp code. i.e. it would throttle
00310         # the actual call to the parameter server using a notification of change
00311         # mechanism.
00312         # This is not available in rospy. Hence I throttle the call to the
00313         # parameter server using a standard timeout mechanism (4Hz)
00314 
00315         now = rospy.Time.now()
00316         if  now >= self.last_time_period_checked + rospy.Duration(0.25):
00317             try:
00318                 self.period = rospy.get_param("~diagnostic_period", 1)
00319                 self.last_time_period_checked = now
00320             except (httplib.CannotSendRequest, httplib.ResponseNotReady):
00321                 pass
00322 
00323     def publish(self, msg):
00324         """Publishes a single diagnostic status or a vector of diagnostic statuses."""
00325         if not type(msg) is list:
00326             msg = [msg]
00327 
00328         for stat in msg:
00329             stat.name = rospy.get_name()[1:]+ ": " + stat.name
00330 
00331         da = DiagnosticArray()
00332         da.status = msg
00333         da.header.stamp = rospy.Time.now() # Add timestamp for ROS 0.10
00334         self.publisher.publish(da)
00335 
00336     def addedTaskCallback(self, task):
00337         stat = DiagnosticStatusWrapper()
00338         stat.name = task.name
00339         stat.summary(0, "Node starting up")
00340         self.publish(stat)


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Mon Aug 14 2017 02:52:20