35 """ diagnostic_updater for Python.
36 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
41 from diagnostic_msgs.msg
import DiagnosticArray
46 import http.client
as httplib
48 from ._diagnostic_status_wrapper
import *
51 """DiagnosticTask is an abstract base class for collecting diagnostic data.
53 Subclasses are provided for generating common diagnostic information.
54 A :class:`DiagnosticTask` has a name, and a function that is called to create a
55 :class:`DiagnosticStatusWrapper`.
59 """Constructs a :class:`DiagnosticTask` setting its name in the process.
61 :param str name: The name of the diagnostic task.
66 """Returns the name of the :class:`DiagnosticTask`.
73 """Fills out this Task's :class:`DiagnosticStatusWrapper`.
75 :param DiagnosticStatusWrapper stat: the :class:`DiagnosticStatusWrapper` to fill
76 :return: the filled :class:`DiagnosticStatusWrapper`
77 :rtype: DiagnosticStatusWrapper
84 """A :class:`DiagnosticTask` based on a function.
86 The :class:`FunctionDiagnosticTask` calls the function when it updates. The
87 function updates the :class:`DiagnosticStatusWrapper` and collects data.
89 This is useful for gathering information about a device or driver, like temperature,
94 """Constructs a GenericFunctionDiagnosticTask based on the given name and function.
96 :param str name: Name of the function.
97 :param fn: Function to be called when run is called.
99 DiagnosticTask.__init__(self, name)
108 """Merges :class:`CompositeDiagnosticTask` into a single :class:`DiagnosticTask`.
110 The :class:`CompositeDiagnosticTask` allows multiple :class:`DiagnosticTask` instances to
111 be combined into a single task that produces a single
112 :class:`DiagnosticStatusWrapper`. The output of the combination has the max of
113 the status levels, and a concatenation of the non-zero-level messages.
115 For instance, this could be used to combine the calibration and offset data
118 :ivar tasks: List of tasks
119 :vartype tasks: list of :class:`DiagnosticTask`
123 """Constructs a :class:`CompositeDiagnosticTask` with the given name.
125 :param str name: The name of the diagnostic task.
127 DiagnosticTask.__init__(self, name)
135 original_summary.summary(stat)
137 for task
in self.
tasks:
139 stat.summary(original_summary)
141 stat = task.run(stat)
143 combined_summary.mergeSummary(stat)
147 stat.summary(combined_summary)
151 """Adds a child :class:`CompositeDiagnosticTask`.
153 This :class:`CompositeDiagnosticTask` will be called each time this
154 :class:`CompositeDiagnosticTask` is run.
156 :param DiagnosticTask t: the :class:`DiagnosticTask` to add.
163 """Internal use only.
165 Base class for :class:`Updater` and self_test::Dispatcher.
166 The class manages a collection of diagnostic updaters. It contains the
167 common functionality used for producing diagnostic updates and for
170 :ivar tasks: List of tasks
171 :vartype tasks: list of :class:`DiagnosticTask`
172 :ivar threading.Lock lock: The lock protecting the enclosed list of tasks.
176 """Class used to represent a diagnostic task internally in
177 :class:`DiagnosticTaskVector`.
185 stat.name = self.
name
194 """Allows an action to be taken when a task is added. The :class:`Updater` class
195 uses this to immediately publish a diagnostic that says that the node
198 :param DiagnosticTask task: the added task.
203 """Add a task to the :class:`DiagnosticTaskVector`.
207 `add(task)`: where task is a DiagnosticTask
209 `add(name, fn)`: add a DiagnosticTask embodied by a name and function
212 task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0].getName(), args[0].run)
214 task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0], args[1])
217 self.tasks.append(task)
218 self.addedTaskCallback(task)
221 """Removes a task based on its name.
223 Removes the first task that matches the specified name. (New in
226 :param str name: Name of the task to remove.
227 :return: Returns true if a task matched and was removed.
232 for i
in range(len(self.
tasks)):
233 if self.
tasks[i].name == name:
243 """Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
245 This class manages a list of diagnostic tasks. Its update function
246 should be called frequently. At some predetermined rate, the update
247 function will cause all the diagnostic tasks to run, and will collate
248 and publish the resulting diagnostics. The publication rate is
249 determined by the `~diagnostic_period` ros parameter.
251 The class also allows an update to be forced when something significant
252 has happened, and allows a single message to be broadcast on all the
253 diagnostics if normal operation of the node is suspended for some
258 """Constructs an updater class."""
259 DiagnosticTaskVector.__init__(self)
260 self.
publisher = rospy.Publisher(
"/diagnostics", DiagnosticArray, queue_size=10)
271 """Causes the diagnostics to update if the inter-update interval
279 """Forces the diagnostics to update.
281 Useful if the node has undergone a drastic state change that should be
282 published immediately.
286 warn_nohwid = len(self.
hwid)==0
291 for task
in self.
tasks:
293 status.name = task.name
295 status.message =
"No message was set"
296 status.hardware_id = self.
hwid
298 stat = task.run(status)
300 status_vec.append(status)
305 if self.
verbose and status.level:
306 rospy.logwarn(
"Non-zero diagnostic status. Name: '%s', status %i: '%s'" %
307 (status.name, status.level, status.message))
310 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.");
316 """Outputs a message on all the known DiagnosticStatus.
318 Useful if something drastic is happening such as shutdown or a self-test.
320 :param int lvl: Level of the diagnostic being output.
321 :param str msg: Status message to output.
326 for task
in self.
tasks:
328 status.name = task.name
329 status.summary(lvl, msg)
330 status_vec.append(status)
336 :param str hwid: The hardware ID.
341 """Recheck the `~diagnostic_period` on the parameter server."""
349 now = rospy.Time.now()
352 self.
period = rospy.get_param_cached(
"~diagnostic_period", 1)
354 except (httplib.CannotSendRequest, httplib.ResponseNotReady):
358 """Publishes a single diagnostic status or a vector of diagnostic statuses.
360 :param msg: The status(es) to publish.
361 :type msg: diagnostic_msgs.msg.DiagnosticStatus
363 if not type(msg)
is list:
367 stat.name = rospy.get_name()[1:]+
": " + stat.name
369 da = DiagnosticArray()
371 da.header.stamp = rospy.Time.now()
376 stat.name = task.name
377 stat.summary(0,
"Node starting up")