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 = 'robot_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_agg_pub')
00050 pub = rospy.Publisher('diagnostics_agg', DiagnosticArray)
00051
00052 statuses = [
00053 [
00054 DiagnosticStatus(1, '/BASE', 'OK', '', []),
00055 DiagnosticStatus(0, '/BASE/group1', 'OK', '', []),
00056 DiagnosticStatus(1, '/BASE/group1/item1', 'Warning', '', []),
00057 DiagnosticStatus(0, '/BASE/group1/item2', 'OK', '', []),
00058
00059 DiagnosticStatus(0, '/BASE/group2', 'OK', '', []),
00060 DiagnosticStatus(0, '/BASE/group2/item1', 'OK', '', []),
00061 DiagnosticStatus(1, '/BASE/group2/item2', 'Warning', '', []),
00062
00063 DiagnosticStatus(2, '/BASE2', 'OK', '', []),
00064 DiagnosticStatus(2, '/BASE2/group3', 'OK', '', []),
00065 DiagnosticStatus(0, '/BASE2/group3/item1', 'OK', '', []),
00066 DiagnosticStatus(2, '/BASE2/group3/item2', 'Error', '', [])
00067 ],
00068
00069 [
00070 DiagnosticStatus(1, '/BASE', 'OK', '', []),
00071 DiagnosticStatus(1, '/BASE/group1/item1', 'Warning', '', []),
00072 DiagnosticStatus(0, '/BASE/group1/item2', 'OK', '', []),
00073
00074 DiagnosticStatus(0, '/BASE/group2', 'OK', '', []),
00075 DiagnosticStatus(0, '/BASE/group2/item1', 'OK', '', []),
00076
00077 DiagnosticStatus(2, '/BASE2', 'OK', '', []),
00078 DiagnosticStatus(2, '/BASE2/group3', 'OK', '', []),
00079 DiagnosticStatus(2, '/BASE2/group3/item2', 'Error', '', []),
00080
00081
00082 DiagnosticStatus(0, '/BASE3/group1', 'OK', '', []),
00083 DiagnosticStatus(0, '/BASE3/group1/item2', 'Error', '', [])
00084 ]
00085 ]
00086
00087 array = DiagnosticArray()
00088
00089 array.header.stamp = rospy.get_rostime()
00090
00091 i = 0
00092 ind = 0
00093 while not rospy.is_shutdown():
00094 old_ind = ind
00095 ind = 0
00096 if (i % 10 > 5):
00097 ind = 1
00098 i = i + 1
00099
00100 if (old_ind != ind):
00101 print "switched", ind
00102
00103 array.status = statuses[ind]
00104 pub.publish(array)
00105 sleep(1)