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