_diagnostic_status_wrapper.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 from diagnostic_msgs.msg import DiagnosticStatus, KeyValue
41 
42 OK = DiagnosticStatus.OK
43 WARN = DiagnosticStatus.WARN
44 ERROR = DiagnosticStatus.ERROR
45 
46 class DiagnosticStatusWrapper(DiagnosticStatus):
47  """ Wrapper for the :diagnostic_msgs:`DiagnosticStatus` message that makes it
48  easier to update.
49 
50  This class handles common string formatting and vector handling issues
51  for filling the :diagnostic_msgs:`DiagnosticStatus` message. It is a subclass of
52  :diagnostic_msgs:`DiagnosticStatus`, so it can be passed directly to
53  diagnostic publish calls.
54  """
55 
56  def __init__(self, *args, **kwds):
57  """
58  Constructor. Any message fields that are implicitly/explicitly
59  set to None will be assigned a default value. The recommend
60  use is keyword arguments as this is more robust to future message
61  changes. You cannot mix in-order arguments and keyword arguments.
62 
63  The available fields are:
64  level,name,message,hardware_id,values
65 
66  :param args: complete set of field values, in .msg order
67  :param kwds: use keyword arguments corresponding to message field names
68  to set specific fields.
69  """
70  DiagnosticStatus.__init__(self, *args, **kwds)
71 
72 
73  def summary(self, *args):
74  """ Fills out the level and message fields of the :diagnostic_msgs:`DiagnosticStatus`.
75 
76  Usage:
77 
78  `summary(diagnostic_status)`: Copies the summary from a :diagnostic_msgs:`DiagnosticStatus` message
79 
80  `summary(lvl,msg)`: sets from lvl and messages
81  """
82  if len(args)==1:
83  self.level = args[0].level
84  self.message = args[0].message
85  elif len(args)==2:
86  self.level = args[0]
87  self.message = str(args[1])
88 
89 
90  def clearSummary(self):
91  """ Clears the summary, setting the level to zero and the message to "".
92  """
93  self.summary(0, "")
94 
95 
96  def mergeSummary(self, *args):
97  """ Merges a level and message with the existing ones.
98 
99  It is sometimes useful to merge two :diagnostic_msgs:`DiagnosticStatus` messages. In that case,
100  the key value pairs can be unioned, but the level and summary message
101  have to be merged more intelligently. This function does the merge in
102  an intelligent manner, combining the summary in this, with the one
103  that is passed in.
104 
105  The combined level is the greater of the two levels to be merged.
106  If both levels are non-zero (not OK), the messages are combined with a
107  semicolon separator. If only one level is zero, and the other is
108  non-zero, the message for the zero level is discarded. If both are
109  zero, the new message is ignored.
110 
111  Usage:
112 
113  `mergeSummary(diagnostic_status)`: merge from a :diagnostic_msgs:`DiagnosticStatus` message
114 
115  `mergeSummary(lvl,msg)`: sets from lvl and msg
116  """
117  if len(args)==1:
118  lvl = args[0].level
119  msg = args[0].message
120  elif len(args)==2:
121  lvl = args[0]
122  msg = args[1]
123 
124  if (lvl>0) == (self.level>0):
125  if len(self.message)>0:
126  self.message += "; "
127  self.message += msg
128  elif lvl > self.level:
129  self.message = msg
130 
131  if lvl > self.level:
132  self.level = lvl
133 
134 
135  def add(self, key, val):
136  """ Add a key-value pair.
137 
138  This method adds a key-value pair.
139 
140  :type key: string
141  :param key: Key to be added.
142  :type any: string
143  :param value: Value to be added.
144  """
145  self.values.append(KeyValue(key,str(val)))
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.clearSummary
def clearSummary(self)
Definition: _diagnostic_status_wrapper.py:90
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper
Definition: _diagnostic_status_wrapper.py:46
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.add
def add(self, key, val)
Definition: _diagnostic_status_wrapper.py:135
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.mergeSummary
def mergeSummary(self, *args)
Definition: _diagnostic_status_wrapper.py:96
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.message
message
Definition: _diagnostic_status_wrapper.py:84
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.__init__
def __init__(self, *args, **kwds)
Definition: _diagnostic_status_wrapper.py:56
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.summary
def summary(self, *args)
Definition: _diagnostic_status_wrapper.py:73
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.level
level
Definition: _diagnostic_status_wrapper.py:83


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