multi_cm_dummy.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (C) 2014, PAL Robotics S.L.
00004 #
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 # * Redistributions of source code must retain the above copyright notice,
00008 # this list of conditions and the following disclaimer.
00009 # * Redistributions in binary form must reproduce the above copyright
00010 # notice, this list of conditions and the following disclaimer in the
00011 # documentation and/or other materials provided with the distribution.
00012 # * Neither the name of PAL Robotics S.L. nor the names of its
00013 # contributors may be used to endorse or promote products derived from
00014 # this software without specific prior written permission.
00015 #
00016 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026 # POSSIBILITY OF SUCH DAMAGE.
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     # Valid controller managers in different namespaces
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     # Partial controller manager ROS API: missing service
00067     cm_incomplete = ControllerManagerDummy('/incomplete')
00068     cm_incomplete.reload_libs.shutdown()
00069 
00070     # Partial controller manager ROS API: service with wrong type
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,  # NOTE: Wrong type
00075                                             cm_bad_type._unload_ctrl_cb)
00076 
00077     rospy.spin()


controller_manager_tests
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Dec 1 2016 03:46:03