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 import rospy
00029 from controller_manager_tests import ControllerManagerDummy
00030 from controller_manager_msgs.msg import ControllerState as CtrlState
00031 from controller_manager_msgs.msg import HardwareInterfaceResources
00032 from controller_manager_msgs.srv import ListControllersResponse, LoadController
00033
00034 if __name__ == '__main__':
00035 rospy.init_node('multi_cm_dummy')
00036
00037
00038 cm_root = ControllerManagerDummy('/')
00039 cm_foo1 = ControllerManagerDummy('/foo/robot/controller_manager1')
00040 cm_foo2 = ControllerManagerDummy('/foo/robot/controller_manager2')
00041 cm_default = ControllerManagerDummy()
00042
00043 ctrl_list = [
00044 CtrlState(name='foo_controller',
00045 state='running',
00046 type='foo_base/foo',
00047 claimed_resources=[
00048 HardwareInterfaceResources(
00049 hardware_interface='hardware_interface::FooInterface',
00050 resources=['one', 'two', 'three'])
00051 ]),
00052 CtrlState(name='bar_controller',
00053 state='running',
00054 type='bar_base/bar',
00055 claimed_resources=[
00056 HardwareInterfaceResources(
00057 hardware_interface='hardware_interface::BarInterface',
00058 resources=['four'])
00059 ])
00060 ]
00061
00062 resp = ListControllersResponse()
00063 resp.controller = ctrl_list
00064 cm_default.list_ctrl_resp = resp
00065
00066
00067 cm_incomplete = ControllerManagerDummy('/incomplete')
00068 cm_incomplete.reload_libs.shutdown()
00069
00070
00071 cm_bad_type = ControllerManagerDummy('/bad_type')
00072 cm_bad_type.unload_ctrl.shutdown()
00073 cm_bad_type.unload_ctrl = rospy.Service('/bad_type/unload_controller',
00074 LoadController,
00075 cm_bad_type._unload_ctrl_cb)
00076
00077 rospy.spin()