controller_manager_dummy.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (C) 2014, PAL Robotics S.L.
4 #
5 # Redistribution and use in source and binary forms, with or without
6 # modification, are permitted provided that the following conditions are met:
7 # * Redistributions of source code must retain the above copyright notice,
8 # this list of conditions and the following disclaimer.
9 # * Redistributions in binary form must reproduce the above copyright
10 # notice, this list of conditions and the following disclaimer in the
11 # documentation and/or other materials provided with the distribution.
12 # * Neither the name of PAL Robotics S.L. nor the names of its
13 # contributors may be used to endorse or promote products derived from
14 # this software without specific prior written permission.
15 #
16 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 # POSSIBILITY OF SUCH DAMAGE.
27 
28 import rospy
29 from controller_manager_msgs.srv import *
30 
31 
33  """
34  Dummy controller manager instance.
35 
36  Creates the expected controller manager ROS interface, with a simple
37  default behavior that can be overridden by modifying its members.
38  """
39  def __init__(self, ns="/controller_manager"):
40  # Controller manager namespace
41  cm_ns = ns
42  if not cm_ns or cm_ns[-1] != '/':
43  cm_ns += '/'
44 
45  # Service return values (reset if a specific behavior is desired)
46  self.list_ctrl_resp = ListControllersResponse()
47  self.list_types_resp = ListControllerTypesResponse()
48  self.load_ctrl_resp = LoadControllerResponse(ok=True)
49  self.unload_ctrl_resp = UnloadControllerResponse(ok=True)
50  self.switch_ctrl_resp = SwitchControllerResponse(ok=True)
51  self.reload_libs_resp = ReloadControllerLibrariesResponse(ok=True)
52 
53  # Service proxies
54  self.list_ctrl = rospy.Service(cm_ns + 'list_controllers',
55  ListControllers,
56  self._list_ctrl_cb)
57  self.list_types = rospy.Service(cm_ns + 'list_controller_types',
58  ListControllerTypes,
59  self._list_types_cb)
60  self.load_ctrl = rospy.Service(cm_ns + 'load_controller',
61  LoadController,
62  self._load_ctrl_cb)
63  self.unload_ctrl = rospy.Service(cm_ns + 'unload_controller',
64  UnloadController,
65  self._unload_ctrl_cb)
66  self.switch_ctrl = rospy.Service(cm_ns + 'switch_controller',
67  SwitchController,
68  self._switch_ctrl_cb)
69  self.reload_libs = rospy.Service(cm_ns + 'reload_controller_libraries',
70  ReloadControllerLibraries,
71  self._reload_libs_cb)
72 
73  def _list_ctrl_cb(self, req):
74  return self.list_ctrl_resp
75 
76  def _list_types_cb(self, req):
77  return self.list_types_resp
78 
79  def _load_ctrl_cb(self, req):
80  return self.load_ctrl_resp
81 
82  def _unload_ctrl_cb(self, req):
83  return self.unload_ctrl_resp
84 
85  def _switch_ctrl_cb(self, req):
86  return self.switch_ctrl_resp
87 
88  def _reload_libs_cb(self, req):
89  return self.reload_libs_resp


controller_manager_tests
Author(s): Vijay Pradeep, Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Jun 7 2019 22:00:10