31 import roslib; roslib.load_manifest(
'test_nodelet')
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)
46 load.wait_for_service()
47 unload.wait_for_service()
48 list.wait_for_service()
50 req = NodeletLoadRequest()
51 req.name =
"/my_nodelet"
52 req.type =
"test_nodelet/Plus"
55 self.assertTrue(res.success)
57 req = NodeletListRequest()
59 self.assertIn(
'/my_nodelet', res.nodelets)
61 req = NodeletUnloadRequest()
62 req.name =
"/my_nodelet"
63 res = unload.call(req)
64 self.assertTrue(res.success)
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)
71 load.wait_for_service()
72 unload.wait_for_service()
73 list.wait_for_service()
75 req = NodeletLoadRequest()
76 req.name =
"/my_nodelet"
77 req.type =
"test_nodelet/FailingNodelet"
78 self.assertRaises(rospy.ServiceException, load.call, req)
82 req = NodeletListRequest()
84 self.assertNotIn(
'/my_nodelet', res.nodelets)
86 req = NodeletUnloadRequest()
87 req.name =
"/my_nodelet"
88 self.assertRaises(rospy.ServiceException, unload.call, req)
91 proc = subprocess.Popen([
"rosrun",
"test_nodelet",
"create_instance_cb_error"],
92 stderr=subprocess.PIPE
96 self.assertEqual(proc.wait(), 1)
99 out = proc.stderr.read()
100 self.assertIn(
'NODELET_TEST_FAILURE', out.decode())
102 if __name__ ==
'__main__':
103 rospy.init_node(
'test_loader')
104 rostest.rosrun(
'test_loader',
'test_loader', TestLoader)