Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <ros/ros.h>
00039 #include <moveit_simple_controller_manager/action_based_controller_handle.h>
00040 #include <moveit_simple_controller_manager/gripper_controller_handle.h>
00041 #include <moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h>
00042 #include <pluginlib/class_list_macros.h>
00043 #include <algorithm>
00044 #include <map>
00045
00046 namespace moveit_simple_controller_manager
00047 {
00048 class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItControllerManager
00049 {
00050 public:
00051 MoveItSimpleControllerManager() : node_handle_("~")
00052 {
00053 if (!node_handle_.hasParam("controller_list"))
00054 {
00055 ROS_ERROR_STREAM("No controller_list specified.");
00056 return;
00057 }
00058
00059 XmlRpc::XmlRpcValue controller_list;
00060 node_handle_.getParam("controller_list", controller_list);
00061 if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00062 {
00063 ROS_ERROR("Parameter controller_list should be specified as an array");
00064 return;
00065 }
00066
00067
00068 for (int i = 0; i < controller_list.size(); ++i)
00069 {
00070 if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
00071 {
00072 ROS_ERROR("Name and joints must be specifed for each controller");
00073 continue;
00074 }
00075
00076 try
00077 {
00078 std::string name = std::string(controller_list[i]["name"]);
00079
00080 std::string action_ns;
00081 if (controller_list[i].hasMember("ns"))
00082 {
00083
00084 action_ns = std::string(controller_list[i]["ns"]);
00085 ROS_WARN("Use of 'ns' is deprecated, use 'action_ns' instead.");
00086 }
00087 else if (controller_list[i].hasMember("action_ns"))
00088 action_ns = std::string(controller_list[i]["action_ns"]);
00089 else
00090 ROS_WARN("Please note that 'action_ns' no longer has a default value.");
00091
00092 if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
00093 {
00094 ROS_ERROR_STREAM("The list of joints for controller " << name << " is not specified as an array");
00095 continue;
00096 }
00097
00098 if (!controller_list[i].hasMember("type"))
00099 {
00100 ROS_ERROR_STREAM("No type specified for controller " << name);
00101 continue;
00102 }
00103
00104 std::string type = std::string(controller_list[i]["type"]);
00105
00106 ActionBasedControllerHandleBasePtr new_handle;
00107 if (type == "GripperCommand")
00108 {
00109 new_handle.reset(new GripperControllerHandle(name, action_ns));
00110 if (static_cast<GripperControllerHandle*>(new_handle.get())->isConnected())
00111 {
00112 if (controller_list[i].hasMember("parallel"))
00113 {
00114 if (controller_list[i]["joints"].size() != 2)
00115 {
00116 ROS_ERROR_STREAM("MoveItSimpleControllerManager: Parallel Gripper requires exactly two joints");
00117 continue;
00118 }
00119 static_cast<GripperControllerHandle*>(new_handle.get())
00120 ->setParallelJawGripper(controller_list[i]["joints"][0], controller_list[i]["joints"][1]);
00121 }
00122 else
00123 {
00124 if (controller_list[i].hasMember("command_joint"))
00125 static_cast<GripperControllerHandle*>(new_handle.get())
00126 ->setCommandJoint(controller_list[i]["command_joint"]);
00127 else
00128 static_cast<GripperControllerHandle*>(new_handle.get())
00129 ->setCommandJoint(controller_list[i]["joints"][0]);
00130 }
00131
00132 if (controller_list[i].hasMember("allow_failure"))
00133 static_cast<GripperControllerHandle*>(new_handle.get())->allowFailure(true);
00134
00135 ROS_INFO_STREAM("Added GripperCommand controller for " << name);
00136 controllers_[name] = new_handle;
00137 }
00138 }
00139 else if (type == "FollowJointTrajectory")
00140 {
00141 new_handle.reset(new FollowJointTrajectoryControllerHandle(name, action_ns));
00142 if (static_cast<FollowJointTrajectoryControllerHandle*>(new_handle.get())->isConnected())
00143 {
00144 ROS_INFO_STREAM("Added FollowJointTrajectory controller for " << name);
00145 controllers_[name] = new_handle;
00146 }
00147 }
00148 else
00149 {
00150 ROS_ERROR("Unknown controller type: '%s'", type.c_str());
00151 continue;
00152 }
00153 if (!controllers_[name])
00154 {
00155 controllers_.erase(name);
00156 continue;
00157 }
00158
00159
00160 for (int j = 0; j < controller_list[i]["joints"].size(); ++j)
00161 controllers_[name]->addJoint(std::string(controller_list[i]["joints"][j]));
00162 }
00163 catch (...)
00164 {
00165 ROS_ERROR("Unable to parse controller information");
00166 }
00167 }
00168 }
00169
00170 virtual ~MoveItSimpleControllerManager()
00171 {
00172 }
00173
00174
00175
00176
00177 virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
00178 {
00179 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
00180 if (it != controllers_.end())
00181 return static_cast<moveit_controller_manager::MoveItControllerHandlePtr>(it->second);
00182 else
00183 ROS_FATAL_STREAM("No such controller: " << name);
00184 return moveit_controller_manager::MoveItControllerHandlePtr();
00185 }
00186
00187
00188
00189
00190 virtual void getControllersList(std::vector<std::string>& names)
00191 {
00192 for (std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.begin();
00193 it != controllers_.end(); ++it)
00194 names.push_back(it->first);
00195 ROS_INFO_STREAM("Returned " << names.size() << " controllers in list");
00196 }
00197
00198
00199
00200
00201
00202 virtual void getActiveControllers(std::vector<std::string>& names)
00203 {
00204 getControllersList(names);
00205 }
00206
00207
00208
00209
00210 virtual void getLoadedControllers(std::vector<std::string>& names)
00211 {
00212 getControllersList(names);
00213 }
00214
00215
00216
00217
00218 virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
00219 {
00220 std::map<std::string, ActionBasedControllerHandleBasePtr>::const_iterator it = controllers_.find(name);
00221 if (it != controllers_.end())
00222 {
00223 it->second->getJoints(joints);
00224 }
00225 else
00226 {
00227 ROS_WARN("The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on "
00228 "the param server?",
00229 name.c_str());
00230 joints.clear();
00231 }
00232 }
00233
00234
00235
00236
00237 virtual moveit_controller_manager::MoveItControllerManager::ControllerState
00238 getControllerState(const std::string& name)
00239 {
00240 moveit_controller_manager::MoveItControllerManager::ControllerState state;
00241 state.active_ = true;
00242 state.default_ = true;
00243 return state;
00244 }
00245
00246
00247 virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
00248 {
00249 return false;
00250 }
00251
00252 protected:
00253 ros::NodeHandle node_handle_;
00254 std::map<std::string, ActionBasedControllerHandleBasePtr> controllers_;
00255 };
00256
00257 }
00258
00259 PLUGINLIB_EXPORT_CLASS(moveit_simple_controller_manager::MoveItSimpleControllerManager,
00260 moveit_controller_manager::MoveItControllerManager);