test_unload_called_twice.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import roslib; roslib.load_manifest('test_nodelet')
00004 import rospy
00005 import unittest
00006 import rostest
00007 import signal
00008 import subprocess
00009 import time
00010 
00011 from nodelet.srv import *
00012 
00013 class TestUnloadCalledTwice(unittest.TestCase):
00014     def test_unload_called_twice(self):
00015         '''
00016         Test that when a nodelet loader is stopped and requests unloading,
00017         the unload() call in LoaderROS is not run twice (#50).
00018         '''
00019 
00020         # start nodelet manager
00021         proc_manager = subprocess.Popen(["rosrun", "nodelet", "nodelet", "manager", "__name:=nodelet_manager"],
00022             stdout=subprocess.PIPE,
00023             stderr=subprocess.PIPE,
00024             bufsize=-1
00025         )
00026 
00027         # wait for nodelet manager to be ready
00028         try:
00029             rospy.wait_for_service('/nodelet_manager/load_nodelet', timeout=2)
00030         except:
00031             self.fail("Could not determine that nodelet manager has started")
00032 
00033         # load nodelet
00034         proc_nodelet = subprocess.Popen(["rosrun", "nodelet", "nodelet", "load", "test_nodelet/Plus", "nodelet_manager", "__name:=test"],
00035             stdout=subprocess.PIPE,
00036             stderr=subprocess.PIPE
00037         )
00038 
00039         # wait for nodelet to be ready
00040         try:
00041             rospy.wait_for_service('test/get_loggers', timeout=2)
00042         except:
00043             self.fail("Could not determine that nodelet has started")
00044         time.sleep(1)
00045 
00046         # stop the nodelet loader via signal (similar to roslaunch killing it)
00047         proc_nodelet.send_signal(signal.SIGINT)
00048         (n_out, n_err) = proc_nodelet.communicate()
00049 
00050         # stop the nodelet manager, too
00051         proc_manager.send_signal(signal.SIGINT)
00052         (m_out, m_err) = proc_manager.communicate()
00053 
00054         # check that nodelet unloaded and that LoaderROS::unload() does not
00055         # complain about nodelet not being found (an indication that it was called
00056         # again after the nodelet was already unloaded)
00057         self.assertIn('Unloading nodelet /test from manager nodelet_manager', n_out)
00058         self.assertNotIn('Failed to find nodelet with name', m_err)
00059 
00060 if __name__ == '__main__':
00061     rospy.init_node('test_unload_called_twice')
00062     rostest.unitrun('test_unload_called_twice', 'test_unload_called_twice', TestUnloadCalledTwice)


test_nodelet
Author(s): Tully Foote
autogenerated on Sun Feb 17 2019 03:43:56