test_selftest.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2010, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 #
34 
35 ##\author Kevin Watts
36 ##\brief Tests for valid self test calls
37 
38 PKG = 'self_test'
39 import roslib; roslib.load_manifest(PKG)
40 
41 SRV_NAME = 'my_node/self_test'
42 
43 import unittest
44 import rospy, rostest
45 
46 import sys
47 from optparse import OptionParser
48 
49 from diagnostic_msgs.srv import SelfTest, SelfTestRequest, SelfTestResponse
50 
51 class TestSelfTest(unittest.TestCase):
52  def __init__(self, *args):
53  super(TestSelfTest, self).__init__(*args)
54 
55  parser = OptionParser(usage="usage ./%prog [options]", prog="test_selftest.py")
56  parser.add_option('--no-id', action="store_true",
57  dest="no_id", default=False,
58  help="No ID expected from self test")
59  parser.add_option('--expect-fail', action="store_true",
60  dest="expect_fail", default=False,
61  help="Self test should fail")
62  parser.add_option('--exception', action="store_true",
63  dest="exception", default=False,
64  help="Self test should throw exception and we should get error message")
65  # Option comes with rostest, will fail w/o this line
66  parser.add_option('--gtest_output', action="store",
67  dest="gtest")
68 
69  options, args = parser.parse_args()
70 
71  self.no_id = options.no_id
72  self.expect_fail = options.expect_fail
73  self.exception = options.exception
74 
75 
76  def test_self_test(self):
77  proxy = rospy.ServiceProxy(SRV_NAME, SelfTest)
78 
79  try:
80  rospy.wait_for_service(SRV_NAME, 15)
81  except Exception, e:
82  self.assert_(False, "Service %s did not respond. Unable to test self_test" % SRV_NAME)
83 
84  try:
85  res = proxy()
86  except Exception, e:
87  import traceback
88  self.assert_(False, "Error calling self_test service. Exception: %s" % traceback.format_exc())
89 
90  if self.no_id:
91  self.assert_(res.id == '', "Result had node ID even though ID was not expected. ID: %s" % res.id)
92  else:
93  self.assert_(res.id != '', "Result had no node ID")
94 
95  if self.expect_fail or self.exception:
96  self.assert_(res.passed == 0, "Self test passed, but it shouldn't have. Result: %d" % res.passed)
97 
98  max_val = 0
99  for tst in res.status:
100  max_val = max(max_val, tst.level)
101 
102  self.assert_(max_val > 0, "Self test failed, but no sub tests reported a failure or warning")
103  else:
104  self.assert_(res.passed, "Self test failed, but we expected a pass")
105 
106  for tst in res.status:
107  self.assert_(tst.level == 0, "Self test subtest failed, but we marked it as a pass")
108 
109 
110  if self.exception:
111  found_ex = False
112  for tst in res.status:
113  if tst.message.find('exception') > -1:
114  found_ex = True
115 
116  self.assert_(found_ex, "Self test threw and exception, but we didn't catch it and report it")
117 
118 
119 if __name__ == '__main__':
120  rostest.run(PKG, sys.argv[0], TestSelfTest, sys.argv)
def __init__(self, args)


self_test
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs and Blaise Gassend
autogenerated on Thu Oct 8 2020 03:21:45