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 #include <ros/ros.h>
00038 #include <moveit/controller_manager/controller_manager.h>
00039 #include <sensor_msgs/JointState.h>
00040 #include <pluginlib/class_list_macros.h>
00041 #include <map>
00042
00043 namespace moveit_fake_controller_manager
00044 {
00045
00046 class FakeControllerHandle : public moveit_controller_manager::MoveItControllerHandle
00047 {
00048 public:
00049 FakeControllerHandle(const std::string &name, ros::NodeHandle &nh, const std::vector<std::string> &joints) :
00050 moveit_controller_manager::MoveItControllerHandle(name),
00051 nh_(nh),
00052 joints_(joints)
00053 {
00054 std::stringstream ss;
00055 ss << "Fake controller '" << name << "' with joints [ ";
00056 for (std::size_t i = 0 ; i < joints.size() ; ++i)
00057 ss << joints[i] << " ";
00058 ss << "]";
00059 ROS_INFO("%s", ss.str().c_str());
00060 pub_ = nh_.advertise<sensor_msgs::JointState>("fake_controller_joint_states", 100, false);
00061 }
00062
00063 void getJoints(std::vector<std::string> &joints) const
00064 {
00065 joints = joints_;
00066 }
00067
00068 virtual bool sendTrajectory(const moveit_msgs::RobotTrajectory &t)
00069 {
00070 ROS_INFO("Fake execution of trajectory");
00071 if (!t.joint_trajectory.points.empty())
00072 {
00073 sensor_msgs::JointState js;
00074 js.header = t.joint_trajectory.header;
00075 js.name = t.joint_trajectory.joint_names;
00076 js.position = t.joint_trajectory.points.back().positions;
00077 js.velocity = t.joint_trajectory.points.back().velocities;
00078 js.effort = t.joint_trajectory.points.back().effort;
00079 pub_.publish(js);
00080 }
00081
00082 return true;
00083 }
00084
00085 virtual bool cancelExecution()
00086 {
00087 ROS_INFO("Fake trajectory execution cancel");
00088 return true;
00089 }
00090
00091 virtual bool waitForExecution(const ros::Duration &)
00092 {
00093 sleep(1);
00094 return true;
00095 }
00096
00097 virtual moveit_controller_manager::ExecutionStatus getLastExecutionStatus()
00098 {
00099 return moveit_controller_manager::ExecutionStatus(moveit_controller_manager::ExecutionStatus::SUCCEEDED);
00100 }
00101
00102 private:
00103 ros::NodeHandle nh_;
00104 std::vector<std::string> joints_;
00105 ros::Publisher pub_;
00106 };
00107
00108
00109 class MoveItFakeControllerManager : public moveit_controller_manager::MoveItControllerManager
00110 {
00111 public:
00112
00113 MoveItFakeControllerManager() : node_handle_("~")
00114 {
00115 if (!node_handle_.hasParam("controller_list"))
00116 {
00117 ROS_ERROR_STREAM("MoveItFakeControllerManager: No controller_list specified.");
00118 return;
00119 }
00120
00121 XmlRpc::XmlRpcValue controller_list;
00122 node_handle_.getParam("controller_list", controller_list);
00123 if (controller_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00124 {
00125 ROS_ERROR("MoveItFakeControllerManager: controller_list should be specified as an array");
00126 return;
00127 }
00128
00129
00130 for (int i = 0 ; i < controller_list.size() ; ++i)
00131 {
00132 if (!controller_list[i].hasMember("name") || !controller_list[i].hasMember("joints"))
00133 {
00134 ROS_ERROR("MoveItFakeControllerManager: Name and joints must be specifed for each controller");
00135 continue;
00136 }
00137
00138 try
00139 {
00140 std::string name = std::string(controller_list[i]["name"]);
00141
00142 if (controller_list[i]["joints"].getType() != XmlRpc::XmlRpcValue::TypeArray)
00143 {
00144 ROS_ERROR_STREAM("MoveItFakeControllerManager: The list of joints for controller " << name << " is not specified as an array");
00145 continue;
00146 }
00147 std::vector<std::string> joints;
00148 for (int j = 0 ; j < controller_list[i]["joints"].size() ; ++j)
00149 joints.push_back(std::string(controller_list[i]["joints"][j]));
00150
00151 controllers_[name].reset(new FakeControllerHandle(name, node_handle_, joints));
00152 }
00153 catch (...)
00154 {
00155 ROS_ERROR("MoveItFakeControllerManager: Unable to parse controller information");
00156 }
00157 }
00158 }
00159
00160 virtual ~MoveItFakeControllerManager()
00161 {
00162 }
00163
00164
00165
00166
00167 virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
00168 {
00169 std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>::const_iterator it = controllers_.find(name);
00170 if (it != controllers_.end())
00171 return it->second;
00172 else
00173 ROS_FATAL_STREAM("No such controller: " << name);
00174 return moveit_controller_manager::MoveItControllerHandlePtr();
00175 }
00176
00177
00178
00179
00180 virtual void getControllersList(std::vector<std::string> &names)
00181 {
00182 for (std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>::const_iterator it = controllers_.begin() ; it != controllers_.end() ; ++it)
00183 names.push_back(it->first);
00184 ROS_INFO_STREAM("Returned " << names.size() << " controllers in list");
00185 }
00186
00187
00188
00189
00190 virtual void getActiveControllers(std::vector<std::string> &names)
00191 {
00192 getControllersList(names);
00193 }
00194
00195
00196
00197
00198 virtual void getLoadedControllers(std::vector<std::string> &names)
00199 {
00200 getControllersList(names);
00201 }
00202
00203
00204
00205
00206 virtual void getControllerJoints(const std::string &name, std::vector<std::string> &joints)
00207 {
00208 std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>::const_iterator it = controllers_.find(name);
00209 if (it != controllers_.end())
00210 {
00211 static_cast<FakeControllerHandle*>(it->second.get())->getJoints(joints);
00212 }
00213 else
00214 {
00215 ROS_WARN("The joints for controller '%s' are not known. Perhaps the controller configuration is not loaded on the param server?", name.c_str());
00216 joints.clear();
00217 }
00218 }
00219
00220
00221
00222
00223 virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState(const std::string &name)
00224 {
00225 moveit_controller_manager::MoveItControllerManager::ControllerState state;
00226 state.active_ = true;
00227 state.default_ = true;
00228 return state;
00229 }
00230
00231
00232 virtual bool switchControllers(const std::vector<std::string> &activate, const std::vector<std::string> &deactivate) { return false; }
00233
00234 protected:
00235
00236 ros::NodeHandle node_handle_;
00237 std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> controllers_;
00238 };
00239
00240 }
00241
00242 PLUGINLIB_EXPORT_CLASS(moveit_fake_controller_manager::MoveItFakeControllerManager,
00243 moveit_controller_manager::MoveItControllerManager);