_diagnostic_updater.py
Go to the documentation of this file.
00001 # -*- coding: utf-8 -*-
00002 
00003 """ diagnostic_updater for Python.
00004 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
00005 """
00006 
00007 import roslib
00008 roslib.load_manifest('diagnostic_updater')
00009 import rospy
00010 import threading
00011 from diagnostic_msgs.msg import DiagnosticArray
00012 
00013 from ._diagnostic_status_wrapper import *
00014 
00015 class DiagnosticTask:
00016     """DiagnosticTask is an abstract base class for collecting diagnostic data.
00017 
00018     Subclasses are provided for generating common diagnostic information.
00019     A DiagnosticTask has a name, and a function that is called to cleate a
00020     DiagnosticStatusWrapper.
00021     """
00022 
00023     def __init__(self, name):
00024         """Constructs a DiagnosticTask setting its name in the process."""
00025         self.name = name
00026 
00027     def getName(self):
00028         """Returns the name of the DiagnosticTask."""
00029         return self.name
00030 
00031     def run(self, stat):
00032         """Fills out this Task's DiagnosticStatusWrapper.
00033         @param stat: the DiagnosticStatusWrapper to fill
00034         @return the filled DiagnosticStatusWrapper
00035         """
00036         return stat
00037 
00038 
00039 
00040 class FunctionDiagnosticTask(DiagnosticTask):
00041     """A DiagnosticTask based on a function.
00042 
00043     The FunctionDiagnosticTask calls the function when it updates. The
00044     function updates the DiagnosticStatusWrapper and collects data.
00045 
00046     This is useful for gathering information about a device or driver, like temperature,
00047     calibration, etc.
00048     """
00049 
00050     def __init__(self, name, fn):
00051         """Constructs a GenericFunctionDiagnosticTask based on the given name and function.
00052         @param name Name of the function.
00053         @param fn Function to be called when run is called.
00054         """
00055         DiagnosticTask.__init__(self, name)
00056         self.fn = fn
00057 
00058     def run(self, stat):
00059         return self.fn(stat)
00060 
00061 
00062 
00063 class CompositeDiagnosticTask(DiagnosticTask):
00064     """Merges CompositeDiagnosticTask into a single DiagnosticTask.
00065 
00066     The CompositeDiagnosticTask allows multiple DiagnosticTask instances to
00067     be combined into a single task that produces a single single
00068     DiagnosticStatusWrapped. The output of the combination has the max of
00069     the status levels, and a concatenation of the non-zero-level messages.
00070 
00071     For instance, this could be used to combine the calibration and offset data
00072     from an IMU driver.
00073     """
00074 
00075     def __init__(self, name):
00076         """Constructs a CompositeDiagnosticTask with the given name."""
00077         DiagnosticTask.__init__(self, name)
00078         self.tasks = []
00079 
00080     def run(self, stat):
00081         """Runs each child and merges their outputs."""
00082         combined_summary = DiagnosticStatusWrapper()
00083         original_summary = DiagnosticStatusWrapper()
00084 
00085         original_summary.summary(stat)
00086 
00087         for task in self.tasks:
00088             # Put the summary that was passed in.
00089             stat.summary(original_summary)
00090             # Let the next task add entries and put its summary.
00091             stat = task.run(stat)
00092             # Merge the new summary into the combined summary.
00093             combined_summary.mergeSummary(stat)
00094 
00095 
00096         # Copy the combined summary into the output.
00097         stat.summary(combined_summary)
00098         return stat
00099 
00100     def addTask(self, t):
00101         """Adds a child CompositeDiagnosticTask.
00102 
00103         This CompositeDiagnosticTask will be called each time this
00104         CompositeDiagnosticTask is run.
00105         """
00106         self.tasks.append(t)
00107 
00108 
00109 
00110 class DiagnosticTaskVector:
00111     """Internal use only.
00112 
00113     Base class for diagnostic_updater::Updater and self_test::Dispatcher.
00114     The class manages a collection of diagnostic updaters. It contains the
00115     common functionality used for producing diagnostic updates and for
00116     self-tests.
00117     """
00118 
00119     class DiagnosticTaskInternal:
00120         """Class used to represent a diagnostic task internally in
00121         DiagnosticTaskVector.
00122         """
00123 
00124         def __init__(self, name, fn):
00125             self.name = name
00126             self.fn = fn
00127 
00128         def run(self, stat):
00129             stat.name = self.name
00130             return self.fn(stat)
00131 
00132 
00133     def __init__(self):
00134         self.tasks = []
00135         self.lock = threading.Lock()
00136 
00137     def addedTaskCallback(self, task):
00138         """Allows an action to be taken when a task is added. The Updater class
00139         uses this to immediately publish a diagnostic that says that the node
00140         is loading.
00141         """
00142         pass
00143 
00144     def add(self, *args):
00145         """Add a task to the DiagnosticTaskVector.
00146 
00147         Usage:
00148         add(task): where task is a DiagnosticTask
00149         add(name, fn): add a DiagnosticTask embodied by a name and function
00150         """
00151         if len(args)==1:
00152             task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0].getName(), args[0].run)
00153         elif len(args)==2:
00154             task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0], args[1])
00155 
00156         with self.lock:
00157             self.tasks.append(task)
00158             self.addedTaskCallback(task)
00159 
00160     def removeByName(self, name):
00161         """Removes a task based on its name.
00162 
00163         Removes the first task that matches the specified name. (New in
00164         version 1.1.2)
00165 
00166         @param name Name of the task to remove.
00167         @return Returns true if a task matched and was removed.
00168         """
00169         found = False
00170         with self.lock:
00171             for i in range(len(self.tasks)):
00172                 if self.tasks[i].name == name:
00173                     self.tasks.pop(i)
00174                     found = True
00175                     break
00176         return found
00177 
00178 
00179 
00180 
00181 class Updater(DiagnosticTaskVector):
00182     """Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
00183 
00184     This class manages a list of diagnostic tasks. Its update function
00185     should be called frequently. At some predetermined rate, the update
00186     function will cause all the diagnostic tasks to run, and will collate
00187     and publish the resulting diagnostics. The publication rate is
00188     determined by the "~diagnostic_period" ros parameter.
00189 
00190     The class also allows an update to be forced when something significant
00191     has happened, and allows a single message to be broadcast on all the
00192     diagnostics if normal operation of the node is suspended for some
00193     reason.
00194     """
00195 
00196     def __init__(self):
00197         """Constructs an updater class."""
00198         DiagnosticTaskVector.__init__(self)
00199         self.publisher = rospy.Publisher("/diagnostics", DiagnosticArray)
00200 
00201         self.period = 1.0
00202         self.next_time = rospy.Time.now()
00203 
00204         self.verbose = False
00205         self.hwid = ""
00206         self.warn_nohwid_done = False
00207 
00208     def update(self):
00209         """Causes the diagnostics to update if the inter-update interval
00210         has been exceeded.
00211         """
00212         if rospy.Time.now() < self.next_time:
00213             # @todo put this back in after fix of #2157 update_diagnostic_period(); // Will be checked in force_update otherwise.
00214             pass
00215         else:
00216             self.force_update()
00217 
00218     def force_update(self):
00219         """Forces the diagnostics to update.
00220 
00221         Useful if the node has undergone a drastic state change that should be
00222         published immediately.
00223         """
00224         self.update_diagnostic_period()
00225         self.next_time = rospy.Time.now() + rospy.Duration.from_sec(self.period)
00226 
00227         warn_nohwid = len(self.hwid)==0
00228 
00229         status_vec = []
00230 
00231         with self.lock: # Make sure no adds happen while we are processing here.
00232             for task in self.tasks:
00233                 status = DiagnosticStatusWrapper()
00234                 status.name = task.name
00235                 status.level = 2
00236                 status.message = "No message was set"
00237                 status.hardware_id = self.hwid
00238 
00239                 stat = task.run(status)
00240 
00241                 status_vec.append(status)
00242 
00243                 if status.level:
00244                     warn_nohwid = False
00245 
00246                 if self.verbose and status.level:
00247                     rospy.logwarn("Non-zero diagnostic status. Name: '%s', status %i: '%s'" %
00248                                 (status.name, status.level, status.message))
00249 
00250         if warn_nohwid and not self.warn_nohwid_done:
00251             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.");
00252             self.warn_nohwid_done = True
00253 
00254         self.publish(status_vec)
00255 
00256     def getPeriod(self):
00257         """Returns the interval between updates."""
00258         return self.period
00259 
00260     def broadcast(self, lvl, msg):
00261         """Outputs a message on all the known DiagnosticStatus.
00262 
00263         Useful if something drastic is happening such as shutdown or a self-test.
00264 
00265         @param lvl Level of the diagnostic being output.
00266         @param msg Status message to output.
00267         """
00268 
00269         status_vec = []
00270 
00271         for task in self.tasks:
00272             status = DiagnosticStatusWrapper()
00273             status.name = task.name
00274             status.summary(lvl, msg)
00275             status_vec.append(status)
00276 
00277         self.publish(status_vec)
00278 
00279     def setHardwareID(self, hwid):
00280         self.hwid = hwid
00281 
00282     def update_diagnostic_period(self):
00283         """Recheck the diagnostic_period on the parameter server. (Cached)"""
00284         old_period = self.period
00285         self.period = rospy.get_param("~diagnostic_period", 1)
00286         self.next_time += rospy.Duration(self.period - old_period) # Update next_time
00287 
00288     def publish(self, msg):
00289         """Publishes a single diagnostic status or a vector of diagnostic statuses."""
00290         if not type(msg) is list:
00291             msg = [msg]
00292 
00293         for stat in msg:
00294             stat.name = rospy.get_name()[1:]+ ": " + stat.name
00295 
00296         da = DiagnosticArray()
00297         da.status = msg
00298         da.header.stamp = rospy.Time.now() # Add timestamp for ROS 0.10
00299         self.publisher.publish(da)
00300 
00301     def addedTaskCallback(self, task):
00302         stat = DiagnosticStatusWrapper()
00303         stat.name = task.name
00304         stat.summary(0, "Node starting up")
00305         self.publish(stat)


diagnostic_updater
Author(s): Jeremy Leibs, Blaise Gassend, Brice Rebsamen
autogenerated on Fri Jan 3 2014 11:18:57