Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 import roslib; roslib.load_manifest('test_nodelet')
00032 import rospy
00033 import unittest
00034 import rostest
00035 import random
00036
00037 from nodelet.srv import *
00038
00039 class TestLoader(unittest.TestCase):
00040 def test_loader(self):
00041 load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad)
00042 unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload)
00043 list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList)
00044
00045 load.wait_for_service()
00046 unload.wait_for_service()
00047 list.wait_for_service()
00048
00049 req = NodeletLoadRequest()
00050 req.name = "/my_nodelet"
00051 req.type = "test_nodelet/Plus"
00052
00053 res = load.call(req)
00054 self.assertTrue(res.success)
00055
00056 req = NodeletListRequest()
00057 res = list.call(req)
00058 self.assertTrue("/my_nodelet" in res.nodelets)
00059
00060 req = NodeletUnloadRequest()
00061 req.name = "/my_nodelet"
00062 res = unload.call(req)
00063 self.assertTrue(res.success)
00064
00065 def test_loader_failed_initialization(self):
00066 load = rospy.ServiceProxy('/nodelet_manager/load_nodelet', NodeletLoad)
00067 unload = rospy.ServiceProxy('/nodelet_manager/unload_nodelet', NodeletUnload)
00068 list = rospy.ServiceProxy('/nodelet_manager/list', NodeletList)
00069
00070 load.wait_for_service()
00071 unload.wait_for_service()
00072 list.wait_for_service()
00073
00074 req = NodeletLoadRequest()
00075 req.name = "/my_nodelet"
00076 req.type = "test_nodelet/FailingNodelet"
00077 self.assertRaises(rospy.ServiceException, load.call, req)
00078
00079
00080
00081 req = NodeletListRequest()
00082 res = list.call(req)
00083 self.assertFalse("/my_nodelet" in res.nodelets)
00084
00085 req = NodeletUnloadRequest()
00086 req.name = "/my_nodelet"
00087 self.assertRaises(rospy.ServiceException, unload.call, req)
00088
00089
00090 if __name__ == '__main__':
00091 rospy.init_node('test_loader')
00092 rostest.unitrun('test_loader', 'test_loader', TestLoader)
00093