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>
60 template <
typename... T>
61 std::string concatenateWithSeparator(
char separator, T... content)
64 (result.append(content).append({ separator }), ...);
65 result.erase(result.end() - 1);
76 template <
typename... T>
77 std::string makeParameterName(T... strings)
79 return concatenateWithSeparator<T...>(
'.', strings...);
93 static const std::string PARAM_BASE_NAME =
"moveit_simple_controller_manager";
101 void initialize(
const rclcpp::Node::SharedPtr& node)
override
104 if (!
node_->has_parameter(makeParameterName(PARAM_BASE_NAME,
"controller_names")))
106 RCLCPP_ERROR_STREAM(
getLogger(),
"No controller_names specified.");
109 rclcpp::Parameter controller_names_param;
110 node_->get_parameter(makeParameterName(PARAM_BASE_NAME,
"controller_names"), controller_names_param);
111 if (controller_names_param.get_type() != rclcpp::ParameterType::PARAMETER_STRING_ARRAY)
113 RCLCPP_ERROR(
getLogger(),
"Parameter controller_names should be specified as a string array");
116 std::vector<std::string> controller_names = controller_names_param.as_string_array();
118 for (
const std::string& controller_name : controller_names)
122 std::string action_ns;
123 const std::string& action_ns_param = makeParameterName(PARAM_BASE_NAME, controller_name,
"action_ns");
124 if (!
node_->get_parameter(action_ns_param, action_ns))
126 RCLCPP_ERROR_STREAM(
getLogger(),
"No action namespace specified for controller `"
127 << controller_name <<
"` through parameter `" << action_ns_param <<
'`');
132 if (!
node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name,
"type"), type))
134 RCLCPP_ERROR_STREAM(
getLogger(),
"No type specified for controller " << controller_name);
138 std::vector<std::string> controller_joints;
139 if (!
node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name,
"joints"), controller_joints) ||
140 controller_joints.empty())
142 RCLCPP_ERROR_STREAM(
getLogger(),
"No joints specified for controller " << controller_name);
146 ActionBasedControllerHandleBasePtr new_handle;
147 if (type ==
"GripperCommand")
150 const std::string& max_effort_param = makeParameterName(PARAM_BASE_NAME, controller_name,
"max_effort");
151 if (!node->get_parameter(max_effort_param, max_effort))
153 RCLCPP_INFO_STREAM(
getLogger(),
"Max effort set to 0.0");
157 new_handle = std::make_shared<GripperControllerHandle>(
node_, controller_name, action_ns, max_effort);
158 bool parallel_gripper =
false;
159 if (
node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name,
"parallel"), parallel_gripper) &&
162 if (controller_joints.size() != 2)
164 RCLCPP_ERROR_STREAM(
getLogger(),
"Parallel Gripper requires exactly two joints, "
165 << controller_joints.size() <<
" are specified");
169 ->setParallelJawGripper(controller_joints[0], controller_joints[1]);
173 std::string command_joint;
174 if (!
node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name,
"command_joint"),
176 command_joint = controller_joints[0];
182 node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, controller_name,
"allow_failure"), allow_failure,
186 RCLCPP_INFO_STREAM(
getLogger(),
"Added GripperCommand controller for " << controller_name);
189 else if (type ==
"FollowJointTrajectory")
191 new_handle = std::make_shared<FollowJointTrajectoryControllerHandle>(
node_, controller_name, action_ns);
192 RCLCPP_INFO_STREAM(
getLogger(),
"Added FollowJointTrajectory controller for " << controller_name);
197 RCLCPP_ERROR_STREAM(
getLogger(),
"Unknown controller type: " << type);
207 node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, controller_name,
"default"), state.
default_,
false);
213 for (
const std::string& controller_joint : controller_joints)
214 new_handle->addJoint(controller_joint);
218 RCLCPP_ERROR_STREAM(
getLogger(),
"Caught unknown exception while parsing controller information");
227 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.find(
name);
230 return static_cast<moveit_controller_manager::MoveItControllerHandlePtr
>(it->second);
234 RCLCPP_FATAL_STREAM(
getLogger(),
"No such controller: " <<
name);
236 return moveit_controller_manager::MoveItControllerHandlePtr();
244 for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.begin();
246 names.push_back(it->first);
247 RCLCPP_INFO_STREAM(
getLogger(),
"Returned " << names.size() <<
" controllers in list");
272 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.find(
name);
275 it->second->getJoints(joints);
280 "The joints for controller '%s' are not known. Perhaps the controller configuration is "
281 "not loaded on the param server?",
295 const std::vector<std::string>& )
override
302 std::map<std::string, ActionBasedControllerHandleBasePtr>
controllers_;
303 std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState>
controller_states_;
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt,...
MoveItSimpleControllerManager()=default
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.
~MoveItSimpleControllerManager() override=default
void initialize(const rclcpp::Node::SharedPtr &node) override
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.
rclcpp::Node::SharedPtr node_
void getControllersList(std::vector< std::string > &names) override
Get the list of known controller names.
virtual void getLoadedControllers(std::vector< std::string > &names)
PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_controller_manager::MoveItControllerManager)
rclcpp::Logger getLogger()
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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...