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 = 'diagnostic_aggregator'
00040
00041 import roslib; roslib.load_manifest(PKG)
00042
00043
00044 import rospy
00045 from time import sleep
00046
00047 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00048
00049 if __name__ == '__main__':
00050 rospy.init_node('diag_pub')
00051 pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=10)
00052
00053 array = DiagnosticArray()
00054 array.status = [
00055
00056 DiagnosticStatus(0, 'pref1a', 'OK', '', []),
00057 DiagnosticStatus(1, 'pref1b', 'Warning', '', []),
00058 DiagnosticStatus(0, 'contains1a', 'OK', '', []),
00059 DiagnosticStatus(0, 'prefix1: contains1b', 'OK', '', []),
00060 DiagnosticStatus(0, 'name1', 'OK', '', []),
00061 DiagnosticStatus(0, 'prefix1: expected1a', 'OK', '', []),
00062 DiagnosticStatus(0, 'prefix1: expected1b', 'OK', '', []),
00063 DiagnosticStatus(0, 'prefix1: expected1c', 'OK', '', []),
00064 DiagnosticStatus(0, 'prefix1: expected1d', 'OK', '', []),
00065 DiagnosticStatus(0, 'find1_items: find_remove1a', 'OK', '', []),
00066 DiagnosticStatus(0, 'find1_items: find_remove1b', 'OK', '', []),
00067
00068
00069 DiagnosticStatus(0, 'contain2a', 'OK', '', []),
00070 DiagnosticStatus(0, 'contain2b', 'OK', '', []),
00071 DiagnosticStatus(0, 'name2', 'OK', '', []),
00072
00073
00074 DiagnosticStatus(2, 'other1', 'Error', '', []),
00075 DiagnosticStatus(0, 'other2', 'OK', '', []),
00076 DiagnosticStatus(0, 'other3', 'OK', '', [])]
00077 array.header.stamp = rospy.get_rostime()
00078
00079 while not rospy.is_shutdown():
00080 pub.publish(array)
00081 sleep(1)