3 import roslib; roslib.load_manifest(
'test_nodelet')
16 Test that the bond is broken cleanly when closing a nodelet loader (#50). 17 This relies on a debug message printed by the bondcpp package in case 22 proc_manager = subprocess.Popen([
"rosrun",
"nodelet",
"nodelet",
"manager",
"__name:=nodelet_manager"],
23 stdout=subprocess.PIPE,
24 stderr=subprocess.PIPE,
30 rospy.wait_for_service(
'/nodelet_manager/load_nodelet', timeout=2)
32 self.fail(
"Could not determine that nodelet manager has started")
35 proc_nodelet = subprocess.Popen([
"rosrun",
"nodelet",
"nodelet",
"load",
"test_nodelet/Plus",
"nodelet_manager",
"__name:=test"],
36 stdout=subprocess.PIPE,
37 stderr=subprocess.PIPE,
43 rospy.wait_for_service(
'test/get_loggers', timeout=2)
45 self.fail(
"Could not determine that nodelet has started")
49 proc_nodelet.send_signal(signal.SIGINT)
50 (n_out, n_err) = proc_nodelet.communicate()
53 proc_manager.send_signal(signal.SIGINT)
54 (m_out, m_err) = proc_manager.communicate()
57 self.assertIn(
'Unloading nodelet /test from manager nodelet_manager', n_out)
58 self.assertNotIn(
'Bond failed to break on destruction', m_out)
59 self.assertNotIn(
'Bond failed to break on destruction', n_out)
61 if __name__ ==
'__main__':
62 rospy.init_node(
'test_bond_break_on_shutdown')
63 rostest.unitrun(
'test_bond_break_on_shutdown',
'test_bond_break_on_shutdown', TestBondBreakOnShutdown)
def test_bond_break_on_shutdown(self)