Go to the documentation of this file.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
00041 DURATION = 5
00042 PKG = 'test_diagnostic_aggregator'
00043 import roslib; roslib.load_manifest(PKG)
00044 import rospy, rostest, unittest
00045 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
00046 from time import sleep
00047 import sys
00048 import threading
00049
00050 from optparse import OptionParser
00051
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 TestFailInit(unittest.TestCase):
00060 def __init__(self, *args):
00061 super(TestFailInit, self).__init__(*args)
00062
00063 parser = OptionParser(usage="usage ./%prog [options]", prog="fail_init_test.py")
00064 parser.add_option('--ns', action="store", default=None,
00065 dest="ns", metavar="NAMESPACE",
00066 help="Expected namespace that analyzer will fail in")
00067
00068 parser.add_option('--gtest_output', action="store",
00069 dest="gtest")
00070
00071 options, args = parser.parse_args(rospy.myargv())
00072
00073 if not options.ns:
00074 parser.error("Option --ns is mandatory. Unable to parse args")
00075
00076 self._ns = options.ns
00077 self._item = None
00078
00079 self._mutex = threading.Lock()
00080
00081
00082 rospy.init_node('test_fail_init')
00083 self._starttime = rospy.get_time()
00084
00085 sub_agg = rospy.Subscriber("/diagnostics_agg", DiagnosticArray, self.diag_agg_cb)
00086
00087 def diag_agg_cb(self, msg):
00088 with self._mutex:
00089 for stat in msg.status:
00090 if stat.name.find(self._ns) > 0:
00091 self._item = stat
00092 break
00093
00094 def test_fail_init(self):
00095 while not rospy.is_shutdown():
00096 sleep(1.0)
00097 if rospy.get_time() - self._starttime > DURATION:
00098 break
00099
00100 self.assert_(not rospy.is_shutdown(), "Rospy shutdown!")
00101
00102 with self._mutex:
00103 self.assert_(self._ns, "Namespace is none. Option --ns not given")
00104 self.assert_(self._item, "No item with name %s found in diag_agg" % self._ns)
00105 self.assert_(self._item.level == 3, "Item failed to initialize, but was not stale. Level: %d" % self._item.level)
00106
00107
00108 if __name__ == '__main__':
00109 if False:
00110 suite = unittest.TestSuite()
00111 suite.addTest(TestFailInit('test_fail_init'))
00112 unittest.TextTestRunner(verbosity = 2).run(suite)
00113 else:
00114 rostest.run(PKG, sys.argv[0], TestFailInit, sys.argv)