_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 DiagnosticStatus.
75 
76  Usage:
77  summary(diagnostic_status): Copies the summary from a DiagnosticStatus message
78  summary(lvl,msg): sets from lvl and messages
79  """
80  if len(args)==1:
81  self.level = args[0].level
82  self.message = args[0].message
83  elif len(args)==2:
84  self.level = args[0]
85  self.message = str(args[1])
86 
87 
88  def clearSummary(self):
89  """ Clears the summary, setting the level to zero and the message to "".
90  """
91  self.summary(0, "")
92 
93 
94  def mergeSummary(self, *args):
95  """ Merges a level and message with the existing ones.
96 
97  It is sometimes useful to merge two DiagnosticStatus messages. In that case,
98  the key value pairs can be unioned, but the level and summary message
99  have to be merged more intelligently. This function does the merge in
100  an intelligent manner, combining the summary in *this, with the one
101  that is passed in.
102 
103  The combined level is the greater of the two levels to be merged.
104  If both levels are non-zero (not OK), the messages are combined with a
105  semicolon separator. If only one level is zero, and the other is
106  non-zero, the message for the zero level is discarded. If both are
107  zero, the new message is ignored.
108 
109  Usage:
110  mergeSummary(diagnostic_status): merge from a DiagnosticStatus message
111  mergeSummary(lvl,msg): sets from lvl and msg
112  """
113  if len(args)==1:
114  lvl = args[0].level
115  msg = args[0].message
116  elif len(args)==2:
117  lvl = args[0]
118  msg = args[1]
119 
120  if (lvl>0) == (self.level>0):
121  if len(self.message)>0:
122  self.message += "; "
123  self.message += msg
124  elif lvl > self.level:
125  self.message = msg
126 
127  if lvl > self.level:
128  self.level = lvl
129 
130 
131  def add(self, key, val):
132  """ Add a key-value pair.
133 
134  This method adds a key-value pair. Any type that has a << stream
135  operator can be passed as the second argument. Formatting is done
136  using a std::stringstream.
137 
138  @type key string
139  @param key Key to be added.
140  @type value string
141  @param value Value to be added.
142  """
143  self.values.append(KeyValue(key,str(val)))
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.clearSummary
def clearSummary(self)
Definition: _diagnostic_status_wrapper.py:88
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:131
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.mergeSummary
def mergeSummary(self, *args)
Definition: _diagnostic_status_wrapper.py:94
diagnostic_updater._diagnostic_status_wrapper.DiagnosticStatusWrapper.message
message
Definition: _diagnostic_status_wrapper.py:82
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:81


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Tue Nov 15 2022 03:17:19