29 from __future__
import with_statement
34 from sr_robot_msgs.msg
import MechanismStatistics
35 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus, KeyValue
40 mutex = threading.Lock()
42 has_warned_invalid =
False 47 my_version = sys.version_info
48 if my_version[0] == 2
and my_version[1] >= 6:
53 global has_warned_invalid
54 ds = DiagnosticStatus()
55 ds.level = DiagnosticStatus.OK
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' 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:
69 "NaN value for joint data. controller_manager restart required.")
70 has_warned_invalid =
True 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:
78 "Infinite value for joint data. controller_manager restart required.")
79 has_warned_invalid =
True 81 ds.name =
"Joint (%s)" % js.name
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))]
98 rospy.init_node(
'joints_to_diagnostics')
106 global last_msg, last_update_time
108 last_update_time = rospy.get_time()
113 global last_msg, last_update_time
118 if rospy.get_time() - last_update_time > 3:
121 d = DiagnosticArray()
122 d.header.stamp = last_msg.header.stamp
123 if last_msg.joint_statistics == []:
124 ds = DiagnosticStatus()
126 ds.message =
'No Joint states from controller manager' 127 ds.name =
"Joints: none" 130 d.status = [
joint_to_diag(js)
for js
in last_msg.joint_statistics]
133 pub_diag = rospy.Publisher(
'/diagnostics', DiagnosticArray)
134 rospy.Subscriber(
'mechanism_statistics', MechanismStatistics, state_cb)
136 my_rate = rospy.Rate(1.0)
137 while not rospy.is_shutdown():