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 from __future__ import with_statement
00040 DURATION = 10
00041 PKG = 'diagnostic_aggregator'
00042 import roslib; roslib.load_manifest(PKG)
00043 import rospy, rostest, unittest
00044 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00045 from time import sleep
00046 import sys
00047 import threading
00048
00049 MULTI_NAME = 'multi'
00050 HEADER1 = 'Header1'
00051 HEADER2 = 'Header2'
00052
00053 def get_raw_name(agg_name):
00054 return agg_name.split('/')[-1]
00055
00056 def get_header_name(agg_name):
00057 return '/'.join(agg_name.split('/')[1:-1])
00058
00059 class DiagnosticItem:
00060 def __init__(self, msg):
00061 self.name = get_raw_name(msg.name)
00062 self.header = get_header_name(msg.name)
00063 self.level = msg.level
00064 self.message = msg.message
00065
00066 self.update_time = rospy.get_time()
00067
00068 def is_stale(self):
00069 return rospy.get_time() - self.update_time > 5
00070
00071 def update(self, msg):
00072 self.level = msg.level
00073 self.message = msg.message
00074
00075 self.update_time = rospy.get_time()
00076
00077 class TestMultipleMatch(unittest.TestCase):
00078 def __init__(self, *args):
00079 super(TestMultipleMatch, self).__init__(*args)
00080
00081 self._mutex = threading.Lock()
00082
00083 self._multi_items = {}
00084
00085 rospy.init_node('test_multiple_match')
00086 self._starttime = rospy.get_time()
00087
00088 sub_agg = rospy.Subscriber("/diagnostics_agg", DiagnosticArray, self.diag_agg_cb)
00089
00090 def diag_agg_cb(self, msg):
00091 with self._mutex:
00092 for stat in msg.status:
00093 if stat.name.find(MULTI_NAME) > 0:
00094 self._multi_items[get_header_name(stat.name)] = DiagnosticItem(stat)
00095
00096 def test_multiple_match(self):
00097 while not rospy.is_shutdown():
00098 sleep(1.0)
00099 if rospy.get_time() - self._starttime > DURATION:
00100 break
00101
00102 self.assert_(not rospy.is_shutdown(), "Rospy shutdown!")
00103
00104 with self._mutex:
00105 self.assert_(self._multi_items.has_key(HEADER1), "Didn't have item under %s. Items: %s" % (HEADER1, self._multi_items))
00106 self.assert_(self._multi_items[HEADER1].name == MULTI_NAME, "Item name under %s didn't match %s" % (HEADER1, MULTI_NAME))
00107
00108 self.assert_(self._multi_items.has_key(HEADER2), "Didn't have item under %s" % HEADER2)
00109 self.assert_(self._multi_items[HEADER2].name == MULTI_NAME, "Item name under %s didn't match %s" % (HEADER2, MULTI_NAME))
00110
00111
00112 if __name__ == '__main__':
00113 if False:
00114 suite = unittest.TestSuite()
00115 suite.addTest(TestMultipleMatch('test_multiple_match'))
00116 unittest.TextTestRunner(verbosity = 2).run(suite)
00117 else:
00118 rostest.run(PKG, sys.argv[0], TestMultipleMatch, sys.argv)