controller_manager_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, Fraunhofer IPA
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Fraunhofer IPA nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Mathias Lüdtke */
36 
37 #include <ros/ros.h>
38 
40 
42 
44 
45 #include <controller_manager_msgs/ListControllers.h>
46 #include <controller_manager_msgs/SwitchController.h>
47 
50 
51 #include <boost/bimap.hpp>
52 
53 #include <map>
54 #include <memory>
55 
57 {
65 bool checkTimeout(ros::Time& t, double timeout, bool force = false)
66 {
67  ros::Time now = ros::Time::now();
68  if (force || (now - t) >= ros::Duration(timeout))
69  {
70  t = now;
71  return true;
72  }
73  return false;
74 }
75 
77 
85 {
86  const std::string ns_;
88  typedef std::map<std::string, controller_manager_msgs::ControllerState> ControllersMap;
89  ControllersMap managed_controllers_;
90  ControllersMap active_controllers_;
91  typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
92  AllocatorsMap allocators_;
93 
94  typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
95  HandleMap handles_;
96 
98  boost::mutex controllers_mutex_;
99 
105  static bool isActive(const controller_manager_msgs::ControllerState& s)
106  {
107  return s.state == std::string("running");
108  }
109 
116  void discover(bool force = false)
117  {
118  if (!checkTimeout(controllers_stamp_, 1.0, force))
119  return;
120 
121  controller_manager_msgs::ListControllers srv;
122  if (!ros::service::call(getAbsName("controller_manager/list_controllers"), srv))
123  {
124  ROS_WARN_STREAM("Failed to read controllers from " << ns_ << "controller_manager/list_controllers");
125  }
126  managed_controllers_.clear();
127  active_controllers_.clear();
128  for (size_t i = 0; i < srv.response.controller.size(); ++i)
129  {
130  const controller_manager_msgs::ControllerState& c = srv.response.controller[i];
131  if (isActive(c))
132  {
133  active_controllers_.insert(std::make_pair(c.name, c)); // without namespace
134  }
135  if (loader_.isClassAvailable(c.type))
136  {
137  std::string absname = getAbsName(c.name);
138  managed_controllers_.insert(std::make_pair(absname, c)); // with namespace
139  allocate(absname, c);
140  }
141  }
142  }
143 
150  void allocate(const std::string& name, const controller_manager_msgs::ControllerState& controller)
151  {
152  if (handles_.find(name) == handles_.end())
153  {
154  const std::string& type = controller.type;
155  AllocatorsMap::iterator alloc_it = allocators_.find(type);
156  if (alloc_it == allocators_.end())
157  { // create allocator is needed
158  alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
159  }
160 
161  std::vector<std::string> resources;
162 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL)
163  resources = controller.resources;
164 #else
165  // Collect claimed resources across different hardware interfaces
166  for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::const_iterator hir =
167  controller.claimed_resources.begin();
168  hir != controller.claimed_resources.end(); ++hir)
169  {
170  for (std::vector<std::string>::const_iterator r = hir->resources.begin(); r != hir->resources.end(); ++r)
171  {
172  resources.push_back(*r);
173  }
174  }
175 #endif
176 
177  moveit_controller_manager::MoveItControllerHandlePtr handle =
178  alloc_it->second->alloc(name, resources); // allocate handle
179  if (handle)
180  handles_.insert(std::make_pair(name, handle));
181  }
182  }
183 
189  std::string getAbsName(const std::string& name)
190  {
191  return ros::names::append(ns_, name);
192  }
193 
194 public:
199  : ns_(ros::NodeHandle("~").param("ros_control_namespace", std::string("/")))
200  , loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
201  {
202  ROS_INFO_STREAM("Started moveit_ros_control_interface::MoveItControllerManager for namespace " << ns_);
203  }
204 
209  MoveItControllerManager(const std::string& ns)
210  : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
211  {
212  }
213 
219  virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
220  {
221  boost::mutex::scoped_lock lock(controllers_mutex_);
222  HandleMap::iterator it = handles_.find(name);
223  if (it != handles_.end())
224  { // controller is is manager by this interface
225  return it->second;
226  }
227  return moveit_controller_manager::MoveItControllerHandlePtr();
228  }
229 
234  virtual void getControllersList(std::vector<std::string>& names)
235  {
236  boost::mutex::scoped_lock lock(controllers_mutex_);
237  discover();
238 
239  for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
240  {
241  names.push_back(it->first);
242  }
243  }
244 
249  virtual void getActiveControllers(std::vector<std::string>& names)
250  {
251  boost::mutex::scoped_lock lock(controllers_mutex_);
252  discover();
253 
254  for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
255  {
256  if (isActive(it->second))
257  names.push_back(it->first);
258  }
259  }
260 
266  virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
267  {
268  boost::mutex::scoped_lock lock(controllers_mutex_);
269  ControllersMap::iterator it = managed_controllers_.find(name);
270  if (it != managed_controllers_.end())
271  {
272 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL)
273  joints = it->second.resources;
274 #else
275  for (std::size_t i = 0; i < it->second.claimed_resources.size(); ++i)
276  {
277  std::vector<std::string>& resources = it->second.claimed_resources[i].resources;
278  joints.insert(joints.end(), resources.begin(), resources.end());
279  }
280 #endif
281  }
282  }
283 
289  virtual ControllerState getControllerState(const std::string& name)
290  {
291  boost::mutex::scoped_lock lock(controllers_mutex_);
292  discover();
293 
294  ControllerState c;
295  ControllersMap::iterator it = managed_controllers_.find(name);
296  if (it != managed_controllers_.end())
297  {
298  c.active_ = isActive(it->second);
299  }
300  return c;
301  }
302 
310  virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
311  {
312  boost::mutex::scoped_lock lock(controllers_mutex_);
313  discover(true);
314 
315  typedef boost::bimap<std::string, std::string> resources_bimap;
316 
317  resources_bimap claimed_resources;
318 
319  // fill bimap with active controllers and their resources
320  for (ControllersMap::iterator c = active_controllers_.begin(); c != active_controllers_.end(); ++c)
321  {
322 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL)
323  for (std::vector<std::string>::iterator r = c->second.resources.begin(); r != c->second.resources.end(); ++r)
324  {
325  claimed_resources.insert(resources_bimap::value_type(c->second.name, *r));
326  }
327 #else
328  for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::iterator hir =
329  c->second.claimed_resources.begin();
330  hir != c->second.claimed_resources.end(); ++hir)
331  {
332  for (std::vector<std::string>::iterator r = hir->resources.begin(); r != hir->resources.end(); ++r)
333  {
334  claimed_resources.insert(resources_bimap::value_type(c->second.name, *r));
335  }
336  }
337 #endif
338  }
339 
340  controller_manager_msgs::SwitchController srv;
341 
342  for (std::vector<std::string>::const_iterator it = deactivate.begin(); it != deactivate.end(); ++it)
343  {
344  ControllersMap::iterator c = managed_controllers_.find(*it);
345  if (c != managed_controllers_.end())
346  { // controller belongs to this manager
347  srv.request.stop_controllers.push_back(c->second.name);
348  claimed_resources.right.erase(c->second.name); // remove resources
349  }
350  }
351 
352  for (std::vector<std::string>::const_iterator it = activate.begin(); it != activate.end(); ++it)
353  {
354  ControllersMap::iterator c = managed_controllers_.find(*it);
355  if (c != managed_controllers_.end())
356  { // controller belongs to this manager
357  srv.request.start_controllers.push_back(c->second.name);
358 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL)
359  for (std::vector<std::string>::iterator r = c->second.resources.begin(); r != c->second.resources.end(); ++r)
360  { // for all claimed resource
361  resources_bimap::right_const_iterator res = claimed_resources.right.find(*r);
362  if (res != claimed_resources.right.end())
363  { // resource is claimed
364  srv.request.stop_controllers.push_back(res->second); // add claiming controller to stop list
365  claimed_resources.left.erase(res->second); // remove claimed resources
366  }
367  }
368 #else
369  for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::iterator hir =
370  c->second.claimed_resources.begin();
371  hir != c->second.claimed_resources.end(); ++hir)
372  {
373  for (std::vector<std::string>::iterator r = hir->resources.begin(); r != hir->resources.end(); ++r)
374  { // for all claimed resource
375  resources_bimap::right_const_iterator res = claimed_resources.right.find(*r);
376  if (res != claimed_resources.right.end())
377  { // resource is claimed
378  srv.request.stop_controllers.push_back(res->second); // add claiming controller to stop list
379  claimed_resources.left.erase(res->second); // remove claimed resources
380  }
381  }
382  }
383 #endif
384  }
385  }
386  srv.request.strictness = srv.request.STRICT;
387 
388  if (!srv.request.start_controllers.empty() || srv.request.stop_controllers.empty())
389  { // something to switch?
390  if (!ros::service::call(getAbsName("controller_manager/switch_controller"), srv))
391  {
392  ROS_ERROR_STREAM("Could switch controllers at " << ns_);
393  }
394  discover(true);
395  return srv.response.ok;
396  }
397  return true;
398  }
399 };
405 {
406  typedef std::map<std::string, moveit_ros_control_interface::MoveItControllerManagerPtr> ControllerManagersMap;
407  ControllerManagersMap controller_managers_;
410 
415  void discover()
416  {
417  if (!checkTimeout(controller_managers_stamp_, 1.0))
418  return;
419 
420  XmlRpc::XmlRpcValue args, result, system_state;
421  args[0] = ros::this_node::getName();
422 
423  if (!ros::master::execute("getSystemState", args, result, system_state, true))
424  {
425  return;
426  }
427 
428  // refer to http://wiki.ros.org/ROS/Master_API#Name_service_and_system_state
429  XmlRpc::XmlRpcValue services = system_state[2];
430 
431  for (int i = 0; i < services.size(); ++i)
432  {
433  std::string service = services[i][0];
434  std::size_t found = service.find("controller_manager/list_controllers");
435  if (found != std::string::npos)
436  {
437  std::string ns = service.substr(0, found);
438  if (controller_managers_.find(ns) == controller_managers_.end())
439  { // create MoveItControllerManager if it does not exists
440  ROS_INFO_STREAM("Adding controller_manager interface for node at namespace " << ns);
441  controller_managers_.insert(
442  std::make_pair(ns, std::make_shared<moveit_ros_control_interface::MoveItControllerManager>(ns)));
443  }
444  }
445  }
446  }
447 
453  static std::string getNamespace(const std::string& name)
454  {
455  size_t pos = name.find('/', 1);
456  if (pos == std::string::npos)
457  pos = 0;
458  return name.substr(0, pos + 1);
459  }
460 
461 public:
467  virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name)
468  {
469  boost::mutex::scoped_lock lock(controller_managers_mutex_);
470 
471  std::string ns = getNamespace(name);
472  ControllerManagersMap::iterator it = controller_managers_.find(ns);
473  if (it != controller_managers_.end())
474  {
475  return it->second->getControllerHandle(name);
476  }
477  return moveit_controller_manager::MoveItControllerHandlePtr();
478  }
479 
484  virtual void getControllersList(std::vector<std::string>& names)
485  {
486  boost::mutex::scoped_lock lock(controller_managers_mutex_);
487  discover();
488 
489  for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
490  {
491  it->second->getControllersList(names);
492  }
493  }
494 
499  virtual void getActiveControllers(std::vector<std::string>& names)
500  {
501  boost::mutex::scoped_lock lock(controller_managers_mutex_);
502  discover();
503 
504  for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
505  {
506  it->second->getActiveControllers(names);
507  }
508  }
509 
515  virtual void getControllerJoints(const std::string& name, std::vector<std::string>& joints)
516  {
517  boost::mutex::scoped_lock lock(controller_managers_mutex_);
518 
519  std::string ns = getNamespace(name);
520  ControllerManagersMap::iterator it = controller_managers_.find(ns);
521  if (it != controller_managers_.end())
522  {
523  it->second->getControllerJoints(name, joints);
524  }
525  }
526 
532  virtual ControllerState getControllerState(const std::string& name)
533  {
534  boost::mutex::scoped_lock lock(controller_managers_mutex_);
535 
536  std::string ns = getNamespace(name);
537  ControllerManagersMap::iterator it = controller_managers_.find(ns);
538  if (it != controller_managers_.end())
539  {
540  return it->second->getControllerState(name);
541  }
542  return ControllerState();
543  }
544 
551  virtual bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate)
552  {
553  boost::mutex::scoped_lock lock(controller_managers_mutex_);
554 
555  for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
556  {
557  if (!it->second->switchControllers(activate, deactivate))
558  return false;
559  }
560  return true;
561  }
562 };
563 
564 } // namespace moveit_ros_control_interface
565 
568 
std::string getAbsName(const std::string &name)
get fully qualified name
MOVEIT_CLASS_FORWARD(ControllerHandleAllocator)
std::map< std::string, ControllerHandleAllocatorPtr > AllocatorsMap
bool param(const std::string &param_name, T &param_val, const T &default_val)
std::map< std::string, moveit_ros_control_interface::MoveItControllerManagerPtr > ControllerManagersMap
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
delegates switch to all known interfaces. Stops of first failing switch.
virtual void getActiveControllers(std::vector< std::string > &names)
Read all active, managed controllers from discovered interfaces.
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
Read resources from cached controller states.
void discover()
Poll ROS master for services and filters all controller_manager/list_controllers instances Throttled ...
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
Find and return the pre-allocated handle for the given controller.
int size() const
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL const std::string & getName()
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
Find appropriate interface and delegate joints query.
virtual void getActiveControllers(std::vector< std::string > &names)
Refresh controller list and output all active, managed controllers.
void discover(bool force=false)
Call list_controllers and populate managed_controllers_ and active_controllers_. Allocates handles if...
MoveItMultiControllerManager discovers all running ros_control node and delegates member function to ...
ROSCPP_DECL const std::string & getNamespace()
virtual void getControllersList(std::vector< std::string > &names)
Read all managed controllers from discovered interfaces.
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > HandleMap
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
static bool isActive(const controller_manager_msgs::ControllerState &s)
Check if given controller is active.
#define ROS_WARN_STREAM(args)
#define ROS_INFO_STREAM(args)
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
static std::string getNamespace(const std::string &name)
Get namespace (including leading and trailing slashes) from controller name.
static Time now()
void allocate(const std::string &name, const controller_manager_msgs::ControllerState &controller)
Allocates a MoveItControllerHandle instance for the given controller Might create allocator object fi...
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
Filter lists for managed controller and computes switching set. Stopped list might be extended by uns...
#define ROS_ERROR_STREAM(args)
virtual ControllerState getControllerState(const std::string &name)
Find appropriate interface and delegate state query.
virtual ControllerState getControllerState(const std::string &name)
Refresh controller state and output the state of the given one, only active_ will be set...
std::map< std::string, controller_manager_msgs::ControllerState > ControllersMap
virtual bool isClassAvailable(const std::string &lookup_name)
r
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
Find appropriate interface and delegate handle creation.
MoveItControllerManager(const std::string &ns)
Configure interface with namespace.
bool checkTimeout(ros::Time &t, double timeout, bool force=false)
check for timeout
PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::MoveItControllerManager, moveit_controller_manager::MoveItControllerManager)
moveit_controller_manager::MoveItControllerManager sub class that interfaces one ros_control controll...
MoveItControllerManager()
The default constructor. Reads the namespace from ~ros_control_namespace param and defaults to /...
virtual void getControllersList(std::vector< std::string > &names)
Refresh controller list and output all managed controllers.
pluginlib::ClassLoader< ControllerHandleAllocator > loader_


moveit_ros_control_interface
Author(s): Mathias Lüdtke
autogenerated on Sun Oct 18 2020 13:19:46