test_add_two_ints.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, 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 Willow Garage, Inc. 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 # Revision $Id$
35 
36 ## Integration test for add_two_ints
37 
38 from __future__ import print_function
39 
40 PKG = 'rospy_tutorials'
41 NAME = 'add_two_ints_test'
42 
43 import sys
44 import unittest
45 
46 import rospy
47 import rostest
48 from rospy_tutorials.srv import *
49 
50 class TestAddTwoInts(unittest.TestCase):
51 
52  def test_add_two_ints(self):
53  rospy.wait_for_service('add_two_ints')
54  s = rospy.ServiceProxy('add_two_ints', AddTwoInts)
55  tests = [(1, 2), (0, 0), (-1, -2), (12312, 980123), (sys.maxsize, -sys.maxsize), (sys.maxsize, -1), (sys.maxsize, 0)]
56  for x, y in tests:
57  print("Requesting %s+%s" % (x, y))
58  # test both simple and formal call syntax
59  resp = s(x, y)
60  resp2 = s.call(AddTwoIntsRequest(x, y))
61  self.assertEquals(resp.sum,resp2.sum)
62  print("%s+%s = %s" % (x, y, resp.sum))
63  self.assertEquals(resp.sum,(x + y), "integration failure, returned sum was %s vs. %s"%(resp.sum, (x+y)))
64 
66  rospy.wait_for_service('add_two_ints')
67  try:
68  s = rospy.ServiceProxy('add_two_ints', BadTwoInts)
69  resp = s(1, 2)
70  self.fail("service call should have failed with exception but instead returned 1+2=%s"%resp.sum)
71  except rospy.ServiceException as e:
72  print("success -- ros exception was thrown: %s" % e)
73  s = rospy.ServiceProxy('add_two_ints', AddTwoInts)
74  resp = s.call(AddTwoIntsRequest(1, 2))
75  self.assertEquals(3,resp.sum)
76 
77 
79  rospy.wait_for_service('add_two_ints')
80  s = rospy.ServiceProxy('add_two_ints', BadTwoInts)
81  tests = [(1, 2), (0, 0), (-1, -2), (12312, 980123), (sys.maxsize, -sys.maxsize), (sys.maxsize, -1), (sys.maxsize, 0)]
82  for x, y in tests:
83  print("Requesting %s+%s" % (x, y))
84  # test both simple and formal call syntax
85  try:
86  resp = s(x, y)
87  if resp.sum == x+y:
88  self.fail("call 1 with bad type failed: the server appears to be incorrectly deserialing the packet as it returned: %s"%resp.sum)
89  else:
90  self.fail("call 1 with bad type failed to throw exception: %s"%resp.sum)
91  except rospy.ServiceException as e:
92  print("success -- ros exception was thrown: %s" % e)
93  try:
94  resp = s.call(BadTwoIntsRequest(x, y))
95  if resp.sum == x+y:
96  self.fail("call 2 with bad type failed: the server appears to be incorrectly deserialing the packet as it returned: %s"%resp.sum)
97  else:
98  self.fail("call 2 with bad type failed to throw exception: %s"%resp.sum)
99  except rospy.ServiceException as e:
100  print("success -- ros exception was thrown: %s" % e)
101 
102 if __name__ == '__main__':
103  rostest.rosrun(PKG, NAME, TestAddTwoInts, sys.argv)


rospy_tutorials
Author(s): Ken Conley, Dirk Thomas
autogenerated on Sun Oct 18 2020 13:09:44