moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
41 #include <boost/algorithm/string/join.hpp>
42 #include <pluginlib/class_list_macros.hpp>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <rclcpp/node.hpp>
46 #include <rclcpp/parameter.hpp>
47 #include <rclcpp/parameter_value.hpp>
48 #include <algorithm>
49 #include <map>
50 
51 namespace
52 {
59 template <typename... T>
60 std::string concatenateWithSeparator(char separator, T... content)
61 {
62  std::string result;
63  (result.append(content).append({ separator }), ...);
64  result.erase(result.end() - 1); // delete trailing separator
65  return result;
66 }
67 
75 template <typename... T>
76 std::string makeParameterName(T... strings)
77 {
78  return concatenateWithSeparator<T...>('.', strings...);
79 }
80 
81 } // namespace
82 
84 {
85 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.plugins.moveit_simple_controller_manager");
86 static const std::string PARAM_BASE_NAME = "moveit_simple_controller_manager";
88 {
89 public:
91 
92  ~MoveItSimpleControllerManager() override = default;
93 
94  void initialize(const rclcpp::Node::SharedPtr& node) override
95  {
96  node_ = node;
97  if (!node_->has_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names")))
98  {
99  RCLCPP_ERROR_STREAM(LOGGER, "No controller_names specified.");
100  return;
101  }
102  rclcpp::Parameter controller_names_param;
103  node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "controller_names"), controller_names_param);
104  if (controller_names_param.get_type() != rclcpp::ParameterType::PARAMETER_STRING_ARRAY)
105  {
106  RCLCPP_ERROR(LOGGER, "Parameter controller_names should be specified as a string array");
107  return;
108  }
109  std::vector<std::string> controller_names = controller_names_param.as_string_array();
110  /* actually create each controller */
111  for (const std::string& controller_name : controller_names)
112  {
113  try
114  {
115  std::string action_ns;
116  const std::string& action_ns_param = makeParameterName(PARAM_BASE_NAME, controller_name, "action_ns");
117  if (!node_->get_parameter(action_ns_param, action_ns))
118  {
119  RCLCPP_ERROR_STREAM(LOGGER, "No action namespace specified for controller `"
120  << controller_name << "` through parameter `" << action_ns_param << "`");
121  continue;
122  }
123 
124  std::string type;
125  if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name, "type"), type))
126  {
127  RCLCPP_ERROR_STREAM(LOGGER, "No type specified for controller " << controller_name);
128  continue;
129  }
130 
131  std::vector<std::string> controller_joints;
132  if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name, "joints"), controller_joints) ||
133  controller_joints.empty())
134  {
135  RCLCPP_ERROR_STREAM(LOGGER, "No joints specified for controller " << controller_name);
136  continue;
137  }
138 
139  ActionBasedControllerHandleBasePtr new_handle;
140  if (type == "GripperCommand")
141  {
142  double max_effort;
143  const std::string& max_effort_param = makeParameterName(PARAM_BASE_NAME, controller_name, "max_effort");
144  if (!node->get_parameter(max_effort_param, max_effort))
145  {
146  RCLCPP_INFO_STREAM(LOGGER, "Max effort set to 0.0");
147  max_effort = 0.0;
148  }
149 
150  new_handle = std::make_shared<GripperControllerHandle>(node_, controller_name, action_ns, max_effort);
151  bool parallel_gripper = false;
152  if (node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "parallel"), parallel_gripper) && parallel_gripper)
153  {
154  if (controller_joints.size() != 2)
155  {
156  RCLCPP_ERROR_STREAM(LOGGER, "Parallel Gripper requires exactly two joints, " << controller_joints.size()
157  << " are specified");
158  continue;
159  }
160  static_cast<GripperControllerHandle*>(new_handle.get())
161  ->setParallelJawGripper(controller_joints[0], controller_joints[1]);
162  }
163  else
164  {
165  std::string command_joint;
166  if (!node_->get_parameter(makeParameterName(PARAM_BASE_NAME, "command_joint"), command_joint))
167  command_joint = controller_joints[0];
168 
169  static_cast<GripperControllerHandle*>(new_handle.get())->setCommandJoint(command_joint);
170  }
171 
172  bool allow_failure;
173  node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, "allow_failure"), allow_failure, false);
174  static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(allow_failure);
175 
176  RCLCPP_INFO_STREAM(LOGGER, "Added GripperCommand controller for " << controller_name);
177  controllers_[controller_name] = new_handle;
178  }
179  else if (type == "FollowJointTrajectory")
180  {
181  new_handle = std::make_shared<FollowJointTrajectoryControllerHandle>(node_, controller_name, action_ns);
182  RCLCPP_INFO_STREAM(LOGGER, "Added FollowJointTrajectory controller for " << controller_name);
183  controllers_[controller_name] = new_handle;
184  }
185  else
186  {
187  RCLCPP_ERROR_STREAM(LOGGER, "Unknown controller type: " << type);
188  continue;
189  }
190  if (!controllers_[controller_name])
191  {
192  controllers_.erase(controller_name);
193  continue;
194  }
195 
197  node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, controller_name, "default"), state.default_, false);
198  state.active_ = true;
199 
200  controller_states_[controller_name] = state;
201 
202  /* add list of joints, used by controller manager and MoveIt */
203  for (const std::string& controller_joint : controller_joints)
204  new_handle->addJoint(controller_joint);
205  }
206  catch (...)
207  {
208  RCLCPP_ERROR_STREAM(LOGGER, "Caught unknown exception while parsing controller information");
209  }
210  }
211  }
212  /*
213  * Get a controller, by controller name (which was specified in the controllers.yaml
214  */
215  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
216  {
217  std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
218  if (it != controllers_.end())
219  return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
220  else
221  RCLCPP_FATAL_STREAM(LOGGER, "No such controller: " << name);
222  return moveit_controller_manager::MoveItControllerHandlePtr();
223  }
224 
225  /*
226  * Get the list of controller names.
227  */
228  void getControllersList(std::vector<std::string>& names) override
229  {
230  for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin();
231  it != controllers_.end(); ++it)
232  names.push_back(it->first);
233  RCLCPP_INFO_STREAM(LOGGER, "Returned " << names.size() << " controllers in list");
234  }
235 
236  /*
237  * This plugin assumes that all controllers are already active -- and if they are not, well, it has no way to deal
238  * with it anyways!
239  */
240  void getActiveControllers(std::vector<std::string>& names) override
241  {
242  getControllersList(names);
243  }
244 
245  /*
246  * Controller must be loaded to be active, see comment above about active controllers...
247  */
248  virtual void getLoadedControllers(std::vector<std::string>& names)
249  {
250  getControllersList(names);
251  }
252 
253  /*
254  * Get the list of joints that a controller can control.
255  */
256  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
257  {
258  std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
259  if (it != controllers_.end())
260  {
261  it->second->getJoints(joints);
262  }
263  else
264  {
265  RCLCPP_WARN(LOGGER,
266  "The joints for controller '%s' are not known. Perhaps the controller configuration is "
267  "not loaded on the param server?",
268  name.c_str());
269  joints.clear();
270  }
271  }
272 
274  getControllerState(const std::string& name) override
275  {
276  return controller_states_[name];
277  }
278 
279  /* Cannot switch our controllers */
280  bool switchControllers(const std::vector<std::string>& /* activate */,
281  const std::vector<std::string>& /* deactivate */) override
282  {
283  return false;
284  }
285 
286 protected:
287  rclcpp::Node::SharedPtr node_;
288  std::map<std::string, ActionBasedControllerHandleBasePtr> controllers_;
289  std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState> controller_states_;
290 };
291 
292 } // end namespace moveit_simple_controller_manager
293 
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt,...
bool switchControllers(const std::vector< std::string > &, const std::vector< std::string > &) override
Activate and deactivate controllers.
void getControllerJoints(const std::string &name, std::vector< std::string > &joints) override
Report the joints a controller operates on, given the controller name.
void getActiveControllers(std::vector< std::string > &names) override
Get the list of active controllers.
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name) override
Return a given named controller.
std::map< std::string, moveit_controller_manager::MoveItControllerManager::ControllerState > controller_states_
std::map< std::string, ActionBasedControllerHandleBasePtr > controllers_
moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name) override
Report the state of a controller, given its name.
void getControllersList(std::vector< std::string > &names) override
Get the list of known controller names.
PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_controller_manager::MoveItControllerManager)
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Each controller known to MoveIt has a state. This structure describes that controller's state.
bool default_
It is often the case that multiple controllers could be used to execute a motion. Marking a controlle...
bool active_
A controller can be active or inactive. This means that MoveIt could activate the controller when nee...