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>
59 template <
typename... T>
60 std::string concatenateWithSeparator(
char separator, T... content)
63 (result.append(content).append({ separator }), ...);
64 result.erase(result.end() - 1);
75 template <
typename... T>
76 std::string makeParameterName(T... strings)
78 return concatenateWithSeparator<T...>(
'.', strings...);
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";
94 void initialize(
const rclcpp::Node::SharedPtr& node)
override
97 if (!
node_->has_parameter(makeParameterName(PARAM_BASE_NAME,
"controller_names")))
99 RCLCPP_ERROR_STREAM(LOGGER,
"No controller_names specified.");
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)
106 RCLCPP_ERROR(LOGGER,
"Parameter controller_names should be specified as a string array");
109 std::vector<std::string> controller_names = controller_names_param.as_string_array();
111 for (
const std::string& controller_name : controller_names)
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))
119 RCLCPP_ERROR_STREAM(LOGGER,
"No action namespace specified for controller `"
120 << controller_name <<
"` through parameter `" << action_ns_param <<
"`");
125 if (!
node_->get_parameter(makeParameterName(PARAM_BASE_NAME, controller_name,
"type"),
type))
127 RCLCPP_ERROR_STREAM(LOGGER,
"No type specified for controller " << controller_name);
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())
135 RCLCPP_ERROR_STREAM(LOGGER,
"No joints specified for controller " << controller_name);
139 ActionBasedControllerHandleBasePtr new_handle;
140 if (
type ==
"GripperCommand")
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))
146 RCLCPP_INFO_STREAM(LOGGER,
"Max effort set to 0.0");
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)
154 if (controller_joints.size() != 2)
156 RCLCPP_ERROR_STREAM(LOGGER,
"Parallel Gripper requires exactly two joints, " << controller_joints.size()
157 <<
" are specified");
161 ->setParallelJawGripper(controller_joints[0], controller_joints[1]);
165 std::string command_joint;
166 if (!
node_->get_parameter(makeParameterName(PARAM_BASE_NAME,
"command_joint"), command_joint))
167 command_joint = controller_joints[0];
173 node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME,
"allow_failure"), allow_failure,
false);
176 RCLCPP_INFO_STREAM(LOGGER,
"Added GripperCommand controller for " << controller_name);
179 else if (
type ==
"FollowJointTrajectory")
181 new_handle = std::make_shared<FollowJointTrajectoryControllerHandle>(
node_, controller_name, action_ns);
182 RCLCPP_INFO_STREAM(LOGGER,
"Added FollowJointTrajectory controller for " << controller_name);
187 RCLCPP_ERROR_STREAM(LOGGER,
"Unknown controller type: " <<
type);
197 node_->get_parameter_or(makeParameterName(PARAM_BASE_NAME, controller_name,
"default"), state.
default_,
false);
203 for (
const std::string& controller_joint : controller_joints)
204 new_handle->addJoint(controller_joint);
208 RCLCPP_ERROR_STREAM(LOGGER,
"Caught unknown exception while parsing controller information");
217 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.find(
name);
219 return static_cast<moveit_controller_manager::MoveItControllerHandlePtr
>(it->second);
221 RCLCPP_FATAL_STREAM(LOGGER,
"No such controller: " <<
name);
222 return moveit_controller_manager::MoveItControllerHandlePtr();
230 for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.begin();
232 names.push_back(it->first);
233 RCLCPP_INFO_STREAM(LOGGER,
"Returned " << names.size() <<
" controllers in list");
258 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.find(
name);
261 it->second->getJoints(joints);
266 "The joints for controller '%s' are not known. Perhaps the controller configuration is "
267 "not loaded on the param server?",
281 const std::vector<std::string>& )
override
288 std::map<std::string, ActionBasedControllerHandleBasePtr>
controllers_;
289 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)
const rclcpp::Logger 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...