49 const std::string
LOGNAME(
"SimpleControllerManager");
58 if (!node_handle_.hasParam(
"controller_list"))
65 node_handle_.getParam(
"controller_list", controller_list);
73 for (
int i = 0; i < controller_list.
size(); ++i)
75 if (!
isStruct(controller_list[i], {
"name",
"joints",
"action_ns",
"type" }))
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"]);
87 if (!
isArray(controller_list[i][
"joints"]))
90 "The list of joints for controller " <<
name <<
" is not specified as an array");
94 ActionBasedControllerHandleBasePtr new_handle;
95 if (type ==
"GripperCommand")
97 const double max_effort =
98 controller_list[i].
hasMember(
"max_effort") ? double(controller_list[i][
"max_effort"]) : 0.0;
100 new_handle = std::make_shared<GripperControllerHandle>(
name, action_ns, max_effort);
103 if (controller_list[i].hasMember(
"parallel"))
105 if (controller_list[i][
"joints"].size() != 2)
111 ->setParallelJawGripper(controller_list[i][
"joints"][0], controller_list[i][
"joints"][1]);
115 if (controller_list[i].hasMember(
"command_joint"))
117 ->setCommandJoint(controller_list[i][
"command_joint"]);
122 if (controller_list[i].hasMember(
"allow_failure"))
126 controllers_[
name] = new_handle;
129 else if (type ==
"FollowJointTrajectory")
133 if (h->isConnected())
136 controllers_[
name] = new_handle;
144 if (!controllers_[
name])
146 controllers_.erase(
name);
151 state.
default_ = controller_list[i].
hasMember(
"default") ? (bool)controller_list[i][
"default"] :
false;
154 controller_states_[
name] = state;
157 for (
int j = 0; j < controller_list[i][
"joints"].
size(); ++j)
158 new_handle->addJoint(std::string(controller_list[i][
"joints"][j]));
160 new_handle->configure(controller_list[i]);
174 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
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);
181 return moveit_controller_manager::MoveItControllerHandlePtr();
189 for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin();
190 it != controllers_.end(); ++it)
191 names.push_back(it->first);
201 getControllersList(names);
209 getControllersList(names);
217 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(
name);
218 if (it != controllers_.end())
220 it->second->getJoints(joints);
225 "The joints for controller '%s' are not known. Perhaps the controller configuration is "
226 "not loaded on the param server?",
235 return controller_states_[
name];
240 const std::vector<std::string>& )
override
247 std::map<std::string, ActionBasedControllerHandleBasePtr>
controllers_;
248 std::map<std::string, moveit_controller_manager::MoveItControllerManager::ControllerState>
controller_states_;