moveit_simple_controller_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Unbounded Robotics Inc.
5  * Copyright (c) 2012, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */
37 
38 #include <ros/ros.h>
43 #include <algorithm>
44 #include <map>
45 
47 {
49 {
50 public:
52  {
53  if (!node_handle_.hasParam("controller_list"))
54  {
55  ROS_ERROR_STREAM_NAMED("manager", "No controller_list specified.");
56  return;
57  }
58 
59  XmlRpc::XmlRpcValue controller_list;
60  node_handle_.getParam("controller_list", controller_list);
61  if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
62  {
63  ROS_ERROR("Parameter controller_list should be specified as an array");
64  return;
65  }
66 
67  /* actually create each controller */
68  for (int i = 0; i < controller_list.size(); ++i)
69  {
70  if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
71  {
72  ROS_ERROR_STREAM_NAMED("manager", "Name and joints must be specifed for each controller");
73  continue;
74  }
75 
76  try
77  {
78  std::string name = std::string(controller_list[i]["name"]);
79 
80  std::string action_ns;
81  if (controller_list[i].hasMember("ns"))
82  {
83  /* TODO: this used to be called "ns", renaming to "action_ns" and will remove in the future */
84  action_ns = std::string(controller_list[i]["ns"]);
85  ROS_WARN_NAMED("manager", "Use of 'ns' is deprecated, use 'action_ns' instead.");
86  }
87  else if (controller_list[i].hasMember("action_ns"))
88  action_ns = std::string(controller_list[i]["action_ns"]);
89  else
90  ROS_WARN_NAMED("manager", "Please note that 'action_ns' no longer has a default value.");
91 
92  if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
93  {
94  ROS_ERROR_STREAM_NAMED("manager", "The list of joints for controller " << name
95  << " is not specified as an array");
96  continue;
97  }
98 
99  if (!controller_list[i].hasMember("type"))
100  {
101  ROS_ERROR_STREAM_NAMED("manager", "No type specified for controller " << name);
102  continue;
103  }
104 
105  std::string type = std::string(controller_list[i]["type"]);
106 
107  ActionBasedControllerHandleBasePtr new_handle;
108  if (type == "GripperCommand")
109  {
110  new_handle.reset(new GripperControllerHandle(name, action_ns));
111  if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
112  {
113  if (controller_list[i].hasMember("parallel"))
114  {
115  if (controller_list[i]["joints"].size() != 2)
116  {
117  ROS_ERROR_STREAM_NAMED("manager", "Parallel Gripper requires exactly two joints");
118  continue;
119  }
120  static_cast<GripperControllerHandle*>(new_handle.get())
121  ->setParallelJawGripper(controller_list[i]["joints"][0], controller_list[i]["joints"][1]);
122  }
123  else
124  {
125  if (controller_list[i].hasMember("command_joint"))
126  static_cast<GripperControllerHandle*>(new_handle.get())
127  ->setCommandJoint(controller_list[i]["command_joint"]);
128  else
129  static_cast<GripperControllerHandle*>(new_handle.get())
130  ->setCommandJoint(controller_list[i]["joints"][0]);
131  }
132 
133  if (controller_list[i].hasMember("allow_failure"))
134  static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(true);
135 
136  ROS_INFO_STREAM_NAMED("manager", "Added GripperCommand controller for " << name);
137  controllers_[name] = new_handle;
138  }
139  }
140  else if (type == "FollowJointTrajectory")
141  {
142  new_handle.reset(new FollowJointTrajectoryControllerHandle(name, action_ns));
143  if (static_cast<FollowJointTrajectoryControllerHandle*>(new_handle.get())->isConnected())
144  {
145  ROS_INFO_STREAM_NAMED("manager", "Added FollowJointTrajectory controller for " << name);
146  controllers_[name] = new_handle;
147  }
148  }
149  else
150  {
151  ROS_ERROR_STREAM_NAMED("manager", "Unknown controller type: " << type.c_str());
152  continue;
153  }
154  if (!controllers_[name])
155  {
156  controllers_.erase(name);
157  continue;
158  }
159 
160  /* add list of joints, used by controller manager and moveit */
161  for (int j = 0; j < controller_list[i]["joints"].size(); ++j)
162  controllers_[name]->addJoint(std::string(controller_list[i]["joints"][j]));
163  }
164  catch (...)
165  {
166  ROS_ERROR_STREAM_NAMED("manager", "Caught unknown exception while parsing controller information");
167  }
168  }
169  }
170 
172  {
173  }
174 
175  /*
176  * Get a controller, by controller name (which was specified in the controllers.yaml
177  */
178  virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
179  {
180  std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
181  if (it != controllers_.end())
182  return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
183  else
184  ROS_FATAL_STREAM_NAMED("manager", "No such controller: " << name);
185  return moveit_controller_manager::MoveItControllerHandlePtr();
186  }
187 
188  /*
189  * Get the list of controller names.
190  */
191  virtual void getControllersList(std::vector<std::string>& names)
192  {
193  for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin();
194  it != controllers_.end(); ++it)
195  names.push_back(it->first);
196  ROS_INFO_STREAM_NAMED("manager", "Returned " << names.size() << " controllers in list");
197  }
198 
199  /*
200  * This plugin assumes that all controllers are already active -- and if they are not, well, it has no way to deal
201  * with it anyways!
202  */
203  virtual void getActiveControllers(std::vector<std::string>& names)
204  {
205  getControllersList(names);
206  }
207 
208  /*
209  * Controller must be loaded to be active, see comment above about active controllers...
210  */
211  virtual void getLoadedControllers(std::vector<std::string>& names)
212  {
213  getControllersList(names);
214  }
215 
216  /*
217  * Get the list of joints that a controller can control.
218  */
219  virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
220  {
221  std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
222  if (it != controllers_.end())
223  {
224  it->second->getJoints(joints);
225  }
226  else
227  {
228  ROS_WARN_NAMED("manager", "The joints for controller '%s' are not known. Perhaps the controller configuration is "
229  "not loaded on the param server?",
230  name.c_str());
231  joints.clear();
232  }
233  }
234 
235  /*
236  * Controllers are all active and default -- that's what makes this thing simple.
237  */
239  getControllerState(const std::string& name)
240  {
242  state.active_ = true;
243  state.default_ = true;
244  return state;
245  }
246 
247  /* Cannot switch our controllers */
248  virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
249  {
250  return false;
251  }
252 
253 protected:
255  std::map<std::string, ActionBasedControllerHandleBasePtr> controllers_;
256 };
257 
258 } // end namespace moveit_simple_controller_manager
259 
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
int size() const
#define ROS_INFO_STREAM_NAMED(name, args)
PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_controller_manager::MoveItControllerManager)
Type const & getType() const
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
#define ROS_FATAL_STREAM_NAMED(name, args)
bool hasMember(const std::string &name) const
bool getParam(const std::string &key, std::string &s) const
std::map< std::string, ActionBasedControllerHandleBasePtr > controllers_
bool hasParam(const std::string &key) const
#define ROS_ERROR(...)
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Wed Jul 10 2019 04:04:40