joints_to_diagnostics.py
Go to the documentation of this file.
1 #! /usr/bin/python
2 # Copyright (c) 2009, Willow Garage, Inc.
3 # All rights reserved.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above copyright
11 # notice, this list of conditions and the following disclaimer in the
12 # documentation and/or other materials provided with the distribution.
13 # * Neither the name of the Willow Garage, Inc. nor the names of its
14 # contributors may be used to endorse or promote products derived from
15 # this software without specific prior written permission.
16 #
17 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 # POSSIBILITY OF SUCH DAMAGE.
28 
29 from __future__ import with_statement
30 
31 import sys
32 import rospy
33 
34 from sr_robot_msgs.msg import MechanismStatistics
35 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
36 
37 import math
38 
39 import threading
40 mutex = threading.Lock()
41 
42 has_warned_invalid = False
43 
44 # Math.isnan is new in python 2.6, need to check version
45 
46 check_nan = False
47 my_version = sys.version_info
48 if my_version[0] == 2 and my_version[1] >= 6:
49  check_nan = True
50 
51 
52 def joint_to_diag(js):
53  global has_warned_invalid
54  ds = DiagnosticStatus()
55  ds.level = DiagnosticStatus.OK
56  ds.message = 'OK'
57 
58  # Hack to stop gripper joints from being "uncalibrated"
59  if not js.is_calibrated and js.name.find("float") < 0 and js.name.find("finger") < 0:
60  ds.level = DiagnosticStatus.WARN
61  ds.message = 'Uncalibrated'
62 
63  if check_nan and (math.isnan(js.position) or math.isnan(js.velocity) or
64  math.isnan(js.measured_effort) or math.isnan(js.commanded_effort)):
65  ds.level = DiagnosticStatus.ERROR
66  ds.message = 'NaN in joint data'
67  if not has_warned_invalid:
68  rospy.logerr(
69  "NaN value for joint data. controller_manager restart required.")
70  has_warned_invalid = True
71 
72  if check_nan and (math.isinf(js.position) or math.isinf(js.velocity) or
73  math.isinf(js.measured_effort) or math.isinf(js.commanded_effort)):
74  ds.level = DiagnosticStatus.ERROR
75  ds.message = 'Inf in joint data'
76  if not has_warned_invalid:
77  rospy.logerr(
78  "Infinite value for joint data. controller_manager restart required.")
79  has_warned_invalid = True
80 
81  ds.name = "Joint (%s)" % js.name
82  ds.values = [
83  KeyValue('Position', str(js.position)),
84  KeyValue('Velocity', str(js.velocity)),
85  KeyValue('Measured Effort', str(js.measured_effort)),
86  KeyValue('Commanded Effort', str(js.commanded_effort)),
87  KeyValue('Calibrated', str(js.is_calibrated)),
88  KeyValue('Odometer', str(js.odometer)),
89  KeyValue('Max Position', str(js.max_position)),
90  KeyValue('Min Position', str(js.min_position)),
91  KeyValue('Max Abs. Velocity', str(js.max_abs_velocity)),
92  KeyValue('Max Abs. Effort', str(js.max_abs_effort)),
93  KeyValue('Limits Hit', str(js.violated_limits))]
94 
95  return ds
96 
97 
98 rospy.init_node('joints_to_diagnostics')
99 
100 last_msg = None
101 last_update_time = 0
102 
103 
104 def state_cb(msg):
105  with mutex:
106  global last_msg, last_update_time
107  last_msg = msg
108  last_update_time = rospy.get_time()
109 
110 
112  with mutex:
113  global last_msg, last_update_time
114  if last_msg is None:
115  return
116 
117  # Don't publish anything without updates
118  if rospy.get_time() - last_update_time > 3:
119  return
120 
121  d = DiagnosticArray()
122  d.header.stamp = last_msg.header.stamp
123  if last_msg.joint_statistics == []:
124  ds = DiagnosticStatus()
125  ds.level = 0
126  ds.message = 'No Joint states from controller manager'
127  ds.name = "Joints: none"
128  d.status = [ds]
129  else:
130  d.status = [joint_to_diag(js) for js in last_msg.joint_statistics]
131  pub_diag.publish(d)
132 
133 pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray)
134 rospy.Subscriber('mechanism_statistics', MechanismStatistics, state_cb)
135 
136 my_rate = rospy.Rate(1.0)
137 while not rospy.is_shutdown():
138  my_rate.sleep()
139  publish_diags()


sr_edc_controller_configuration
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:53