_diagnostic_updater.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 # -*- coding: utf-8 -*-
34 
35 """ diagnostic_updater for Python.
36 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
37 """
38 
39 import rospy
40 import threading
41 from diagnostic_msgs.msg import DiagnosticArray
42 
43 try:
44  import httplib
45 except ImportError:
46  import http.client as httplib
47 
48 from ._diagnostic_status_wrapper import *
49 
51  """DiagnosticTask is an abstract base class for collecting diagnostic data.
52 
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`.
56  """
57 
58  def __init__(self, name):
59  """Constructs a :class:`DiagnosticTask` setting its name in the process.
60 
61  :param str name: The name of the diagnostic task.
62  """
63  self.name = name
64 
65  def getName(self):
66  """Returns the name of the :class:`DiagnosticTask`.
67 
68  :rtype: str
69  """
70  return self.name
71 
72  def run(self, stat):
73  """Fills out this Task's :class:`DiagnosticStatusWrapper`.
74 
75  :param DiagnosticStatusWrapper stat: the :class:`DiagnosticStatusWrapper` to fill
76  :return: the filled :class:`DiagnosticStatusWrapper`
77  :rtype: DiagnosticStatusWrapper
78  """
79  return stat
80 
81 
82 
84  """A :class:`DiagnosticTask` based on a function.
85 
86  The :class:`FunctionDiagnosticTask` calls the function when it updates. The
87  function updates the :class:`DiagnosticStatusWrapper` and collects data.
88 
89  This is useful for gathering information about a device or driver, like temperature,
90  calibration, etc.
91  """
92 
93  def __init__(self, name, fn):
94  """Constructs a GenericFunctionDiagnosticTask based on the given name and function.
95 
96  :param str name: Name of the function.
97  :param fn: Function to be called when run is called.
98  """
99  DiagnosticTask.__init__(self, name)
100  self.fn = fn
101 
102  def run(self, stat):
103  return self.fn(stat)
104 
105 
106 
108  """Merges :class:`CompositeDiagnosticTask` into a single :class:`DiagnosticTask`.
109 
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.
114 
115  For instance, this could be used to combine the calibration and offset data
116  from an IMU driver.
117 
118  :ivar tasks: List of tasks
119  :vartype tasks: list of :class:`DiagnosticTask`
120  """
121 
122  def __init__(self, name):
123  """Constructs a :class:`CompositeDiagnosticTask` with the given name.
124 
125  :param str name: The name of the diagnostic task.
126  """
127  DiagnosticTask.__init__(self, name)
128 
129  self.tasks = []
130 
131  def run(self, stat):
132  combined_summary = DiagnosticStatusWrapper()
133  original_summary = DiagnosticStatusWrapper()
134 
135  original_summary.summary(stat)
136 
137  for task in self.tasks:
138  # Put the summary that was passed in.
139  stat.summary(original_summary)
140  # Let the next task add entries and put its summary.
141  stat = task.run(stat)
142  # Merge the new summary into the combined summary.
143  combined_summary.mergeSummary(stat)
144 
145 
146  # Copy the combined summary into the output.
147  stat.summary(combined_summary)
148  return stat
149 
150  def addTask(self, t):
151  """Adds a child :class:`CompositeDiagnosticTask`.
152 
153  This :class:`CompositeDiagnosticTask` will be called each time this
154  :class:`CompositeDiagnosticTask` is run.
155 
156  :param DiagnosticTask t: the :class:`DiagnosticTask` to add.
157  """
158  self.tasks.append(t)
159 
160 
161 
163  """Internal use only.
164 
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
168  self-tests.
169 
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.
173  """
174 
176  """Class used to represent a diagnostic task internally in
177  :class:`DiagnosticTaskVector`.
178  """
179 
180  def __init__(self, name, fn):
181  self.name = name
182  self.fn = fn
183 
184  def run(self, stat):
185  stat.name = self.name
186  return self.fn(stat)
187 
188 
189  def __init__(self):
190  self.tasks = []
191  self.lock = threading.Lock()
192 
193  def addedTaskCallback(self, task):
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
196  is loading.
197 
198  :param DiagnosticTask task: the added task.
199  """
200  pass
201 
202  def add(self, *args):
203  """Add a task to the :class:`DiagnosticTaskVector`.
204 
205  Usage:
206 
207  `add(task)`: where task is a DiagnosticTask
208 
209  `add(name, fn)`: add a DiagnosticTask embodied by a name and function
210  """
211  if len(args)==1:
212  task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0].getName(), args[0].run)
213  elif len(args)==2:
214  task = DiagnosticTaskVector.DiagnosticTaskInternal(args[0], args[1])
215 
216  with self.lock:
217  self.tasks.append(task)
218  self.addedTaskCallback(task)
219 
220  def removeByName(self, name):
221  """Removes a task based on its name.
222 
223  Removes the first task that matches the specified name. (New in
224  version 1.1.2)
225 
226  :param str name: Name of the task to remove.
227  :return: Returns true if a task matched and was removed.
228  :rtype: bool
229  """
230  found = False
231  with self.lock:
232  for i in range(len(self.tasks)):
233  if self.tasks[i].name == name:
234  self.tasks.pop(i)
235  found = True
236  break
237  return found
238 
239 
240 
241 
243  """Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
244 
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.
250 
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
254  reason.
255  """
256 
257  def __init__(self):
258  """Constructs an updater class."""
259  DiagnosticTaskVector.__init__(self)
260  self.publisher = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=10)
261 
262  self.last_time = rospy.Time.now()
264  self.period = 1
265 
266  self.verbose = False
267  self.hwid = ""
268  self.warn_nohwid_done = False
269 
270  def update(self):
271  """Causes the diagnostics to update if the inter-update interval
272  has been exceeded.
273  """
275  if rospy.Time.now() >= self.last_time + rospy.Duration(self.period):
276  self.force_update()
277 
278  def force_update(self):
279  """Forces the diagnostics to update.
280 
281  Useful if the node has undergone a drastic state change that should be
282  published immediately.
283  """
284  self.last_time = rospy.Time.now()
285 
286  warn_nohwid = len(self.hwid)==0
287 
288  status_vec = []
289 
290  with self.lock: # Make sure no adds happen while we are processing here.
291  for task in self.tasks:
292  status = DiagnosticStatusWrapper()
293  status.name = task.name
294  status.level = 2
295  status.message = "No message was set"
296  status.hardware_id = self.hwid
297 
298  stat = task.run(status)
299 
300  status_vec.append(status)
301 
302  if status.level:
303  warn_nohwid = False
304 
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))
308 
309  if warn_nohwid and not self.warn_nohwid_done:
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.");
311  self.warn_nohwid_done = True
312 
313  self.publish(status_vec)
314 
315  def broadcast(self, lvl, msg):
316  """Outputs a message on all the known DiagnosticStatus.
317 
318  Useful if something drastic is happening such as shutdown or a self-test.
319 
320  :param int lvl: Level of the diagnostic being output.
321  :param str msg: Status message to output.
322  """
323 
324  status_vec = []
325 
326  for task in self.tasks:
327  status = DiagnosticStatusWrapper()
328  status.name = task.name
329  status.summary(lvl, msg)
330  status_vec.append(status)
331 
332  self.publish(status_vec)
333 
334  def setHardwareID(self, hwid):
335  """
336  :param str hwid: The hardware ID.
337  """
338  self.hwid = hwid
339 
341  """Recheck the `~diagnostic_period` on the parameter server."""
342 
343  # This was getParamCached() call in the cpp code. i.e. it would throttle
344  # the actual call to the parameter server using a notification of change
345  # mechanism.
346  # This is not available in rospy. Hence I throttle the call to the
347  # parameter server using a standard timeout mechanism (4Hz)
348 
349  now = rospy.Time.now()
350  if now >= self.last_time_period_checked + rospy.Duration(0.25):
351  try:
352  self.period = rospy.get_param_cached("~diagnostic_period", 1)
353  self.last_time_period_checked = now
354  except (httplib.CannotSendRequest, httplib.ResponseNotReady):
355  pass
356 
357  def publish(self, msg):
358  """Publishes a single diagnostic status or a vector of diagnostic statuses.
359 
360  :param msg: The status(es) to publish.
361  :type msg: diagnostic_msgs.msg.DiagnosticStatus
362  """
363  if not type(msg) is list:
364  msg = [msg]
365 
366  for stat in msg:
367  stat.name = rospy.get_name()[1:]+ ": " + stat.name
368 
369  da = DiagnosticArray()
370  da.status = msg
371  da.header.stamp = rospy.Time.now() # Add timestamp for ROS 0.10
372  self.publisher.publish(da)
373 
374  def addedTaskCallback(self, task):
375  stat = DiagnosticStatusWrapper()
376  stat.name = task.name
377  stat.summary(0, "Node starting up")
378  self.publish(stat)
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask.addTask
def addTask(self, t)
Definition: _diagnostic_updater.py:150
diagnostic_updater._diagnostic_updater.Updater.addedTaskCallback
def addedTaskCallback(self, task)
Definition: _diagnostic_updater.py:374
diagnostic_updater._diagnostic_updater.Updater.broadcast
def broadcast(self, lvl, msg)
Definition: _diagnostic_updater.py:315
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask.__init__
def __init__(self, name)
Definition: _diagnostic_updater.py:122
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.DiagnosticTaskInternal
Definition: _diagnostic_updater.py:175
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.DiagnosticTaskInternal.name
name
Definition: _diagnostic_updater.py:181
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.removeByName
def removeByName(self, name)
Definition: _diagnostic_updater.py:220
diagnostic_updater._diagnostic_updater.DiagnosticTask
Definition: _diagnostic_updater.py:50
diagnostic_updater._diagnostic_updater.FunctionDiagnosticTask.fn
fn
Definition: _diagnostic_updater.py:100
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper
Definition: _diagnostic_status_wrapper.py:46
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.DiagnosticTaskInternal.__init__
def __init__(self, name, fn)
Definition: _diagnostic_updater.py:180
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask
Definition: _diagnostic_updater.py:107
diagnostic_updater._diagnostic_updater.FunctionDiagnosticTask.run
def run(self, stat)
Definition: _diagnostic_updater.py:102
diagnostic_updater._diagnostic_updater.Updater.last_time_period_checked
last_time_period_checked
Definition: _diagnostic_updater.py:263
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.tasks
tasks
Definition: _diagnostic_updater.py:190
diagnostic_updater._diagnostic_updater.FunctionDiagnosticTask.__init__
def __init__(self, name, fn)
Definition: _diagnostic_updater.py:93
diagnostic_updater._diagnostic_updater.Updater.publish
def publish(self, msg)
Definition: _diagnostic_updater.py:357
diagnostic_updater._diagnostic_updater.Updater.hwid
hwid
Definition: _diagnostic_updater.py:267
diagnostic_updater._diagnostic_updater.Updater
Definition: _diagnostic_updater.py:242
diagnostic_updater._diagnostic_updater.Updater.update
def update(self)
Definition: _diagnostic_updater.py:270
diagnostic_updater._diagnostic_updater.DiagnosticTask.__init__
def __init__(self, name)
Definition: _diagnostic_updater.py:58
diagnostic_updater._diagnostic_updater.Updater.__init__
def __init__(self)
Definition: _diagnostic_updater.py:257
diagnostic_updater._diagnostic_updater.DiagnosticTask.getName
def getName(self)
Definition: _diagnostic_updater.py:65
diagnostic_updater._diagnostic_updater.Updater.setHardwareID
def setHardwareID(self, hwid)
Definition: _diagnostic_updater.py:334
diagnostic_updater._diagnostic_updater.Updater.verbose
verbose
Definition: _diagnostic_updater.py:266
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask.tasks
tasks
Definition: _diagnostic_updater.py:129
diagnostic_updater._diagnostic_updater.Updater.force_update
def force_update(self)
Definition: _diagnostic_updater.py:278
diagnostic_updater._diagnostic_updater.Updater.warn_nohwid_done
warn_nohwid_done
Definition: _diagnostic_updater.py:268
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.addedTaskCallback
def addedTaskCallback(self, task)
Definition: _diagnostic_updater.py:193
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.add
def add(self, *args)
Definition: _diagnostic_updater.py:202
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.lock
lock
Definition: _diagnostic_updater.py:191
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector
Definition: _diagnostic_updater.py:162
diagnostic_updater._diagnostic_updater.Updater.publisher
publisher
Definition: _diagnostic_updater.py:260
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.DiagnosticTaskInternal.fn
fn
Definition: _diagnostic_updater.py:182
diagnostic_updater._diagnostic_updater.DiagnosticTask.name
name
Definition: _diagnostic_updater.py:63
diagnostic_updater._diagnostic_updater.CompositeDiagnosticTask.run
def run(self, stat)
Definition: _diagnostic_updater.py:131
diagnostic_updater._diagnostic_updater.Updater._check_diagnostic_period
def _check_diagnostic_period(self)
Definition: _diagnostic_updater.py:340
diagnostic_updater._diagnostic_updater.Updater.last_time
last_time
Definition: _diagnostic_updater.py:262
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.__init__
def __init__(self)
Definition: _diagnostic_updater.py:189
diagnostic_updater._diagnostic_updater.FunctionDiagnosticTask
Definition: _diagnostic_updater.py:83
diagnostic_updater._diagnostic_updater.DiagnosticTask.run
def run(self, stat)
Definition: _diagnostic_updater.py:72
diagnostic_updater._diagnostic_updater.DiagnosticTaskVector.DiagnosticTaskInternal.run
def run(self, stat)
Definition: _diagnostic_updater.py:184
diagnostic_updater._diagnostic_updater.Updater.period
period
Definition: _diagnostic_updater.py:264


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Tue May 6 2025 02:17:37