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
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 PKG = 'runtime_monitor'
00040
00041 import roslib; roslib.load_manifest(PKG)
00042
00043 import rospy
00044 from time import sleep
00045
00046 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00047
00048 if __name__ == '__main__':
00049 rospy.init_node('diag_pub')
00050 pub = rospy.Publisher('/diagnostics', DiagnosticArray)
00051
00052 start_time = rospy.get_time()
00053
00054 while not rospy.is_shutdown():
00055 array = DiagnosticArray()
00056 array.status = [
00057 DiagnosticStatus(0, 'EtherCAT Device (fl_caster_l_wheel_motor)', 'OK', '', []),
00058 DiagnosticStatus(0, 'EtherCAT Device (fl_caster_r_wheel_motor)', 'OK', '', []),
00059 DiagnosticStatus(0, 'EtherCAT Device (fl_caster_rotation_motor)', 'OK', '', []),
00060 DiagnosticStatus(2, 'EtherCAT Device (fr_caster_l_wheel_motor)', 'Motor model', '', []),
00061 DiagnosticStatus(1, 'EtherCAT Device (fr_caster_r_wheel_motor)', 'High temperature', '', []),
00062 DiagnosticStatus(0, 'EtherCAT Device (fr_caster_rotation_motor)', 'OK', '', []),
00063
00064 DiagnosticStatus(0, 'tilt_hokuyo_node: Frequency Status', 'OK', '', []),
00065 DiagnosticStatus(0, 'tilt_hokuyo_node: Connection Status', 'OK', '', []),
00066 DiagnosticStatus(0, 'base_hokuyo_node: Frequency Status', 'OK', '', []),
00067 DiagnosticStatus(0, 'base_hokuyo_node: Connection Status', 'OK', '', []),
00068
00069 DiagnosticStatus(0, 'Joint (fl_caster_l_wheel_joint)', 'OK', '', []),
00070 DiagnosticStatus(0, 'Joint (fl_caster_r_wheel_joint)', 'OK', '', []),
00071 DiagnosticStatus(1, 'Joint (fl_caster_rotation_joint)', 'Uncalibrated', '', []),
00072 DiagnosticStatus(1, 'Joint (fr_caster_l_wheel_joint)', 'Uncalibrated', '', []),
00073 DiagnosticStatus(0, 'Joint (fr_caster_r_wheel_joint)', 'OK', '', []),
00074 DiagnosticStatus(0, 'Joint (fr_caster_rotation_joint)', 'OK', '', [])]
00075 array.header.stamp = rospy.get_rostime()
00076
00077
00078 if rospy.get_time() - start_time > 5:
00079 array.status.append(DiagnosticStatus(2, 'EtherCAT Device (fr_caster_l_wheel_motor)', 'Motor model', '', []))
00080 else:
00081 array.status.append(DiagnosticStatus(0, 'EtherCAT Device (fr_caster_l_wheel_motor)', 'OK', '', []))
00082
00083 pub.publish(array)
00084 sleep(1)