39 PKG =
'diagnostic_aggregator'
41 import roslib; roslib.load_manifest(PKG)
45 from time
import sleep
47 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus
49 if __name__ ==
'__main__':
50 rospy.init_node(
'diag_pub')
51 pub = rospy.Publisher(
'/diagnostics', DiagnosticArray, queue_size=10)
53 start_time = rospy.get_time()
55 while not rospy.is_shutdown():
56 array = DiagnosticArray()
59 DiagnosticStatus(0,
'expected1',
'OK',
'', []),
60 DiagnosticStatus(1,
'expected2',
'OK',
'', []),
61 DiagnosticStatus(2,
'expected3',
'OK',
'', []),
63 DiagnosticStatus(0,
'startswith1',
'OK',
'', []),
64 DiagnosticStatus(0,
'startswith2',
'OK',
'', []),
65 DiagnosticStatus(1,
'startswith3',
'OK',
'', []),
68 DiagnosticStatus(2,
'other2',
'OK',
'', []),
69 DiagnosticStatus(0,
'other3',
'OK',
'', [])]
71 array.header.stamp = rospy.get_rostime()
73 if rospy.get_time() - start_time < 5:
75 array.status.append(DiagnosticStatus(0,
'expected4',
'I will be stale',
'', []))
76 array.status.append(DiagnosticStatus(0,
'expected5',
'I will be stale',
'', []))
79 array.status.append(DiagnosticStatus(2,
'other1',
'Error',
'', []))