rosdiagnostic.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2017, Clearpath Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of Willow Garage, Inc. nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 import argparse
34 import os
35 import re
36 import rosgraph
37 import rospy
38 import socket
39 import sys
40 
41 from datetime import datetime
42 from dateutil.tz import tzlocal
43 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
44 
45 
46 class ROSTopicException(Exception):
47  """
48  Base exception class of related errors
49  """
50  pass
51 
52 
54  """
55  Errors related to network I/O failures
56  """
57  pass
58 
59 
61  """
62  Make sure that master is available
63  :raises: :exc:`ROSTopicException` If unable to successfully communicate with master
64  """
65  try:
66  rosgraph.Master('/rostopic').getPid()
67  except socket.error:
68  raise ROSTopicIOException("Unable to communicate with master!")
69 
70 
71 class RosDiagnostics(object):
72 
73  DIAG_MSG_LVL_STR_NOCOLOR = {
74  DiagnosticStatus.OK: ' OK ',
75  DiagnosticStatus.WARN: 'WARN ',
76  DiagnosticStatus.ERROR: 'ERROR',
77  DiagnosticStatus.STALE: 'STALE',
78  }
79 
80  DIAG_MSG_LVL_STR_COLOR = {
81  DiagnosticStatus.OK: '\033[92m OK \033[0m',
82  DiagnosticStatus.WARN: '\033[93mWARN \033[0m',
83  DiagnosticStatus.ERROR: '\033[91mERROR\033[0m',
84  DiagnosticStatus.STALE: '\033[94mSTALE\033[0m',
85  }
86 
87  def __init__(self, options):
88  self._lvl_strings_map = self.DIAG_MSG_LVL_STR_NOCOLOR if options.nocolor else self.DIAG_MSG_LVL_STR_COLOR
89  self._options = options
90  rospy.Subscriber(options.topic, DiagnosticArray, self._diag_callback, queue_size=1)
91 
92  def _get_ns(self, name):
93  # Split namespace by slashes, return the base namespace.
94  return '/'.join(name.split('/')[:-1])
95 
96  def _get_non_leaf_statuses(self, statuses):
97  return [self._get_ns(s.name) for s in statuses]
98 
99  def _get_leaf_statuses(self, statuses):
100  parent_namespaces = self._get_non_leaf_statuses(statuses)
101  return [s for s in statuses if s.name not in parent_namespaces]
102 
103  def _print_begin_banner(self, msg):
104  if not self._options.follow:
105  dt = datetime.fromtimestamp(msg.header.stamp.to_sec(), tzlocal())
106  print('=====================================================================')
107  print('Diagnostics generated on: {}'.format(dt))
108  print('---------------------------------------------------------------------')
109 
110  def _print_end_banner(self, msg):
111  if not self._options.follow:
112  print('=====================================================================')
113  rospy.signal_shutdown('Run complete')
114 
115  def _diag_callback(self, msg):
116  prog = re.compile(self._options.filter)
117  self._print_begin_banner(msg)
118  for diag in sorted(self._get_leaf_statuses(msg.status), key=lambda d: d.level, reverse=True):
119  if prog.search(diag.name):
120  self._print_status(diag, msg.header.stamp)
121  self._print_end_banner(msg)
122 
123  def _print_status(self, diag, ts):
124  if self._options.min_level <= diag.level:
125  print('[ {} ] {} - {}'.format(self._lvl_strings_map[diag.level], diag.name, diag.message))
126  if self._options.detail:
127  dt = datetime.fromtimestamp(ts.to_sec(), tzlocal())
128  print(' timestamp: {}'.format(dt))
129  print(' hardware_id: {}'.format(diag.hardware_id))
130  for kv in diag.values:
131  print(' - {}: {}'.format(kv.key, kv.value))
132 
133 
135  parser = argparse.ArgumentParser(
136  description='ROS Diagnostic Viewer is a command-line tool for printing information about ROS Diagnostics.'
137  )
138  parser.add_argument('-f', '--follow', action='store_true', dest='follow',
139  help='follows the diagnostic messages continuously')
140 
141  parser.add_argument('-l', '--level', action='store', metavar='LEVEL', type=int, default=DiagnosticStatus.WARN,
142  dest='min_level',
143  help='the minimum diagnostic level to display (OK=0, WARN=1, ERROR=2, STALE=3) [default=1]')
144 
145  parser.add_argument('--topic', action='store', metavar='TOPIC', type=str, default='/diagnostics_agg', dest='topic',
146  help='topic to read the diagnostics from')
147 
148  parser.add_argument('--filter', action='store', metavar='FILTER', type=str, default='.*', dest='filter',
149  help='regular expression to be applied as a filter to the diagnostic name')
150 
151  parser.add_argument('--nocolor', action='store_true',
152  help='output should not make use of any color')
153 
154  parser.add_argument('-d', '--detail', action='store_true',
155  help='printing the full diagnostic details ')
156 
157  args = parser.parse_args(argv)
158 
159  _check_master()
160  rospy.init_node('rosdiagnostic', anonymous=True)
161  rosdiag = RosDiagnostics(args)
162  rospy.spin()
163  del rosdiag
164 
165 
166 def rosdiagnosticmain(argv=None):
167  if argv is None:
168  argv = sys.argv
169  # filter out remapping arguments in case we are being invoked via roslaunch
170  argv = rospy.myargv(argv)
171 
172  try:
173  _rosdiagnostic_cmd_echo(argv[1:])
174  except socket.error:
175  sys.stderr.write("Network communication failed. Most likely failed to communicate with master.\n")
176  sys.exit(1)
177  except rosgraph.MasterException as e:
178  # mainly for invalid master URI/rosgraph.masterapi
179  sys.stderr.write("ERROR: %s\n" % str(e))
180  sys.exit(1)
181  except ROSTopicException as e:
182  sys.stderr.write("ERROR: %s\n" % str(e))
183  sys.exit(1)
184  except KeyboardInterrupt:
185  pass
186  except rospy.ROSInterruptException:
187  pass
def rosdiagnosticmain(argv=None)


rosdiagnostic
Author(s): Guillaume Autran
autogenerated on Thu Oct 8 2020 03:19:37