39 PKG = 
'test_diagnostic_aggregator' 
   42 from time 
import sleep
 
   44 from diagnostic_msgs.msg 
import DiagnosticArray, DiagnosticStatus
 
   46 if __name__ == 
'__main__':
 
   47     rospy.init_node(
'diag_pub')
 
   48     pub = rospy.Publisher(
'/diagnostics', DiagnosticArray, queue_size=10)
 
   50     while not rospy.is_shutdown():
 
   51         array = DiagnosticArray()
 
   52         array.header.stamp = rospy.get_rostime()
 
   55             DiagnosticStatus(0, 
'Match Item', 
'OK', 
'', []),
 
   58             DiagnosticStatus(1, 
'Something', 
'OK', 
'', []),
 
   59             DiagnosticStatus(2, 
'Something Else', 
'OK', 
'', []),
 
   62             DiagnosticStatus(2, 
'other1', 
'OK', 
'', []),
 
   63             DiagnosticStatus(1, 
'other2', 
'OK', 
'', []),
 
   64             DiagnosticStatus(0, 
'other3', 
'OK', 
'', [])]