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 // TODO: Create a ROS parameter allowing to customize this default timeout
60 static constexpr double SERVICE_CALL_TIMEOUT = 3.0;
61 
63 {
70 std::string parseJointNameFromResource(const std::string& claimed_interface)
71 {
72  const auto index = claimed_interface.find('/');
73  if (index == std::string::npos)
74  return claimed_interface;
75  return claimed_interface.substr(0, index);
76 }
77 
87 void deconflictControllerActivationLists(std::vector<std::string>& activate_controllers,
88  std::vector<std::string>& deactivate_controllers)
89 {
90  // Convert vectors to sets for uniqueness
91  std::unordered_set activate_set(activate_controllers.begin(), activate_controllers.end());
92  std::unordered_set deactivate_set(deactivate_controllers.begin(), deactivate_controllers.end());
93 
94  // Find common elements
95  std::unordered_set<std::string> common_controllers;
96  for (const auto& str : activate_set)
97  {
98  if (deactivate_set.count(str))
99  {
100  common_controllers.insert(str);
101  }
102  }
103 
104  // Remove common elements from both sets
105  for (const auto& controller_name : common_controllers)
106  {
107  activate_set.erase(controller_name);
108  deactivate_set.erase(controller_name);
109  }
110 
111  // Convert sets back to vectors
112  activate_controllers.assign(activate_set.begin(), activate_set.end());
113  deactivate_controllers.assign(deactivate_set.begin(), deactivate_set.end());
114 }
115 
116 MOVEIT_CLASS_FORWARD(Ros2ControlManager); // Defines Ros2ControlManagerPtr, ConstPtr, WeakPtr... etc
117 
125 {
126  std::string ns_;
127  pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
128  typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
129 
131  ControllersMap managed_controllers_;
133  ControllersMap active_controllers_;
134 
135  typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
136  AllocatorsMap allocators_;
137 
138  typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
139  HandleMap handles_;
140 
141  rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
142 
146  std::mutex controllers_mutex_;
147 
148  rclcpp::Node::SharedPtr node_;
149  rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
150  rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
151 
152  // Chained controllers have dependent controllers (other controllers which must be started if the chained controller is started)
153  std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
154  // Controllers may have preceding chained controllers (other chained controllers which must be shutdown if the controller is shutdown)
155  std::unordered_map<std::string /* controller name */, std::vector<std::string> /* reverse dependencies */>
156  dependency_map_reverse_;
157 
163  static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
164  {
165  return s.state == std::string("active");
166  }
167 
174  void discover(bool force = false)
175  {
176  // Skip if controller stamp is too new for new discovery, enforce update if force==true
177  if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
178  return;
179 
180  controllers_stamp_ = node_->now();
181 
182  auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
183  auto result_future = list_controllers_service_->async_send_request(request);
184  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
185  {
186  RCLCPP_WARN_STREAM(LOGGER, "Failed to read controllers from " << list_controllers_service_->get_service_name()
187  << " within " << SERVICE_CALL_TIMEOUT
188  << " seconds");
189  return;
190  }
191 
192  managed_controllers_.clear();
193  active_controllers_.clear();
194 
195  auto result = result_future.get();
197  {
198  return;
199  }
200 
201  for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
202  {
203  // If the controller is active, add it to the map of active controllers.
204  if (isActive(controller))
205  {
206  // Get the names of the interfaces currently claimed by the active controller.
207  auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
208  .first->second.claimed_interfaces; // without namespace
209  // Modify the claimed interface names in-place to only include the name of the joint and not the command type
210  // (e.g. position, velocity, etc.).
211  std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
212  [](const std::string& claimed_interface) {
213  return parseJointNameFromResource(claimed_interface);
214  });
215  }
216 
217  // Instantiate a controller handle if one is available for this type of controller.
218  if (loader_.isClassAvailable(controller.type))
219  {
220  std::string absname = getAbsName(controller.name);
221  auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
222  // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
223  auto& required_interfaces = controller_it->second.required_command_interfaces;
224  // Modify the required interface names in-place to only include the name of the joint and not the command type
225  // (e.g. position, velocity, etc.).
226  std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
227  [](const std::string& required_interface) {
228  return parseJointNameFromResource(required_interface);
229  });
230  allocate(absname, controller_it->second);
231  }
232  }
233  }
234 
241  void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
242  {
243  if (handles_.find(name) == handles_.end())
244  {
245  const std::string& type = controller.type;
246  AllocatorsMap::iterator alloc_it = allocators_.find(type);
247  if (alloc_it == allocators_.end())
248  { // create allocator is needed
249  alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
250  }
251 
252  std::vector<std::string> resources;
253  // Collect claimed resources across different hardware interfaces
254  for (const auto& resource : controller.claimed_interfaces)
255  {
256  resources.push_back(parseJointNameFromResource(resource));
257  }
258 
259  moveit_controller_manager::MoveItControllerHandlePtr handle =
260  alloc_it->second->alloc(node_, name, resources); // allocate handle
261  if (handle)
262  handles_.insert(std::make_pair(name, handle));
263  }
264  }
265 
271  std::string getAbsName(const std::string& name)
272  {
273  return rclcpp::names::append(ns_, name);
274  }
275 
276 public:
281  : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
282  {
283  RCLCPP_INFO_STREAM(LOGGER, "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
284  }
285 
290  Ros2ControlManager(const std::string& ns)
291  : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
292  {
293  }
294 
295  void initialize(const rclcpp::Node::SharedPtr& node) override
296  {
297  node_ = node;
298  if (ns_.empty())
299  {
300  if (!node_->has_parameter("ros_control_namespace"))
301  {
302  ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
303  }
304  else
305  {
306  node_->get_parameter<std::string>("ros_control_namespace", ns_);
307  }
308  }
309 
310  list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
311  getAbsName("controller_manager/list_controllers"));
312  switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
313  getAbsName("controller_manager/switch_controller"));
314 
315  std::scoped_lock<std::mutex> lock(controllers_mutex_);
316  discover(true);
317  }
323  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
324  {
325  std::scoped_lock<std::mutex> lock(controllers_mutex_);
326  HandleMap::iterator it = handles_.find(name);
327  if (it != handles_.end())
328  { // controller is is manager by this interface
329  return it->second;
330  }
331  return moveit_controller_manager::MoveItControllerHandlePtr();
332  }
333 
338  void getControllersList(std::vector<std::string>& names) override
339  {
340  std::scoped_lock<std::mutex> lock(controllers_mutex_);
341  discover();
342 
343  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
344  managed_controllers_)
345  {
346  names.push_back(managed_controller.first);
347  }
348  }
349 
354  void getActiveControllers(std::vector<std::string>& names) override
355  {
356  std::scoped_lock<std::mutex> lock(controllers_mutex_);
357  discover();
358 
359  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
360  managed_controllers_)
361  {
362  if (isActive(managed_controller.second))
363  names.push_back(managed_controller.first);
364  }
365  }
366 
372  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
373  {
374  std::scoped_lock<std::mutex> lock(controllers_mutex_);
375  ControllersMap::iterator it = managed_controllers_.find(name);
376  if (it != managed_controllers_.end())
377  {
378  for (const auto& required_resource : it->second.required_command_interfaces)
379  {
380  joints.push_back(required_resource);
381  }
382  }
383  }
384 
390  ControllerState getControllerState(const std::string& name) override
391  {
392  std::scoped_lock<std::mutex> lock(controllers_mutex_);
393  discover();
394 
396  ControllersMap::iterator it = managed_controllers_.find(name);
397  if (it != managed_controllers_.end())
398  {
399  c.active_ = isActive(it->second);
400  }
401  return c;
402  }
403 
411  bool switchControllers(const std::vector<std::string>& activate_base,
412  const std::vector<std::string>& deactivate_base) override
413  {
414  // add_all_dependencies traverses the provided dependency map and appends the results to the controllers vector.
415  auto add_all_dependencies = [](const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
416  const std::function<bool(const std::string&)>& should_include,
417  std::vector<std::string>& controllers) {
418  auto queue = controllers;
419  while (!queue.empty())
420  {
421  auto controller = queue.back();
422  queue.pop_back();
423  if (controller.size() > 1 && controller[0] == '/')
424  {
425  // Remove leading / from controller name
426  controller.erase(0, 1);
427  }
428  if (dependencies.find(controller) == dependencies.end())
429  {
430  continue;
431  }
432  for (const auto& dependency : dependencies.at(controller))
433  {
434  queue.push_back(dependency);
435  if (should_include(dependency))
436  {
437  controllers.push_back("/" + dependency);
438  }
439  }
440  }
441  };
442 
443  std::vector<std::string> activate = activate_base;
444  add_all_dependencies(
445  dependency_map_,
446  [this](const std::string& dependency) {
447  return active_controllers_.find(dependency) == active_controllers_.end();
448  },
449  activate);
450  std::vector<std::string> deactivate = deactivate_base;
451  add_all_dependencies(
452  dependency_map_reverse_,
453  [this](const std::string& dependency) {
454  return active_controllers_.find(dependency) != active_controllers_.end();
455  },
456  deactivate);
457 
458  // The dependencies for chained controller activation must be started first, but they are processed last, so the
459  // order needs to be flipped
460  std::reverse(activate.begin(), activate.end());
461 
462  std::scoped_lock<std::mutex> lock(controllers_mutex_);
463  discover(true);
464 
465  typedef boost::bimap<std::string, std::string> resources_bimap;
466 
467  resources_bimap claimed_resources;
468 
469  // fill bimap with active controllers and their resources
470  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
471  active_controllers_)
472  {
473  for (const auto& resource : active_controller.second.claimed_interfaces)
474  {
475  claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
476  }
477  }
478 
479  auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
480  for (const std::string& it : deactivate)
481  {
482  ControllersMap::iterator c = managed_controllers_.find(it);
483  if (c != managed_controllers_.end())
484  { // controller belongs to this manager
485  request->deactivate_controllers.push_back(c->second.name);
486  claimed_resources.right.erase(c->second.name); // remove resources
487  }
488  }
489 
490  // For each controller to activate, find conflicts between the interfaces required by that controller and the
491  // interfaces claimed by currently-active controllers.
492  for (const std::string& it : activate)
493  {
494  ControllersMap::iterator c = managed_controllers_.find(it);
495  if (c != managed_controllers_.end())
496  { // controller belongs to this manager
497  request->activate_controllers.push_back(c->second.name);
498  for (const auto& required_resource : c->second.required_command_interfaces)
499  {
500  resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
501  if (res != claimed_resources.right.end())
502  { // resource is claimed
503  if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
504  res->second) == request->deactivate_controllers.end())
505  {
506  request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
507  }
508  claimed_resources.left.erase(res->second); // remove claimed resources
509  }
510  }
511  }
512  }
513 
514  // ROS2 Control expects simplified controller activation/deactivation.
515  // E.g. a controller should not be stopped and started at the same time, rather it should be removed from both the
516  // activation and deactivation request.
517  deconflictControllerActivationLists(request->activate_controllers, request->deactivate_controllers);
518 
519  // Setting level to STRICT means that the controller switch will only be committed if all controllers are
520  // successfully activated or deactivated.
521  request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
522 
523  if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
524  { // something to switch?
525  auto result_future = switch_controller_service_->async_send_request(request);
526  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
527  {
528  RCLCPP_ERROR_STREAM(LOGGER, "Couldn't switch controllers at " << switch_controller_service_->get_service_name()
529  << " within " << SERVICE_CALL_TIMEOUT
530  << " seconds");
531  return false;
532  }
533  discover(true);
534  return result_future.get()->ok;
535  }
536  return true;
537  }
543  bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
544  {
545  std::unordered_map<std::string, size_t> controller_name_map;
546  for (size_t i = 0; i < result->controller.size(); ++i)
547  {
548  controller_name_map[result->controller[i].name] = i;
549  }
550 
551  dependency_map_.clear();
552  dependency_map_reverse_.clear();
553  for (auto& controller : result->controller)
554  {
555  if (controller.chain_connections.size() > 1)
556  {
557  RCLCPP_ERROR_STREAM(LOGGER, "Controller with name %s chains to more than one controller. Chaining to more than "
558  "one controller is not supported.");
559  return false;
560  }
561  for (const auto& chained_controller : controller.chain_connections)
562  {
563  auto ind = controller_name_map[chained_controller.name];
564  dependency_map_[controller.name].push_back(chained_controller.name);
565  dependency_map_reverse_[chained_controller.name].push_back(controller.name);
566  std::copy(result->controller[ind].reference_interfaces.begin(),
567  result->controller[ind].reference_interfaces.end(),
568  std::back_inserter(controller.required_command_interfaces));
569  }
570  }
571 
572  return true;
573  }
574 };
580 {
581  typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
582  ControllerManagersMap controller_managers_;
583  rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
584  std::mutex controller_managers_mutex_;
585 
586  rclcpp::Node::SharedPtr node_;
587 
588  void initialize(const rclcpp::Node::SharedPtr& node) override
589  {
590  node_ = node;
591  }
596  void discover()
597  {
598  // Skip if last discovery is too new for discovery rate
599  if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
600  return;
601 
602  controller_managers_stamp_ = node_->now();
603 
604  const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
605 
606  for (const auto& service : services)
607  {
608  const auto& service_name = service.first;
609  std::size_t found = service_name.find("controller_manager/list_controllers");
610  if (found != std::string::npos)
611  {
612  std::string ns = service_name.substr(0, found);
613  if (controller_managers_.find(ns) == controller_managers_.end())
614  { // create Ros2ControlManager if it does not exist
615  RCLCPP_INFO_STREAM(LOGGER, "Adding controller_manager interface for node at namespace " << ns);
616  auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
617  controller_manager->initialize(node_);
618  controller_managers_.insert(std::make_pair(ns, controller_manager));
619  }
620  }
621  }
622  }
623 
629  static std::string getNamespace(const std::string& name)
630  {
631  size_t pos = name.find('/', 1);
632  if (pos == std::string::npos)
633  pos = 0;
634  return name.substr(0, pos + 1);
635  }
636 
637 public:
643  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
644  {
645  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
646 
647  std::string ns = getNamespace(name);
648  ControllerManagersMap::iterator it = controller_managers_.find(ns);
649  if (it != controller_managers_.end())
650  {
651  return it->second->getControllerHandle(name);
652  }
653  return moveit_controller_manager::MoveItControllerHandlePtr();
654  }
655 
660  void getControllersList(std::vector<std::string>& names) override
661  {
662  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
663  discover();
664 
665  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
666  controller_managers_)
667  {
668  controller_manager.second->getControllersList(names);
669  }
670  }
671 
676  void getActiveControllers(std::vector<std::string>& names) override
677  {
678  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
679  discover();
680 
681  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
682  controller_managers_)
683  {
684  controller_manager.second->getActiveControllers(names);
685  }
686  }
687 
693  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
694  {
695  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
696 
697  std::string ns = getNamespace(name);
698  ControllerManagersMap::iterator it = controller_managers_.find(ns);
699  if (it != controller_managers_.end())
700  {
701  it->second->getControllerJoints(name, joints);
702  }
703  }
704 
710  ControllerState getControllerState(const std::string& name) override
711  {
712  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
713 
714  std::string ns = getNamespace(name);
715  ControllerManagersMap::iterator it = controller_managers_.find(ns);
716  if (it != controller_managers_.end())
717  {
718  return it->second->getControllerState(name);
719  }
720  return ControllerState();
721  }
722 
729  bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
730  {
731  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
732 
733  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
734  controller_managers_)
735  {
736  if (!controller_manager.second->switchControllers(activate, deactivate))
737  return false;
738  }
739  return true;
740  }
741 };
742 
743 } // namespace moveit_ros_control_interface
744 
747 
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)
void deconflictControllerActivationLists(std::vector< std::string > &activate_controllers, std::vector< std::string > &deactivate_controllers)
Modifies controller activation/deactivation lists to conform to ROS 2 control expectations....
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.