3 import roslib; roslib.load_manifest(
'test_nodelet')
16 Test that when a nodelet loader is stopped and requests unloading, 17 the unload() call in LoaderROS is not run twice (#50). 21 proc_manager = subprocess.Popen([
"rosrun",
"nodelet",
"nodelet",
"manager",
"__name:=nodelet_manager"],
22 stdout=subprocess.PIPE,
23 stderr=subprocess.PIPE,
29 rospy.wait_for_service(
'/nodelet_manager/load_nodelet', timeout=2)
31 self.fail(
"Could not determine that nodelet manager has started")
34 proc_nodelet = subprocess.Popen([
"rosrun",
"nodelet",
"nodelet",
"load",
"test_nodelet/Plus",
"nodelet_manager",
"__name:=test"],
35 stdout=subprocess.PIPE,
36 stderr=subprocess.PIPE
41 rospy.wait_for_service(
'test/get_loggers', timeout=2)
43 self.fail(
"Could not determine that nodelet has started")
47 proc_nodelet.send_signal(signal.SIGINT)
48 (n_out, n_err) = proc_nodelet.communicate()
51 proc_manager.send_signal(signal.SIGINT)
52 (m_out, m_err) = proc_manager.communicate()
57 self.assertIn(
'Unloading nodelet /test from manager nodelet_manager', n_out)
58 self.assertNotIn(
'Failed to find nodelet with name', m_err)
60 if __name__ ==
'__main__':
61 rospy.init_node(
'test_unload_called_twice')
62 rostest.unitrun(
'test_unload_called_twice',
'test_unload_called_twice', TestUnloadCalledTwice)
def test_unload_called_twice(self)