controller_manager_plugin.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2015, Fraunhofer IPA
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Fraunhofer IPA nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Mathias Lüdtke */
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));  // without namespace
00133       }
00134       if (loader_.isClassAvailable(c.type))
00135       {
00136         std::string absname = getAbsName(c.name);
00137         managed_controllers_.insert(std::make_pair(absname, c));  // with namespace
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       {  // create allocator is needed
00157         alloc_it = allocators_.insert(std::make_pair(type, loader_.createInstance(type))).first;
00158       }
00159 
00160       // Collect claimed resources across different hardware interfaces
00161       std::vector<std::string> resources;
00162       for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::const_iterator hir =
00163                controller.claimed_resources.begin();
00164            hir != controller.claimed_resources.end(); ++hir)
00165       {
00166         for (std::vector<std::string>::const_iterator r = hir->resources.begin(); r != hir->resources.end(); ++r)
00167         {
00168           resources.push_back(*r);
00169         }
00170       }
00171 
00172       moveit_controller_manager::MoveItControllerHandlePtr handle =
00173           alloc_it->second->alloc(name, resources);  // allocate handle
00174       if (handle)
00175         handles_.insert(std::make_pair(name, handle));
00176     }
00177   }
00178 
00184   std::string getAbsName(const std::string& name)
00185   {
00186     return ros::names::append(ns_, name);
00187   }
00188 
00189 public:
00193   MoveItControllerManager()
00194     : ns_(ros::NodeHandle("~").param("ros_control_namespace", std::string("/")))
00195     , loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
00196   {
00197     ROS_INFO_STREAM("Started moveit_ros_control_interface::MoveItControllerManager for namespace " << ns_);
00198   }
00199 
00204   MoveItControllerManager(const std::string& ns)
00205     : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
00206   {
00207   }
00208 
00214   virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
00215   {
00216     boost::mutex::scoped_lock lock(controllers_mutex_);
00217     HandleMap::iterator it = handles_.find(name);
00218     if (it != handles_.end())
00219     {  // controller is is manager by this interface
00220       return it->second;
00221     }
00222     return moveit_controller_manager::MoveItControllerHandlePtr();
00223   }
00224 
00229   virtual void getControllersList(std::vector<std::string>& names)
00230   {
00231     boost::mutex::scoped_lock lock(controllers_mutex_);
00232     discover();
00233 
00234     for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
00235     {
00236       names.push_back(it->first);
00237     }
00238   }
00239 
00244   virtual void getActiveControllers(std::vector<std::string>& names)
00245   {
00246     boost::mutex::scoped_lock lock(controllers_mutex_);
00247     discover();
00248 
00249     for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
00250     {
00251       if (isActive(it->second))
00252         names.push_back(it->first);
00253     }
00254   }
00255 
00261   virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
00262   {
00263     boost::mutex::scoped_lock lock(controllers_mutex_);
00264     ControllersMap::iterator it = managed_controllers_.find(name);
00265     if (it != managed_controllers_.end())
00266     {
00267       for (std::size_t i = 0; i < it->second.claimed_resources.size(); ++i)
00268       {
00269         std::vector<std::string>& resources = it->second.claimed_resources[i].resources;
00270         joints.insert(joints.end(), resources.begin(), resources.end());
00271       }
00272     }
00273   }
00274 
00280   virtual ControllerState getControllerState(const std::string& name)
00281   {
00282     boost::mutex::scoped_lock lock(controllers_mutex_);
00283     discover();
00284 
00285     ControllerState c;
00286     ControllersMap::iterator it = managed_controllers_.find(name);
00287     if (it != managed_controllers_.end())
00288     {
00289       c.active_ = isActive(it->second);
00290     }
00291     return c;
00292   }
00293 
00301   virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
00302   {
00303     boost::mutex::scoped_lock lock(controllers_mutex_);
00304     discover(true);
00305 
00306     typedef boost::bimap<std::string, std::string> resources_bimap;
00307 
00308     resources_bimap claimed_resources;
00309 
00310     // fill bimap with active controllers and their resources
00311     for (ControllersMap::iterator c = active_controllers_.begin(); c != active_controllers_.end(); ++c)
00312     {
00313       for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::iterator hir =
00314                c->second.claimed_resources.begin();
00315            hir != c->second.claimed_resources.end(); ++hir)
00316       {
00317         for (std::vector<std::string>::iterator r = hir->resources.begin(); r != hir->resources.end(); ++r)
00318         {
00319           claimed_resources.insert(resources_bimap::value_type(c->second.name, *r));
00320         }
00321       }
00322     }
00323 
00324     controller_manager_msgs::SwitchController srv;
00325 
00326     for (std::vector<std::string>::const_iterator it = deactivate.begin(); it != deactivate.end(); ++it)
00327     {
00328       ControllersMap::iterator c = managed_controllers_.find(*it);
00329       if (c != managed_controllers_.end())
00330       {  // controller belongs to this manager
00331         srv.request.stop_controllers.push_back(c->second.name);
00332         claimed_resources.right.erase(c->second.name);  // remove resources
00333       }
00334     }
00335 
00336     for (std::vector<std::string>::const_iterator it = activate.begin(); it != activate.end(); ++it)
00337     {
00338       ControllersMap::iterator c = managed_controllers_.find(*it);
00339       if (c != managed_controllers_.end())
00340       {  // controller belongs to this manager
00341         srv.request.start_controllers.push_back(c->second.name);
00342 
00343         for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::iterator hir =
00344                  c->second.claimed_resources.begin();
00345              hir != c->second.claimed_resources.end(); ++hir)
00346         {
00347           for (std::vector<std::string>::iterator r = hir->resources.begin(); r != hir->resources.end(); ++r)
00348           {  // for all claimed resource
00349             resources_bimap::right_const_iterator res = claimed_resources.right.find(*r);
00350             if (res != claimed_resources.right.end())
00351             {                                                       // resource is claimed
00352               srv.request.stop_controllers.push_back(res->second);  // add claiming controller to stop list
00353               claimed_resources.left.erase(res->second);            // remove claimed resources
00354             }
00355           }
00356         }
00357       }
00358     }
00359     srv.request.strictness = srv.request.STRICT;
00360 
00361     if (!srv.request.start_controllers.empty() || srv.request.stop_controllers.empty())
00362     {  // something to switch?
00363       if (!ros::service::call(getAbsName("controller_manager/switch_controller"), srv))
00364       {
00365         ROS_ERROR_STREAM("Could switch controllers at " << ns_);
00366       }
00367       discover(true);
00368       return srv.response.ok;
00369     }
00370     return true;
00371   }
00372 };
00377 class MoveItMultiControllerManager : public moveit_controller_manager::MoveItControllerManager
00378 {
00379   typedef std::map<std::string, moveit_ros_control_interface::MoveItControllerManagerPtr> ControllerManagersMap;
00380   ControllerManagersMap controller_managers_;
00381   ros::Time controller_managers_stamp_;
00382   boost::mutex controller_managers_mutex_;
00383 
00388   void discover()
00389   {
00390     if (!checkTimeout(controller_managers_stamp_, 1.0))
00391       return;
00392 
00393     XmlRpc::XmlRpcValue args, result, system_state;
00394     args[0] = ros::this_node::getName();
00395 
00396     if (!ros::master::execute("getSystemState", args, result, system_state, true))
00397     {
00398       return;
00399     }
00400 
00401     // refer to http://wiki.ros.org/ROS/Master_API#Name_service_and_system_state
00402     XmlRpc::XmlRpcValue services = system_state[2];
00403 
00404     for (int i = 0; i < services.size(); ++i)
00405     {
00406       std::string service = services[i][0];
00407       std::size_t found = service.find("controller_manager/list_controllers");
00408       if (found != std::string::npos)
00409       {
00410         std::string ns = service.substr(0, found);
00411         if (controller_managers_.find(ns) == controller_managers_.end())
00412         {  // create MoveItControllerManager if it does not exists
00413           ROS_INFO_STREAM("Adding controller_manager interface for node at namespace " << ns);
00414           controller_managers_.insert(
00415               std::make_pair(ns, boost::make_shared<moveit_ros_control_interface::MoveItControllerManager>(ns)));
00416         }
00417       }
00418     }
00419   }
00420 
00426   static std::string getNamespace(const std::string& name)
00427   {
00428     size_t pos = name.find('/', 1);
00429     if (pos == std::string::npos)
00430       pos = 0;
00431     return name.substr(0, pos + 1);
00432   }
00433 
00434 public:
00440   virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
00441   {
00442     boost::mutex::scoped_lock lock(controller_managers_mutex_);
00443 
00444     std::string ns = getNamespace(name);
00445     ControllerManagersMap::iterator it = controller_managers_.find(ns);
00446     if (it != controller_managers_.end())
00447     {
00448       return it->second->getControllerHandle(name);
00449     }
00450     return moveit_controller_manager::MoveItControllerHandlePtr();
00451   }
00452 
00457   virtual void getControllersList(std::vector<std::string>& names)
00458   {
00459     boost::mutex::scoped_lock lock(controller_managers_mutex_);
00460     discover();
00461 
00462     for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
00463     {
00464       it->second->getControllersList(names);
00465     }
00466   }
00467 
00472   virtual void getActiveControllers(std::vector<std::string>& names)
00473   {
00474     boost::mutex::scoped_lock lock(controller_managers_mutex_);
00475     discover();
00476 
00477     for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
00478     {
00479       it->second->getActiveControllers(names);
00480     }
00481   }
00482 
00488   virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
00489   {
00490     boost::mutex::scoped_lock lock(controller_managers_mutex_);
00491 
00492     std::string ns = getNamespace(name);
00493     ControllerManagersMap::iterator it = controller_managers_.find(ns);
00494     if (it != controller_managers_.end())
00495     {
00496       it->second->getControllerJoints(name, joints);
00497     }
00498   }
00499 
00505   virtual ControllerState getControllerState(const std::string& name)
00506   {
00507     boost::mutex::scoped_lock lock(controller_managers_mutex_);
00508 
00509     std::string ns = getNamespace(name);
00510     ControllerManagersMap::iterator it = controller_managers_.find(ns);
00511     if (it != controller_managers_.end())
00512     {
00513       return it->second->getControllerState(name);
00514     }
00515     return ControllerState();
00516   }
00517 
00524   virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
00525   {
00526     boost::mutex::scoped_lock lock(controller_managers_mutex_);
00527 
00528     for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
00529     {
00530       if (!it->second->switchControllers(activate, deactivate))
00531         return false;
00532     }
00533     return true;
00534   }
00535 };
00536 
00537 }  // namespace moveit_ros_control_interface
00538 
00539 PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::MoveItControllerManager,
00540                        moveit_controller_manager::MoveItControllerManager);
00541 
00542 PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::MoveItMultiControllerManager,
00543                        moveit_controller_manager::MoveItControllerManager);


moveit_ros_control_interface
Author(s): Mathias Lüdtke
autogenerated on Mon Jul 24 2017 02:22:38