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>
44 #include <algorithm>
45 #include <map>
46 
47 using namespace moveit::core;
48 
49 const std::string LOGNAME("SimpleControllerManager");
50 
52 {
54 {
55 public:
56  MoveItSimpleControllerManager() : node_handle_("~")
57  {
58  if (!node_handle_.hasParam("controller_list"))
59  {
60  ROS_ERROR_STREAM_NAMED(LOGNAME, "No controller_list specified.");
61  return;
62  }
63 
64  XmlRpc::XmlRpcValue controller_list;
65  node_handle_.getParam("controller_list", controller_list);
66  if (!isArray(controller_list))
67  {
68  ROS_ERROR_NAMED(LOGNAME, "Parameter controller_list should be specified as an array");
69  return;
70  }
71 
72  /* actually create each controller */
73  for (int i = 0; i < controller_list.size(); ++i) // NOLINT(modernize-loop-convert)
74  {
75  if (!isStruct(controller_list[i], { "name", "joints", "action_ns", "type" }))
76  {
77  ROS_ERROR_STREAM_NAMED(LOGNAME, "name, joints, action_ns, and type must be specifed for each controller");
78  continue;
79  }
80 
81  try
82  {
83  const std::string name = std::string(controller_list[i]["name"]);
84  const std::string action_ns = std::string(controller_list[i]["action_ns"]);
85  const std::string type = std::string(controller_list[i]["type"]);
86 
87  if (!isArray(controller_list[i]["joints"]))
88  {
90  "The list of joints for controller " << name << " is not specified as an array");
91  continue;
92  }
93 
94  ActionBasedControllerHandleBasePtr new_handle;
95  if (type == "GripperCommand")
96  {
97  const double max_effort =
98  controller_list[i].hasMember("max_effort") ? double(controller_list[i]["max_effort"]) : 0.0;
99 
100  new_handle = std::make_shared<GripperControllerHandle>(name, action_ns, max_effort);
101  if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
102  {
103  if (controller_list[i].hasMember("parallel"))
104  {
105  if (controller_list[i]["joints"].size() != 2)
106  {
107  ROS_ERROR_STREAM_NAMED(LOGNAME, "Parallel Gripper requires exactly two joints");
108  continue;
109  }
110  static_cast<GripperControllerHandle*>(new_handle.get())
111  ->setParallelJawGripper(controller_list[i]["joints"][0], controller_list[i]["joints"][1]);
112  }
113  else
114  {
115  if (controller_list[i].hasMember("command_joint"))
116  static_cast<GripperControllerHandle*>(new_handle.get())
117  ->setCommandJoint(controller_list[i]["command_joint"]);
118  else
119  static_cast<GripperControllerHandle*>(new_handle.get())->setCommandJoint(controller_list[i]["joints"][0]);
120  }
121 
122  if (controller_list[i].hasMember("allow_failure"))
123  static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(true);
124 
125  ROS_INFO_STREAM_NAMED(LOGNAME, "Added GripperCommand controller for " << name);
126  controllers_[name] = new_handle;
127  }
128  }
129  else if (type == "FollowJointTrajectory")
130  {
131  auto h = new FollowJointTrajectoryControllerHandle(name, action_ns);
132  new_handle.reset(h);
133  if (h->isConnected())
134  {
135  ROS_INFO_STREAM_NAMED(LOGNAME, "Added FollowJointTrajectory controller for " << name);
136  controllers_[name] = new_handle;
137  }
138  }
139  else
140  {
141  ROS_ERROR_STREAM_NAMED(LOGNAME, "Unknown controller type: " << type.c_str());
142  continue;
143  }
144  if (!controllers_[name])
145  {
146  controllers_.erase(name);
147  continue;
148  }
149 
151  state.default_ = controller_list[i].hasMember("default") ? (bool)controller_list[i]["default"] : false;
152  state.active_ = true;
153 
154  controller_states_[name] = state;
155 
156  /* add list of joints, used by controller manager and MoveIt */
157  for (int j = 0; j < controller_list[i]["joints"].size(); ++j)
158  new_handle->addJoint(std::string(controller_list[i]["joints"][j]));
159 
160  new_handle->configure(controller_list[i]);
161  }
162  catch (...)
163  {
164  ROS_ERROR_STREAM_NAMED(LOGNAME, "Caught unknown exception while parsing controller information");
165  }
166  }
167  }
168 
169  ~MoveItSimpleControllerManager() override = default;
170 
171  /*
172  * Get a controller, by controller name (which was specified in the controllers.yaml
173  */
174  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
175  {
176  std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
177  if (it != controllers_.end())
178  return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
179  else
180  ROS_FATAL_STREAM_NAMED(LOGNAME, "No such controller: " << name);
181  return moveit_controller_manager::MoveItControllerHandlePtr();
182  }
183 
184  /*
185  * Get the list of controller names.
186  */
187  void getControllersList(std::vector<std::string>& names) override
188  {
189  for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin();
190  it != controllers_.end(); ++it)
191  names.push_back(it->first);
192  ROS_INFO_STREAM_NAMED(LOGNAME, "Returned " << names.size() << " controllers in list");
193  }
194 
195  /*
196  * This plugin assumes that all controllers are already active -- and if they are not, well, it has no way to deal
197  * with it anyways!
198  */
199  void getActiveControllers(std::vector<std::string>& names) override
200  {
201  getControllersList(names);
202  }
203 
204  /*
205  * Controller must be loaded to be active, see comment above about active controllers...
206  */
207  virtual void getLoadedControllers(std::vector<std::string>& names)
208  {
209  getControllersList(names);
210  }
211 
212  /*
213  * Get the list of joints that a controller can control.
214  */
215  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
216  {
217  std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
218  if (it != controllers_.end())
219  {
220  it->second->getJoints(joints);
221  }
222  else
223  {
225  "The joints for controller '%s' are not known. Perhaps the controller configuration is "
226  "not loaded on the param server?",
227  name.c_str());
228  joints.clear();
229  }
230  }
231 
233  getControllerState(const std::string& name) override
234  {
235  return controller_states_[name];
236  }
237 
238  /* Cannot switch our controllers */
239  bool switchControllers(const std::vector<std::string>& /* activate */,
240  const std::vector<std::string>& /* deactivate */) override
241  {
242  return false;
243  }
244 
245 protected:
247  std::map<std::string, ActionBasedControllerHandleBasePtr> controllers_;
248  std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState> controller_states_;
249 };
250 
251 } // end namespace moveit_simple_controller_manager
252 
XmlRpc::XmlRpcValue::size
int size() const
moveit::core
moveit_simple_controller_manager
Definition: action_based_controller_handle.h:45
moveit::core::isStruct
bool isStruct(const XmlRpc::XmlRpcValue &v, const std::vector< std::string > &keys={}, const std::string &name="")
moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllerState
moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name) override
Definition: moveit_simple_controller_manager.cpp:233
ros.h
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_controller_manager::MoveItControllerManager)
moveit_controller_manager::MoveItControllerManager::ControllerState::active_
bool active_
moveit_simple_controller_manager::MoveItSimpleControllerManager
Definition: moveit_simple_controller_manager.cpp:53
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit_simple_controller_manager::MoveItSimpleControllerManager::controller_states_
std::map< std::string, moveit_controller_manager::MoveItControllerManager::ControllerState > controller_states_
Definition: moveit_simple_controller_manager.cpp:248
follow_joint_trajectory_controller_handle.h
moveit_simple_controller_manager::MoveItSimpleControllerManager::MoveItSimpleControllerManager
MoveItSimpleControllerManager()
Definition: moveit_simple_controller_manager.cpp:56
moveit_simple_controller_manager::MoveItSimpleControllerManager::node_handle_
ros::NodeHandle node_handle_
Definition: moveit_simple_controller_manager.cpp:246
name
std::string name
ROS_FATAL_STREAM_NAMED
#define ROS_FATAL_STREAM_NAMED(name, args)
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
moveit_simple_controller_manager::MoveItSimpleControllerManager::getActiveControllers
void getActiveControllers(std::vector< std::string > &names) override
Definition: moveit_simple_controller_manager.cpp:199
moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllerHandle
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name) override
Definition: moveit_simple_controller_manager.cpp:174
moveit_simple_controller_manager::GripperControllerHandle
Definition: gripper_controller_handle.h:83
moveit_simple_controller_manager::ActionBasedControllerHandle::isConnected
bool isConnected() const
Definition: action_based_controller_handle.h:130
moveit_controller_manager::MoveItControllerManager
moveit::core::LOGNAME
const std::string LOGNAME
XmlRpc::XmlRpcValue::hasMember
bool hasMember(const std::string &name) const
moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle
Definition: follow_joint_trajectory_controller_handle.h:82
gripper_controller_handle.h
moveit::core::isArray
bool isArray(const XmlRpc::XmlRpcValue &v, size_t size=0, const std::string &name="", const std::string &description="")
class_list_macros.hpp
ROS_WARN_NAMED
#define ROS_WARN_NAMED(name,...)
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
moveit_simple_controller_manager::MoveItSimpleControllerManager::switchControllers
bool switchControllers(const std::vector< std::string > &, const std::vector< std::string > &) override
Definition: moveit_simple_controller_manager.cpp:239
moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllersList
void getControllersList(std::vector< std::string > &names) override
Definition: moveit_simple_controller_manager.cpp:187
moveit_simple_controller_manager::MoveItSimpleControllerManager::getControllerJoints
void getControllerJoints(const std::string &name, std::vector< std::string > &joints) override
Definition: moveit_simple_controller_manager.cpp:215
moveit_simple_controller_manager::MoveItSimpleControllerManager::controllers_
std::map< std::string, ActionBasedControllerHandleBasePtr > controllers_
Definition: moveit_simple_controller_manager.cpp:247
moveit_simple_controller_manager::MoveItSimpleControllerManager::getLoadedControllers
virtual void getLoadedControllers(std::vector< std::string > &names)
Definition: moveit_simple_controller_manager.cpp:207
xmlrpc_casts.h
XmlRpc::XmlRpcValue
ros::NodeHandle
action_based_controller_handle.h
moveit_controller_manager::MoveItControllerManager::ControllerState::default_
bool default_


moveit_simple_controller_manager
Author(s): Michael Ferguson
autogenerated on Sat Mar 15 2025 02:27:51