moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
41 #include <controller_manager_msgs/srv/list_controllers.hpp>
42 #include <controller_manager_msgs/srv/switch_controller.hpp>
43 #include <pluginlib/class_list_macros.hpp>
44 #include <pluginlib/class_loader.hpp>
45 #include <boost/bimap.hpp>
46 #include <rclcpp/client.hpp>
47 #include <rclcpp/duration.hpp>
48 #include <rclcpp/logger.hpp>
49 #include <rclcpp/logging.hpp>
50 #include <rclcpp/node.hpp>
51 #include <rclcpp/parameter_value.hpp>
52 #include <rclcpp/time.hpp>
53 #include <map>
54 #include <memory>
55 #include <queue>
56 
57 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.plugins.ros_control_interface");
58 static const rclcpp::Duration CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1.0);
59 static const double SERVICE_CALL_TIMEOUT = 1.0;
60 
62 {
69 std::string parseJointNameFromResource(const std::string& claimed_interface)
70 {
71  const auto index = claimed_interface.find('/');
72  if (index == std::string::npos)
73  return claimed_interface;
74  return claimed_interface.substr(0, index);
75 }
76 
77 MOVEIT_CLASS_FORWARD(Ros2ControlManager); // Defines Ros2ControlManagerPtr, ConstPtr, WeakPtr... etc
78 
86 {
87  std::string ns_;
88  pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
89  typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
90 
92  ControllersMap managed_controllers_;
94  ControllersMap active_controllers_;
95 
96  typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
97  AllocatorsMap allocators_;
98 
99  typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
100  HandleMap handles_;
101 
102  rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
103 
107  std::mutex controllers_mutex_;
108 
109  rclcpp::Node::SharedPtr node_;
110  rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
111  rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
112 
113  // Chained controllers have dependencies (other controllers which must be running)
114  std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
115 
121  static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
122  {
123  return s.state == std::string("active");
124  }
125 
132  void discover(bool force = false)
133  {
134  // Skip if controller stamp is too new for new discovery, enforce update if force==true
135  if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
136  return;
137 
138  controllers_stamp_ = node_->now();
139 
140  auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
141  auto result_future = list_controllers_service_->async_send_request(request);
142  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
143  {
144  RCLCPP_WARN_STREAM(LOGGER, "Failed to read controllers from " << list_controllers_service_->get_service_name()
145  << " within " << SERVICE_CALL_TIMEOUT
146  << " seconds");
147  return;
148  }
149 
150  managed_controllers_.clear();
151  active_controllers_.clear();
152 
153  auto result = result_future.get();
155  {
156  return;
157  }
158 
159  for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
160  {
161  // If the controller is active, add it to the map of active controllers.
162  if (isActive(controller))
163  {
164  // Get the names of the interfaces currently claimed by the active controller.
165  auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
166  .first->second.claimed_interfaces; // without namespace
167  // Modify the claimed interface names in-place to only include the name of the joint and not the command type
168  // (e.g. position, velocity, etc.).
169  std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
170  [](const std::string& claimed_interface) {
171  return parseJointNameFromResource(claimed_interface);
172  });
173  }
174 
175  // Instantiate a controller handle if one is available for this type of controller.
176  if (loader_.isClassAvailable(controller.type))
177  {
178  std::string absname = getAbsName(controller.name);
179  auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
180  // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
181  auto& required_interfaces = controller_it->second.required_command_interfaces;
182  // Modify the required interface names in-place to only include the name of the joint and not the command type
183  // (e.g. position, velocity, etc.).
184  std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
185  [](const std::string& required_interface) {
186  return parseJointNameFromResource(required_interface);
187  });
188  allocate(absname, controller_it->second);
189  }
190  }
191  }
192 
199  void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
200  {
201  if (handles_.find(name) == handles_.end())
202  {
203  const std::string& type = controller.type;
204  AllocatorsMap::iterator alloc_it = allocators_.find(type);
205  if (alloc_it == allocators_.end())
206  { // create allocator is needed
207  alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
208  }
209 
210  std::vector<std::string> resources;
211  // Collect claimed resources across different hardware interfaces
212  for (const auto& resource : controller.claimed_interfaces)
213  {
214  resources.push_back(parseJointNameFromResource(resource));
215  }
216 
217  moveit_controller_manager::MoveItControllerHandlePtr handle =
218  alloc_it->second->alloc(node_, name, resources); // allocate handle
219  if (handle)
220  handles_.insert(std::make_pair(name, handle));
221  }
222  }
223 
229  std::string getAbsName(const std::string& name)
230  {
231  return rclcpp::names::append(ns_, name);
232  }
233 
234 public:
239  : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
240  {
241  RCLCPP_INFO_STREAM(LOGGER, "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
242  }
243 
248  Ros2ControlManager(const std::string& ns)
249  : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
250  {
251  }
252 
253  void initialize(const rclcpp::Node::SharedPtr& node) override
254  {
255  node_ = node;
256  if (!ns_.empty())
257  {
258  if (!node_->has_parameter("ros_control_namespace"))
259  {
260  ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
261  }
262  else
263  {
264  node_->get_parameter<std::string>("ros_control_namespace", ns_);
265  }
266  }
267  else if (node->has_parameter("ros_control_namespace"))
268  {
269  node_->get_parameter<std::string>("ros_control_namespace", ns_);
270  RCLCPP_INFO_STREAM(LOGGER, "Namespace for controller manager was specified, namespace: " << ns_);
271  }
272 
273  list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
274  getAbsName("controller_manager/list_controllers"));
275  switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
276  getAbsName("controller_manager/switch_controller"));
277 
278  std::scoped_lock<std::mutex> lock(controllers_mutex_);
279  discover(true);
280  }
286  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
287  {
288  std::scoped_lock<std::mutex> lock(controllers_mutex_);
289  HandleMap::iterator it = handles_.find(name);
290  if (it != handles_.end())
291  { // controller is is manager by this interface
292  return it->second;
293  }
294  return moveit_controller_manager::MoveItControllerHandlePtr();
295  }
296 
301  void getControllersList(std::vector<std::string>& names) override
302  {
303  std::scoped_lock<std::mutex> lock(controllers_mutex_);
304  discover();
305 
306  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
307  managed_controllers_)
308  {
309  names.push_back(managed_controller.first);
310  }
311  }
312 
317  void getActiveControllers(std::vector<std::string>& names) override
318  {
319  std::scoped_lock<std::mutex> lock(controllers_mutex_);
320  discover();
321 
322  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
323  managed_controllers_)
324  {
325  if (isActive(managed_controller.second))
326  names.push_back(managed_controller.first);
327  }
328  }
329 
335  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
336  {
337  std::scoped_lock<std::mutex> lock(controllers_mutex_);
338  ControllersMap::iterator it = managed_controllers_.find(name);
339  if (it != managed_controllers_.end())
340  {
341  for (const auto& required_resource : it->second.required_command_interfaces)
342  {
343  joints.push_back(required_resource);
344  }
345  }
346  }
347 
353  ControllerState getControllerState(const std::string& name) override
354  {
355  std::scoped_lock<std::mutex> lock(controllers_mutex_);
356  discover();
357 
359  ControllersMap::iterator it = managed_controllers_.find(name);
360  if (it != managed_controllers_.end())
361  {
362  c.active_ = isActive(it->second);
363  }
364  return c;
365  }
366 
374  bool switchControllers(const std::vector<std::string>& activate_base,
375  const std::vector<std::string>& deactivate_base) override
376  {
377  // add controller dependencies
378  std::vector<std::string> activate = activate_base;
379  std::vector<std::string> deactivate = deactivate_base;
380  for (auto controllers : { &activate, &deactivate })
381  {
382  auto queue = *controllers;
383  while (!queue.empty())
384  {
385  auto controller = queue.back();
386  controller.erase(0, 1);
387  queue.pop_back();
388  for (const auto& dependency : dependency_map_[controller])
389  {
390  queue.push_back(dependency);
391  controllers->push_back("/" + dependency);
392  }
393  }
394  }
395  // activation dependencies must be started first, but they are processed last, so the order needs to be flipped
396  std::reverse(activate.begin(), activate.end());
397 
398  std::scoped_lock<std::mutex> lock(controllers_mutex_);
399  discover(true);
400 
401  typedef boost::bimap<std::string, std::string> resources_bimap;
402 
403  resources_bimap claimed_resources;
404 
405  // fill bimap with active controllers and their resources
406  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
407  active_controllers_)
408  {
409  for (const auto& resource : active_controller.second.claimed_interfaces)
410  {
411  claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
412  }
413  }
414 
415  auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
416  for (const std::string& it : deactivate)
417  {
418  ControllersMap::iterator c = managed_controllers_.find(it);
419  if (c != managed_controllers_.end())
420  { // controller belongs to this manager
421  request->deactivate_controllers.push_back(c->second.name);
422  claimed_resources.right.erase(c->second.name); // remove resources
423  }
424  }
425 
426  // For each controller to activate, find conflicts between the interfaces required by that controller and the
427  // interfaces claimed by currently-active controllers.
428  for (const std::string& it : activate)
429  {
430  ControllersMap::iterator c = managed_controllers_.find(it);
431  if (c != managed_controllers_.end())
432  { // controller belongs to this manager
433  request->activate_controllers.push_back(c->second.name);
434  for (const auto& required_resource : c->second.required_command_interfaces)
435  {
436  resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
437  if (res != claimed_resources.right.end())
438  { // resource is claimed
439  if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
440  res->second) == request->deactivate_controllers.end())
441  {
442  request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
443  }
444  claimed_resources.left.erase(res->second); // remove claimed resources
445  }
446  }
447  }
448  }
449 
450  // Setting level to STRICT means that the controller switch will only be committed if all controllers are
451  // successfully activated or deactivated.
452  request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
453 
454  if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
455  { // something to switch?
456  auto result_future = switch_controller_service_->async_send_request(request);
457  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
458  {
459  RCLCPP_ERROR_STREAM(LOGGER, "Couldn't switch controllers at " << switch_controller_service_->get_service_name()
460  << " within " << SERVICE_CALL_TIMEOUT
461  << " seconds");
462  return false;
463  }
464  discover(true);
465  return result_future.get()->ok;
466  }
467  return true;
468  }
474  bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
475  {
476  std::unordered_map<std::string, size_t> controller_name_map;
477  for (size_t i = 0; i < result->controller.size(); ++i)
478  {
479  controller_name_map[result->controller[i].name] = i;
480  }
481  for (auto& controller : result->controller)
482  {
483  if (controller.chain_connections.size() > 1)
484  {
485  RCLCPP_ERROR_STREAM(LOGGER, "Controller with name %s chains to more than one controller. Chaining to more than "
486  "one controller is not supported.");
487  return false;
488  }
489  dependency_map_[controller.name].clear();
490  for (const auto& chained_controller : controller.chain_connections)
491  {
492  auto ind = controller_name_map[chained_controller.name];
493  dependency_map_[controller.name].push_back(chained_controller.name);
494  controller.required_command_interfaces = result->controller[ind].required_command_interfaces;
495  controller.claimed_interfaces = result->controller[ind].claimed_interfaces;
496  result->controller[ind].claimed_interfaces.clear();
497  result->controller[ind].required_command_interfaces.clear();
498  }
499  }
500 
501  return true;
502  }
503 };
509 {
510  typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
511  ControllerManagersMap controller_managers_;
512  rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
513  std::mutex controller_managers_mutex_;
514 
515  rclcpp::Node::SharedPtr node_;
516 
517  void initialize(const rclcpp::Node::SharedPtr& node) override
518  {
519  node_ = node;
520  }
525  void discover()
526  {
527  // Skip if last discovery is too new for discovery rate
528  if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
529  return;
530 
531  controller_managers_stamp_ = node_->now();
532 
533  const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
534 
535  for (const auto& service : services)
536  {
537  const auto& service_name = service.first;
538  std::size_t found = service_name.find("controller_manager/list_controllers");
539  if (found != std::string::npos)
540  {
541  std::string ns = service_name.substr(0, found);
542  if (controller_managers_.find(ns) == controller_managers_.end())
543  { // create Ros2ControlManager if it does not exist
544  RCLCPP_INFO_STREAM(LOGGER, "Adding controller_manager interface for node at namespace " << ns);
545  auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
546  controller_manager->initialize(node_);
547  controller_managers_.insert(std::make_pair(ns, controller_manager));
548  }
549  }
550  }
551  }
552 
558  static std::string getNamespace(const std::string& name)
559  {
560  size_t pos = name.find('/', 1);
561  if (pos == std::string::npos)
562  pos = 0;
563  return name.substr(0, pos + 1);
564  }
565 
566 public:
572  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
573  {
574  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
575 
576  std::string ns = getNamespace(name);
577  ControllerManagersMap::iterator it = controller_managers_.find(ns);
578  if (it != controller_managers_.end())
579  {
580  return it->second->getControllerHandle(name);
581  }
582  return moveit_controller_manager::MoveItControllerHandlePtr();
583  }
584 
589  void getControllersList(std::vector<std::string>& names) override
590  {
591  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
592  discover();
593 
594  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
595  controller_managers_)
596  {
597  controller_manager.second->getControllersList(names);
598  }
599  }
600 
605  void getActiveControllers(std::vector<std::string>& names) override
606  {
607  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
608  discover();
609 
610  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
611  controller_managers_)
612  {
613  controller_manager.second->getActiveControllers(names);
614  }
615  }
616 
622  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
623  {
624  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
625 
626  std::string ns = getNamespace(name);
627  ControllerManagersMap::iterator it = controller_managers_.find(ns);
628  if (it != controller_managers_.end())
629  {
630  it->second->getControllerJoints(name, joints);
631  }
632  }
633 
639  ControllerState getControllerState(const std::string& name) override
640  {
641  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
642 
643  std::string ns = getNamespace(name);
644  ControllerManagersMap::iterator it = controller_managers_.find(ns);
645  if (it != controller_managers_.end())
646  {
647  return it->second->getControllerState(name);
648  }
649  return ControllerState();
650  }
651 
658  bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
659  {
660  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
661 
662  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
663  controller_managers_)
664  {
665  if (!controller_manager.second->switchControllers(activate, deactivate))
666  return false;
667  }
668  return true;
669  }
670 };
671 
672 } // namespace moveit_ros_control_interface
673 
676 
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt,...
moveit_controller_manager::Ros2ControlManager sub class that interfaces one ros_control controller_ma...
Ros2ControlManager()
The default constructor. Reads the namespace from ~ros_control_namespace param and defaults to /.
void getControllerJoints(const std::string &name, std::vector< std::string > &joints) override
Read interface names required by each controller from the cached controller state info.
void initialize(const rclcpp::Node::SharedPtr &node) override
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name) override
Find and return the pre-allocated handle for the given controller.
ControllerState getControllerState(const std::string &name) override
Refresh controller state and output the state of the given one, only active_ will be set.
void getControllersList(std::vector< std::string > &names) override
Refresh controller list and output all managed controllers.
void getActiveControllers(std::vector< std::string > &names) override
Refresh controller list and output all active, managed controllers.
Ros2ControlManager(const std::string &ns)
Configure interface with namespace.
bool fixChainedControllers(std::shared_ptr< controller_manager_msgs::srv::ListControllers::Response > &result)
fixChainedControllers modifies ListControllers service response if it contains chained controllers....
bool switchControllers(const std::vector< std::string > &activate_base, const std::vector< std::string > &deactivate_base) override
Filter lists for managed controller and computes switching set. Stopped list might be extended by uns...
Ros2ControlMultiManager discovers all running ros_control node and delegates member function to the c...
ControllerState getControllerState(const std::string &name) override
Find appropriate interface and delegate state query.
void getControllersList(std::vector< std::string > &names) override
Read all managed controllers from discovered interfaces.
void getControllerJoints(const std::string &name, std::vector< std::string > &joints) override
Find appropriate interface and delegate joints query.
bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate) override
delegates switch to all known interfaces. Stops on first failing switch.
moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name) override
Find appropriate interface and delegate handle creation.
void getActiveControllers(std::vector< std::string > &names) override
Read all active, managed controllers from discovered interfaces.
PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::Ros2ControlManager, moveit_controller_manager::MoveItControllerManager)
std::string parseJointNameFromResource(const std::string &claimed_interface)
Get joint name from resource name reported by ros2_control, since claimed_interfaces return by ros2_c...
MOVEIT_CLASS_FORWARD(ControllerHandleAllocator)
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Each controller known to MoveIt has a state. This structure describes that controller's state.