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 
268  list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
269  getAbsName("controller_manager/list_controllers"));
270  switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
271  getAbsName("controller_manager/switch_controller"));
272 
273  std::scoped_lock<std::mutex> lock(controllers_mutex_);
274  discover(true);
275  }
281  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
282  {
283  std::scoped_lock<std::mutex> lock(controllers_mutex_);
284  HandleMap::iterator it = handles_.find(name);
285  if (it != handles_.end())
286  { // controller is is manager by this interface
287  return it->second;
288  }
289  return moveit_controller_manager::MoveItControllerHandlePtr();
290  }
291 
296  void getControllersList(std::vector<std::string>& names) override
297  {
298  std::scoped_lock<std::mutex> lock(controllers_mutex_);
299  discover();
300 
301  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
302  managed_controllers_)
303  {
304  names.push_back(managed_controller.first);
305  }
306  }
307 
312  void getActiveControllers(std::vector<std::string>& names) override
313  {
314  std::scoped_lock<std::mutex> lock(controllers_mutex_);
315  discover();
316 
317  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
318  managed_controllers_)
319  {
320  if (isActive(managed_controller.second))
321  names.push_back(managed_controller.first);
322  }
323  }
324 
330  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
331  {
332  std::scoped_lock<std::mutex> lock(controllers_mutex_);
333  ControllersMap::iterator it = managed_controllers_.find(name);
334  if (it != managed_controllers_.end())
335  {
336  for (const auto& required_resource : it->second.required_command_interfaces)
337  {
338  joints.push_back(required_resource);
339  }
340  }
341  }
342 
348  ControllerState getControllerState(const std::string& name) override
349  {
350  std::scoped_lock<std::mutex> lock(controllers_mutex_);
351  discover();
352 
354  ControllersMap::iterator it = managed_controllers_.find(name);
355  if (it != managed_controllers_.end())
356  {
357  c.active_ = isActive(it->second);
358  }
359  return c;
360  }
361 
369  bool switchControllers(const std::vector<std::string>& activate_base,
370  const std::vector<std::string>& deactivate_base) override
371  {
372  // add controller dependencies
373  std::vector<std::string> activate = activate_base;
374  std::vector<std::string> deactivate = deactivate_base;
375  for (auto controllers : { &activate, &deactivate })
376  {
377  auto queue = *controllers;
378  while (!queue.empty())
379  {
380  auto controller = queue.back();
381  controller.erase(0, 1);
382  queue.pop_back();
383  for (const auto& dependency : dependency_map_[controller])
384  {
385  queue.push_back(dependency);
386  controllers->push_back("/" + dependency);
387  }
388  }
389  }
390  // activation dependencies must be started first, but they are processed last, so the order needs to be flipped
391  std::reverse(activate.begin(), activate.end());
392 
393  std::scoped_lock<std::mutex> lock(controllers_mutex_);
394  discover(true);
395 
396  typedef boost::bimap<std::string, std::string> resources_bimap;
397 
398  resources_bimap claimed_resources;
399 
400  // fill bimap with active controllers and their resources
401  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
402  active_controllers_)
403  {
404  for (const auto& resource : active_controller.second.claimed_interfaces)
405  {
406  claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
407  }
408  }
409 
410  auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
411  for (const std::string& it : deactivate)
412  {
413  ControllersMap::iterator c = managed_controllers_.find(it);
414  if (c != managed_controllers_.end())
415  { // controller belongs to this manager
416  request->deactivate_controllers.push_back(c->second.name);
417  claimed_resources.right.erase(c->second.name); // remove resources
418  }
419  }
420 
421  // For each controller to activate, find conflicts between the interfaces required by that controller and the
422  // interfaces claimed by currently-active controllers.
423  for (const std::string& it : activate)
424  {
425  ControllersMap::iterator c = managed_controllers_.find(it);
426  if (c != managed_controllers_.end())
427  { // controller belongs to this manager
428  request->activate_controllers.push_back(c->second.name);
429  for (const auto& required_resource : c->second.required_command_interfaces)
430  {
431  resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
432  if (res != claimed_resources.right.end())
433  { // resource is claimed
434  if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
435  res->second) == request->deactivate_controllers.end())
436  {
437  request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
438  }
439  claimed_resources.left.erase(res->second); // remove claimed resources
440  }
441  }
442  }
443  }
444 
445  // Setting level to STRICT means that the controller switch will only be committed if all controllers are
446  // successfully activated or deactivated.
447  request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
448 
449  if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
450  { // something to switch?
451  auto result_future = switch_controller_service_->async_send_request(request);
452  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
453  {
454  RCLCPP_ERROR_STREAM(LOGGER, "Couldn't switch controllers at " << switch_controller_service_->get_service_name()
455  << " within " << SERVICE_CALL_TIMEOUT
456  << " seconds");
457  return false;
458  }
459  discover(true);
460  return result_future.get()->ok;
461  }
462  return true;
463  }
469  bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
470  {
471  std::unordered_map<std::string, size_t> controller_name_map;
472  for (size_t i = 0; i < result->controller.size(); ++i)
473  {
474  controller_name_map[result->controller[i].name] = i;
475  }
476  for (auto& controller : result->controller)
477  {
478  if (controller.chain_connections.size() > 1)
479  {
480  RCLCPP_ERROR_STREAM(LOGGER, "Controller with name %s chains to more than one controller. Chaining to more than "
481  "one controller is not supported.");
482  return false;
483  }
484  dependency_map_[controller.name].clear();
485  for (const auto& chained_controller : controller.chain_connections)
486  {
487  auto ind = controller_name_map[chained_controller.name];
488  dependency_map_[controller.name].push_back(chained_controller.name);
489  controller.required_command_interfaces = result->controller[ind].required_command_interfaces;
490  controller.claimed_interfaces = result->controller[ind].claimed_interfaces;
491  result->controller[ind].claimed_interfaces.clear();
492  result->controller[ind].required_command_interfaces.clear();
493  }
494  }
495 
496  return true;
497  }
498 };
504 {
505  typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
506  ControllerManagersMap controller_managers_;
507  rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
508  std::mutex controller_managers_mutex_;
509 
510  rclcpp::Node::SharedPtr node_;
511 
512  void initialize(const rclcpp::Node::SharedPtr& node) override
513  {
514  node_ = node;
515  }
520  void discover()
521  {
522  // Skip if last discovery is too new for discovery rate
523  if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
524  return;
525 
526  controller_managers_stamp_ = node_->now();
527 
528  const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
529 
530  for (const auto& service : services)
531  {
532  const auto& service_name = service.first;
533  std::size_t found = service_name.find("controller_manager/list_controllers");
534  if (found != std::string::npos)
535  {
536  std::string ns = service_name.substr(0, found);
537  if (controller_managers_.find(ns) == controller_managers_.end())
538  { // create Ros2ControlManager if it does not exist
539  RCLCPP_INFO_STREAM(LOGGER, "Adding controller_manager interface for node at namespace " << ns);
540  auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
541  controller_manager->initialize(node_);
542  controller_managers_.insert(std::make_pair(ns, controller_manager));
543  }
544  }
545  }
546  }
547 
553  static std::string getNamespace(const std::string& name)
554  {
555  size_t pos = name.find('/', 1);
556  if (pos == std::string::npos)
557  pos = 0;
558  return name.substr(0, pos + 1);
559  }
560 
561 public:
567  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
568  {
569  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
570 
571  std::string ns = getNamespace(name);
572  ControllerManagersMap::iterator it = controller_managers_.find(ns);
573  if (it != controller_managers_.end())
574  {
575  return it->second->getControllerHandle(name);
576  }
577  return moveit_controller_manager::MoveItControllerHandlePtr();
578  }
579 
584  void getControllersList(std::vector<std::string>& names) override
585  {
586  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
587  discover();
588 
589  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
590  controller_managers_)
591  {
592  controller_manager.second->getControllersList(names);
593  }
594  }
595 
600  void getActiveControllers(std::vector<std::string>& names) override
601  {
602  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
603  discover();
604 
605  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
606  controller_managers_)
607  {
608  controller_manager.second->getActiveControllers(names);
609  }
610  }
611 
617  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
618  {
619  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
620 
621  std::string ns = getNamespace(name);
622  ControllerManagersMap::iterator it = controller_managers_.find(ns);
623  if (it != controller_managers_.end())
624  {
625  it->second->getControllerJoints(name, joints);
626  }
627  }
628 
634  ControllerState getControllerState(const std::string& name) override
635  {
636  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
637 
638  std::string ns = getNamespace(name);
639  ControllerManagersMap::iterator it = controller_managers_.find(ns);
640  if (it != controller_managers_.end())
641  {
642  return it->second->getControllerState(name);
643  }
644  return ControllerState();
645  }
646 
653  bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
654  {
655  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
656 
657  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
658  controller_managers_)
659  {
660  if (!controller_manager.second->switchControllers(activate, deactivate))
661  return false;
662  }
663  return true;
664  }
665 };
666 
667 } // namespace moveit_ros_control_interface
668 
671 
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.