controller_manager_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_msgs.srv import *
00030 
00031 
00032 class ControllerManagerDummy:
00033     """
00034     Dummy controller manager instance.
00035 
00036     Creates the expected controller manager ROS interface, with a simple
00037     default behavior that can be overridden by modifying its members.
00038     """
00039     def __init__(self, ns="/controller_manager"):
00040         # Controller manager namespace
00041         cm_ns = ns
00042         if not cm_ns or cm_ns[-1] != '/':
00043             cm_ns += '/'
00044 
00045         # Service return values (reset if a specific behavior is desired)
00046         self.list_ctrl_resp = ListControllersResponse()
00047         self.list_types_resp = ListControllerTypesResponse()
00048         self.load_ctrl_resp = LoadControllerResponse(ok=True)
00049         self.unload_ctrl_resp = UnloadControllerResponse(ok=True)
00050         self.switch_ctrl_resp = SwitchControllerResponse(ok=True)
00051         self.reload_libs_resp = ReloadControllerLibrariesResponse(ok=True)
00052 
00053         # Service proxies
00054         self.list_ctrl = rospy.Service(cm_ns + 'list_controllers',
00055                                        ListControllers,
00056                                        self._list_ctrl_cb)
00057         self.list_types = rospy.Service(cm_ns + 'list_controller_types',
00058                                         ListControllerTypes,
00059                                         self._list_types_cb)
00060         self.load_ctrl = rospy.Service(cm_ns + 'load_controller',
00061                                        LoadController,
00062                                        self._load_ctrl_cb)
00063         self.unload_ctrl = rospy.Service(cm_ns + 'unload_controller',
00064                                          UnloadController,
00065                                          self._unload_ctrl_cb)
00066         self.switch_ctrl = rospy.Service(cm_ns + 'switch_controller',
00067                                          SwitchController,
00068                                          self._switch_ctrl_cb)
00069         self.reload_libs = rospy.Service(cm_ns + 'reload_controller_libraries',
00070                                          ReloadControllerLibraries,
00071                                          self._reload_libs_cb)
00072 
00073     def _list_ctrl_cb(self, req):
00074         return self.list_ctrl_resp
00075 
00076     def _list_types_cb(self, req):
00077         return self.list_types_resp
00078 
00079     def _load_ctrl_cb(self, req):
00080         return self.load_ctrl_resp
00081 
00082     def _unload_ctrl_cb(self, req):
00083         return self.unload_ctrl_resp
00084 
00085     def _switch_ctrl_cb(self, req):
00086         return self.switch_ctrl_resp
00087 
00088     def _reload_libs_cb(self, req):
00089         return self.reload_libs_resp


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