test_unload_called_twice.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import roslib; roslib.load_manifest('test_nodelet')
4 import rospy
5 import unittest
6 import rostest
7 import signal
8 import subprocess
9 import time
10 
11 from nodelet.srv import *
12 
13 class TestUnloadCalledTwice(unittest.TestCase):
15  '''
16  Test that when a nodelet loader is stopped and requests unloading,
17  the unload() call in LoaderROS is not run twice (#50).
18  '''
19 
20  # start nodelet manager
21  proc_manager = subprocess.Popen(["rosrun", "nodelet", "nodelet", "manager", "__name:=nodelet_manager"],
22  stdout=subprocess.PIPE,
23  stderr=subprocess.PIPE,
24  bufsize=-1
25  )
26 
27  # wait for nodelet manager to be ready
28  try:
29  rospy.wait_for_service('/nodelet_manager/load_nodelet', timeout=2)
30  except:
31  self.fail("Could not determine that nodelet manager has started")
32 
33  # load nodelet
34  proc_nodelet = subprocess.Popen(["rosrun", "nodelet", "nodelet", "load", "test_nodelet/Plus", "nodelet_manager", "__name:=test"],
35  stdout=subprocess.PIPE,
36  stderr=subprocess.PIPE
37  )
38 
39  # wait for nodelet to be ready
40  try:
41  rospy.wait_for_service('test/get_loggers', timeout=2)
42  except:
43  self.fail("Could not determine that nodelet has started")
44  time.sleep(1)
45 
46  # stop the nodelet loader via signal (similar to roslaunch killing it)
47  proc_nodelet.send_signal(signal.SIGINT)
48  (n_out, n_err) = proc_nodelet.communicate()
49 
50  # stop the nodelet manager, too
51  proc_manager.send_signal(signal.SIGINT)
52  (m_out, m_err) = proc_manager.communicate()
53 
54  # check that nodelet unloaded and that LoaderROS::unload() does not
55  # complain about nodelet not being found (an indication that it was called
56  # again after the nodelet was already unloaded)
57  self.assertIn('Unloading nodelet /test from manager nodelet_manager', n_out)
58  self.assertNotIn('Failed to find nodelet with name', m_err)
59 
60 if __name__ == '__main__':
61  rospy.init_node('test_unload_called_twice')
62  rostest.unitrun('test_unload_called_twice', 'test_unload_called_twice', TestUnloadCalledTwice)


test_nodelet
Author(s): Tully Foote
autogenerated on Mon Feb 18 2019 03:26:50