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
00039 #include <moveit/macros/class_forward.h>
00040
00041 #include <moveit_ros_control_interface/ControllerHandle.h>
00042
00043 #include <moveit/controller_manager/controller_manager.h>
00044
00045 #include <controller_manager_msgs/ListControllers.h>
00046 #include <controller_manager_msgs/SwitchController.h>
00047
00048 #include <pluginlib/class_list_macros.h>
00049 #include <map>
00050
00051 #include <pluginlib/class_loader.h>
00052
00053 #include <boost/bimap.hpp>
00054
00055 namespace moveit_ros_control_interface
00056 {
00064 bool checkTimeout(ros::Time& t, double timeout, bool force = false)
00065 {
00066 ros::Time now = ros::Time::now();
00067 if (force || (now - t) >= ros::Duration(timeout))
00068 {
00069 t = now;
00070 return true;
00071 }
00072 return false;
00073 }
00074
00075 MOVEIT_CLASS_FORWARD(MoveItControllerManager);
00076
00083 class MoveItControllerManager : public moveit_controller_manager::MoveItControllerManager
00084 {
00085 const std::string ns_;
00086 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
00087 typedef std::map<std::string, controller_manager_msgs::ControllerState> ControllersMap;
00088 ControllersMap managed_controllers_;
00089 ControllersMap active_controllers_;
00090 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
00091 AllocatorsMap allocators_;
00092
00093 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
00094 HandleMap handles_;
00095
00096 ros::Time controllers_stamp_;
00097 boost::mutex controllers_mutex_;
00098
00104 static bool isActive(const controller_manager_msgs::ControllerState& s)
00105 {
00106 return s.state == std::string("running");
00107 }
00108
00115 void discover(bool force = false)
00116 {
00117 if (!checkTimeout(controllers_stamp_, 1.0, force))
00118 return;
00119
00120 controller_manager_msgs::ListControllers srv;
00121 if (!ros::service::call(getAbsName("controller_manager/list_controllers"), srv))
00122 {
00123 ROS_WARN_STREAM("Failed to read controllers from " << ns_ << "controller_manager/list_controllers");
00124 }
00125 managed_controllers_.clear();
00126 active_controllers_.clear();
00127 for (size_t i = 0; i < srv.response.controller.size(); ++i)
00128 {
00129 const controller_manager_msgs::ControllerState& c = srv.response.controller[i];
00130 if (isActive(c))
00131 {
00132 active_controllers_.insert(std::make_pair(c.name, c));
00133 }
00134 if (loader_.isClassAvailable(c.type))
00135 {
00136 std::string absname = getAbsName(c.name);
00137 managed_controllers_.insert(std::make_pair(absname, c));
00138 allocate(absname, c);
00139 }
00140 }
00141 }
00142
00149 void allocate(const std::string& name, const controller_manager_msgs::ControllerState& controller)
00150 {
00151 if (handles_.find(name) == handles_.end())
00152 {
00153 const std::string& type = controller.type;
00154 AllocatorsMap::iterator alloc_it = allocators_.find(type);
00155 if (alloc_it == allocators_.end())
00156 {
00157 alloc_it = allocators_.insert(std::make_pair(type, loader_.createInstance(type))).first;
00158 }
00159 moveit_controller_manager::MoveItControllerHandlePtr handle =
00160 alloc_it->second->alloc(name, controller.resources);
00161 if (handle)
00162 handles_.insert(std::make_pair(name, handle));
00163 }
00164 }
00165
00171 std::string getAbsName(const std::string& name)
00172 {
00173 return ros::names::append(ns_, name);
00174 }
00175
00176 public:
00180 MoveItControllerManager()
00181 : ns_(ros::NodeHandle("~").param("ros_control_namespace", std::string("/")))
00182 , loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
00183 {
00184 ROS_INFO_STREAM("Started moveit_ros_control_interface::MoveItControllerManager for namespace " << ns_);
00185 }
00186
00191 MoveItControllerManager(const std::string& ns)
00192 : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
00193 {
00194 }
00195
00201 virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
00202 {
00203 boost::mutex::scoped_lock lock(controllers_mutex_);
00204 HandleMap::iterator it = handles_.find(name);
00205 if (it != handles_.end())
00206 {
00207 return it->second;
00208 }
00209 return moveit_controller_manager::MoveItControllerHandlePtr();
00210 }
00211
00216 virtual void getControllersList(std::vector<std::string>& names)
00217 {
00218 boost::mutex::scoped_lock lock(controllers_mutex_);
00219 discover();
00220
00221 for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
00222 {
00223 names.push_back(it->first);
00224 }
00225 }
00226
00231 virtual void getActiveControllers(std::vector<std::string>& names)
00232 {
00233 boost::mutex::scoped_lock lock(controllers_mutex_);
00234 discover();
00235
00236 for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
00237 {
00238 if (isActive(it->second))
00239 names.push_back(it->first);
00240 }
00241 }
00242
00248 virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
00249 {
00250 boost::mutex::scoped_lock lock(controllers_mutex_);
00251 ControllersMap::iterator it = managed_controllers_.find(name);
00252 if (it != managed_controllers_.end())
00253 {
00254 joints = it->second.resources;
00255 }
00256 }
00257
00263 virtual ControllerState getControllerState(const std::string& name)
00264 {
00265 boost::mutex::scoped_lock lock(controllers_mutex_);
00266 discover();
00267
00268 ControllerState c;
00269 ControllersMap::iterator it = managed_controllers_.find(name);
00270 if (it != managed_controllers_.end())
00271 {
00272 c.active_ = isActive(it->second);
00273 }
00274 return c;
00275 }
00276
00284 virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
00285 {
00286 boost::mutex::scoped_lock lock(controllers_mutex_);
00287 discover(true);
00288
00289 typedef boost::bimap<std::string, std::string> resources_bimap;
00290
00291 resources_bimap claimed_resources;
00292
00293
00294 for (ControllersMap::iterator c = active_controllers_.begin(); c != active_controllers_.end(); ++c)
00295 {
00296 for (std::vector<std::string>::iterator r = c->second.resources.begin(); r != c->second.resources.end(); ++r)
00297 {
00298 claimed_resources.insert(resources_bimap::value_type(c->second.name, *r));
00299 }
00300 }
00301
00302 controller_manager_msgs::SwitchController srv;
00303
00304 for (std::vector<std::string>::const_iterator it = deactivate.begin(); it != deactivate.end(); ++it)
00305 {
00306 ControllersMap::iterator c = managed_controllers_.find(*it);
00307 if (c != managed_controllers_.end())
00308 {
00309 srv.request.stop_controllers.push_back(c->second.name);
00310 claimed_resources.right.erase(c->second.name);
00311 }
00312 }
00313
00314 for (std::vector<std::string>::const_iterator it = activate.begin(); it != activate.end(); ++it)
00315 {
00316 ControllersMap::iterator c = managed_controllers_.find(*it);
00317 if (c != managed_controllers_.end())
00318 {
00319 srv.request.start_controllers.push_back(c->second.name);
00320
00321 for (std::vector<std::string>::iterator r = c->second.resources.begin(); r != c->second.resources.end(); ++r)
00322 {
00323 resources_bimap::right_const_iterator res = claimed_resources.right.find(*r);
00324 if (res != claimed_resources.right.end())
00325 {
00326 srv.request.stop_controllers.push_back(res->second);
00327 claimed_resources.left.erase(res->second);
00328 }
00329 }
00330 }
00331 }
00332 srv.request.strictness = srv.request.STRICT;
00333
00334 if (!srv.request.start_controllers.empty() || srv.request.stop_controllers.empty())
00335 {
00336 if (!ros::service::call(getAbsName("controller_manager/switch_controller"), srv))
00337 {
00338 ROS_ERROR_STREAM("Could switch controllers at " << ns_);
00339 }
00340 discover(true);
00341 return srv.response.ok;
00342 }
00343 return true;
00344 }
00345 };
00350 class MoveItMultiControllerManager : public moveit_controller_manager::MoveItControllerManager
00351 {
00352 typedef std::map<std::string, moveit_ros_control_interface::MoveItControllerManagerPtr> ControllerManagersMap;
00353 ControllerManagersMap controller_managers_;
00354 ros::Time controller_managers_stamp_;
00355 boost::mutex controller_managers_mutex_;
00356
00361 void discover()
00362 {
00363 if (!checkTimeout(controller_managers_stamp_, 1.0))
00364 return;
00365
00366 XmlRpc::XmlRpcValue args, result, system_state;
00367 args[0] = ros::this_node::getName();
00368
00369 if (!ros::master::execute("getSystemState", args, result, system_state, true))
00370 {
00371 return;
00372 }
00373
00374
00375 XmlRpc::XmlRpcValue services = system_state[2];
00376
00377 for (int i = 0; i < services.size(); ++i)
00378 {
00379 std::string service = services[i][0];
00380 std::size_t found = service.find("controller_manager/list_controllers");
00381 if (found != std::string::npos)
00382 {
00383 std::string ns = service.substr(0, found);
00384 if (controller_managers_.find(ns) == controller_managers_.end())
00385 {
00386 ROS_INFO_STREAM("Adding controller_manager interface for node at namespace " << ns);
00387 controller_managers_.insert(
00388 std::make_pair(ns, boost::make_shared<moveit_ros_control_interface::MoveItControllerManager>(ns)));
00389 }
00390 }
00391 }
00392 }
00393
00399 static std::string getNamespace(const std::string& name)
00400 {
00401 size_t pos = name.find('/', 1);
00402 if (pos == std::string::npos)
00403 pos = 0;
00404 return name.substr(0, pos + 1);
00405 }
00406
00407 public:
00413 virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
00414 {
00415 boost::mutex::scoped_lock lock(controller_managers_mutex_);
00416
00417 std::string ns = getNamespace(name);
00418 ControllerManagersMap::iterator it = controller_managers_.find(ns);
00419 if (it != controller_managers_.end())
00420 {
00421 return it->second->getControllerHandle(name);
00422 }
00423 return moveit_controller_manager::MoveItControllerHandlePtr();
00424 }
00425
00430 virtual void getControllersList(std::vector<std::string>& names)
00431 {
00432 boost::mutex::scoped_lock lock(controller_managers_mutex_);
00433 discover();
00434
00435 for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
00436 {
00437 it->second->getControllersList(names);
00438 }
00439 }
00440
00445 virtual void getActiveControllers(std::vector<std::string>& names)
00446 {
00447 boost::mutex::scoped_lock lock(controller_managers_mutex_);
00448 discover();
00449
00450 for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
00451 {
00452 it->second->getActiveControllers(names);
00453 }
00454 }
00455
00461 virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
00462 {
00463 boost::mutex::scoped_lock lock(controller_managers_mutex_);
00464
00465 std::string ns = getNamespace(name);
00466 ControllerManagersMap::iterator it = controller_managers_.find(ns);
00467 if (it != controller_managers_.end())
00468 {
00469 it->second->getControllerJoints(name, joints);
00470 }
00471 }
00472
00478 virtual ControllerState getControllerState(const std::string& name)
00479 {
00480 boost::mutex::scoped_lock lock(controller_managers_mutex_);
00481
00482 std::string ns = getNamespace(name);
00483 ControllerManagersMap::iterator it = controller_managers_.find(ns);
00484 if (it != controller_managers_.end())
00485 {
00486 return it->second->getControllerState(name);
00487 }
00488 return ControllerState();
00489 }
00490
00497 virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
00498 {
00499 boost::mutex::scoped_lock lock(controller_managers_mutex_);
00500
00501 for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
00502 {
00503 if (!it->second->switchControllers(activate, deactivate))
00504 return false;
00505 }
00506 return true;
00507 }
00508 };
00509
00510 }
00511
00512 PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::MoveItControllerManager,
00513 moveit_controller_manager::MoveItControllerManager);
00514
00515 PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::MoveItMultiControllerManager,
00516 moveit_controller_manager::MoveItControllerManager);