Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 from __future__ import with_statement
00030
00031 import roslib; roslib.load_manifest('pr2_controller_manager')
00032 import rospy
00033
00034 from pr2_mechanism_msgs.msg import MechanismStatistics
00035 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00036
00037 import math
00038
00039 import threading
00040 mutex = threading.Lock()
00041
00042 has_warned_invalid = False
00043
00044
00045 import sys
00046 check_nan = False
00047 my_version = sys.version_info
00048 if my_version[0] == 2 and my_version[1] >= 6:
00049 check_nan = True
00050
00051 def joint_to_diag(js):
00052 global has_warned_invalid
00053 ds = DiagnosticStatus()
00054 ds.level = DiagnosticStatus.OK
00055 ds.message = 'OK'
00056
00057
00058 if not js.is_calibrated and js.name.find("float") < 0 and js.name.find("finger") < 0:
00059 ds.level = DiagnosticStatus.WARN
00060 ds.message = 'Uncalibrated'
00061
00062 if check_nan and (math.isnan(js.position) or math.isnan(js.velocity) or \
00063 math.isnan(js.measured_effort) or math.isnan(js.commanded_effort)):
00064 ds.level = DiagnosticStatus.ERROR
00065 ds.message = 'NaN in joint data'
00066 if not has_warned_invalid:
00067 rospy.logerr("NaN value for joint data. pr2_controller_manager restart required.")
00068 has_warned_invalid = True
00069
00070 if check_nan and (math.isinf(js.position) or math.isinf(js.velocity) or \
00071 math.isinf(js.measured_effort) or math.isinf(js.commanded_effort)):
00072 ds.level = DiagnosticStatus.ERROR
00073 ds.message = 'Inf in joint data'
00074 if not has_warned_invalid:
00075 rospy.logerr("Infinite value for joint data. pr2_controller_manager restart required.")
00076 has_warned_invalid = True
00077
00078 ds.name = "Joint (%s)" % js.name
00079 ds.values = [
00080 KeyValue('Position', str(js.position)),
00081 KeyValue('Velocity', str(js.velocity)),
00082 KeyValue('Measured Effort', str(js.measured_effort)),
00083 KeyValue('Commanded Effort', str(js.commanded_effort)),
00084 KeyValue('Calibrated', str(js.is_calibrated)),
00085 KeyValue('Odometer', str(js.odometer)),
00086 KeyValue('Max Position', str(js.max_position)),
00087 KeyValue('Min Position', str(js.min_position)),
00088 KeyValue('Max Abs. Velocity', str(js.max_abs_velocity)),
00089 KeyValue('Max Abs. Effort', str(js.max_abs_effort)),
00090 KeyValue('Limits Hit', str(js.violated_limits)) ]
00091
00092 return ds
00093
00094
00095 rospy.init_node('joints_to_diagnostics')
00096
00097 last_msg = None
00098 last_update_time = 0
00099 def state_cb(msg):
00100 with mutex:
00101 global last_msg, last_update_time
00102 last_msg = msg
00103 last_update_time = rospy.get_time()
00104
00105 def publish_diags():
00106 with mutex:
00107 global last_msg, last_update_time
00108 if last_msg is None:
00109 return
00110
00111
00112 if rospy.get_time() - last_update_time > 3:
00113 return
00114
00115 d = DiagnosticArray()
00116 d.header.stamp = last_msg.header.stamp
00117 if last_msg.joint_statistics == []:
00118 ds = DiagnosticStatus()
00119 ds.level = 0
00120 ds.message = 'No Joint states from controller manager'
00121 ds.name = "Joints: none"
00122 d.status = [ds]
00123 else:
00124 d.status = [joint_to_diag(js) for js in last_msg.joint_statistics]
00125 pub_diag.publish(d)
00126
00127 pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray)
00128 rospy.Subscriber('mechanism_statistics', MechanismStatistics, state_cb)
00129
00130 my_rate = rospy.Rate(1.0)
00131 while not rospy.is_shutdown():
00132 my_rate.sleep()
00133 publish_diags()
00134
00135