test_loader.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2009, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # * Redistributions of source code must retain the above copyright
10 # notice, this list of conditions and the following disclaimer.
11 # * Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # * Neither the name of the Willow Garage, Inc. nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 # POSSIBILITY OF SUCH DAMAGE.
29 
30 
31 import roslib; roslib.load_manifest('test_nodelet')
32 import rospy
33 import unittest
34 import rostest
35 import random
36 import subprocess
37 
38 from nodelet.srv import *
39 
40 class TestLoader(unittest.TestCase):
41  def test_loader(self):
42  load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad)
43  unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload)
44  list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList)
45 
46  load.wait_for_service()
47  unload.wait_for_service()
48  list.wait_for_service()
49 
50  req = NodeletLoadRequest()
51  req.name = "/my_nodelet"
52  req.type = "test_nodelet/Plus"
53 
54  res = load.call(req)
55  self.assertTrue(res.success)
56 
57  req = NodeletListRequest()
58  res = list.call(req)
59  self.assertTrue("/my_nodelet" in res.nodelets)
60 
61  req = NodeletUnloadRequest()
62  req.name = "/my_nodelet"
63  res = unload.call(req)
64  self.assertTrue(res.success)
65 
67  load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad)
68  unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload)
69  list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList)
70 
71  load.wait_for_service()
72  unload.wait_for_service()
73  list.wait_for_service()
74 
75  req = NodeletLoadRequest()
76  req.name = "/my_nodelet"
77  req.type = "test_nodelet/FailingNodelet"
78  self.assertRaises(rospy.ServiceException, load.call, req)
79 
80  # If the Nodelet failed to initialize, it shouldn't be stored in the
81  # nodelet map
82  req = NodeletListRequest()
83  res = list.call(req)
84  self.assertFalse("/my_nodelet" in res.nodelets)
85 
86  req = NodeletUnloadRequest()
87  req.name = "/my_nodelet"
88  self.assertRaises(rospy.ServiceException, unload.call, req)
89 
91  proc = subprocess.Popen(["rosrun", "test_nodelet", "create_instance_cb_error"],
92  stderr=subprocess.PIPE
93  )
94 
95  # The load should fail
96  self.assertEqual(proc.wait(), 1)
97 
98  # And the loader should print our error message
99  out = proc.stderr.read()
100  self.assertIn('NODELET_TEST_FAILURE', out)
101 
102 if __name__ == '__main__':
103  rospy.init_node('test_loader')
104  rostest.unitrun('test_loader', 'test_loader', TestLoader)
105 
def test_loader_error_message(self)
Definition: test_loader.py:90
def test_loader_failed_initialization(self)
Definition: test_loader.py:66


test_nodelet
Author(s): Tully Foote
autogenerated on Sat Jul 18 2020 03:17:57