63 ROS_ERROR(
"Parameter controller_list should be specified as an array");
68 for (
int i = 0; i < controller_list.
size(); ++i)
70 if (!controller_list[i].hasMember(
"name") || !controller_list[i].
hasMember(
"joints"))
78 std::string name = std::string(controller_list[i][
"name"]);
80 std::string action_ns;
81 if (controller_list[i].hasMember(
"ns"))
84 action_ns = std::string(controller_list[i][
"ns"]);
85 ROS_WARN_NAMED(
"manager",
"Use of 'ns' is deprecated, use 'action_ns' instead.");
87 else if (controller_list[i].hasMember(
"action_ns"))
88 action_ns = std::string(controller_list[i][
"action_ns"]);
90 ROS_WARN_NAMED(
"manager",
"Please note that 'action_ns' no longer has a default value.");
95 <<
" is not specified as an array");
99 if (!controller_list[i].hasMember(
"type"))
105 std::string type = std::string(controller_list[i][
"type"]);
107 ActionBasedControllerHandleBasePtr new_handle;
108 if (type ==
"GripperCommand")
111 if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
113 if (controller_list[i].hasMember(
"parallel"))
115 if (controller_list[i][
"joints"].size() != 2)
121 ->setParallelJawGripper(controller_list[i][
"joints"][0], controller_list[i][
"joints"][1]);
125 if (controller_list[i].hasMember(
"command_joint"))
126 static_cast<GripperControllerHandle*>(new_handle.get())
127 ->setCommandJoint(controller_list[i][
"command_joint"]);
130 ->setCommandJoint(controller_list[i][
"joints"][0]);
133 if (controller_list[i].hasMember(
"allow_failure"))
134 static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(
true);
140 else if (type ==
"FollowJointTrajectory")
143 if (static_cast<FollowJointTrajectoryControllerHandle*>(new_handle.get())->isConnected())
161 for (
int j = 0; j < controller_list[i][
"joints"].
size(); ++j)
162 controllers_[name]->addJoint(std::string(controller_list[i][
"joints"][j]));
180 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.find(name);
182 return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
185 return moveit_controller_manager::MoveItControllerHandlePtr();
193 for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.begin();
195 names.push_back(it->first);
221 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it =
controllers_.find(name);
224 it->second->getJoints(joints);
228 ROS_WARN_NAMED(
"manager",
"The joints for controller '%s' are not known. Perhaps the controller configuration is " 229 "not loaded on the param server?",
248 virtual bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
255 std::map<std::string, ActionBasedControllerHandleBasePtr>
controllers_;
virtual void getActiveControllers(std::vector< std::string > &names)
virtual void getLoadedControllers(std::vector< std::string > &names)
ros::NodeHandle node_handle_
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_WARN_NAMED(name,...)
#define ROS_INFO_STREAM_NAMED(name, args)
PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_controller_manager::MoveItControllerManager)
Type const & getType() const
virtual void getControllersList(std::vector< std::string > &names)
MoveItSimpleControllerManager()
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
#define ROS_FATAL_STREAM_NAMED(name, args)
bool hasMember(const std::string &name) const
bool getParam(const std::string &key, std::string &s) const
virtual ~MoveItSimpleControllerManager()
std::map< std::string, ActionBasedControllerHandleBasePtr > controllers_
bool hasParam(const std::string &key) const
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)