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 
61 {
62 static constexpr double DEFAULT_SERVICE_CALL_TIMEOUT = 3.0;
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  std::chrono::duration<double> service_call_timeout_;
128  pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
129  typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
130 
132  ControllersMap managed_controllers_;
134  ControllersMap active_controllers_;
135 
136  typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
137  AllocatorsMap allocators_;
138 
139  typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
140  HandleMap handles_;
141 
142  rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
143 
147  std::mutex controllers_mutex_;
148 
149  rclcpp::Node::SharedPtr node_;
150  rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
151  rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
152 
153  // Chained controllers have dependent controllers (other controllers which must be started if the chained controller is started)
154  std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
155  // Controllers may have preceding chained controllers (other chained controllers which must be shutdown if the controller is shutdown)
156  std::unordered_map<std::string /* controller name */, std::vector<std::string> /* reverse dependencies */>
157  dependency_map_reverse_;
158 
164  static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
165  {
166  return s.state == std::string("active");
167  }
168 
175  void discover(bool force = false)
176  {
177  // Skip if controller stamp is too new for new discovery, enforce update if force==true
178  if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
179  return;
180 
181  controllers_stamp_ = node_->now();
182 
183  auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
184  auto result_future = list_controllers_service_->async_send_request(request);
185  if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
186  {
187  RCLCPP_WARN_STREAM(LOGGER, "Failed to read controllers from " << list_controllers_service_->get_service_name()
188  << " within " << service_call_timeout_.count()
189  << " seconds");
190  return;
191  }
192 
193  managed_controllers_.clear();
194  active_controllers_.clear();
195 
196  auto result = result_future.get();
198  {
199  return;
200  }
201 
202  for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
203  {
204  // If the controller is active, add it to the map of active controllers.
205  if (isActive(controller))
206  {
207  // Get the names of the interfaces currently claimed by the active controller.
208  auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
209  .first->second.claimed_interfaces; // without namespace
210  // Modify the claimed interface names in-place to only include the name of the joint and not the command type
211  // (e.g. position, velocity, etc.).
212  std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
213  [](const std::string& claimed_interface) {
214  return parseJointNameFromResource(claimed_interface);
215  });
216  }
217 
218  // Instantiate a controller handle if one is available for this type of controller.
219  if (loader_.isClassAvailable(controller.type))
220  {
221  std::string absname = getAbsName(controller.name);
222  auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
223  // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
224  auto& required_interfaces = controller_it->second.required_command_interfaces;
225  // Modify the required interface names in-place to only include the name of the joint and not the command type
226  // (e.g. position, velocity, etc.).
227  std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
228  [](const std::string& required_interface) {
229  return parseJointNameFromResource(required_interface);
230  });
231  allocate(absname, controller_it->second);
232  }
233  }
234  }
235 
242  void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
243  {
244  if (handles_.find(name) == handles_.end())
245  {
246  const std::string& type = controller.type;
247  AllocatorsMap::iterator alloc_it = allocators_.find(type);
248  if (alloc_it == allocators_.end())
249  { // create allocator is needed
250  alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
251  }
252 
253  std::vector<std::string> resources;
254  // Collect claimed resources across different hardware interfaces
255  for (const auto& resource : controller.claimed_interfaces)
256  {
257  resources.push_back(parseJointNameFromResource(resource));
258  }
259 
260  moveit_controller_manager::MoveItControllerHandlePtr handle =
261  alloc_it->second->alloc(node_, name, resources); // allocate handle
262  if (handle)
263  handles_.insert(std::make_pair(name, handle));
264  }
265  }
266 
272  std::string getAbsName(const std::string& name)
273  {
274  return rclcpp::names::append(ns_, name);
275  }
276 
277 public:
282  : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
283  {
284  RCLCPP_INFO_STREAM(LOGGER, "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
285  }
286 
291  Ros2ControlManager(const std::string& ns)
292  : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
293  {
294  }
295 
296  void initialize(const rclcpp::Node::SharedPtr& node) override
297  {
298  node_ = node;
299  if (ns_.empty())
300  {
301  if (!node_->has_parameter("ros_control_namespace"))
302  {
303  ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
304  }
305  else
306  {
307  node_->get_parameter<std::string>("ros_control_namespace", ns_);
308  }
309  }
310 
311  double timeout_seconds;
312  if (!node_->has_parameter("controller_service_call_timeout"))
313  {
314  timeout_seconds =
315  node_->declare_parameter<double>("controller_service_call_timeout", DEFAULT_SERVICE_CALL_TIMEOUT);
316  }
317  else
318  {
319  node_->get_parameter("controller_service_call_timeout", timeout_seconds);
320  }
321  service_call_timeout_ = std::chrono::duration<double>(timeout_seconds);
322 
323  RCLCPP_INFO_STREAM(LOGGER, "Using service call timeout " << service_call_timeout_.count() << " seconds");
324 
325  list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
326  getAbsName("controller_manager/list_controllers"));
327  switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
328  getAbsName("controller_manager/switch_controller"));
329 
330  std::scoped_lock<std::mutex> lock(controllers_mutex_);
331  discover(true);
332  }
338  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
339  {
340  std::scoped_lock<std::mutex> lock(controllers_mutex_);
341  HandleMap::iterator it = handles_.find(name);
342  if (it != handles_.end())
343  { // controller is is manager by this interface
344  return it->second;
345  }
346  return moveit_controller_manager::MoveItControllerHandlePtr();
347  }
348 
353  void getControllersList(std::vector<std::string>& names) override
354  {
355  std::scoped_lock<std::mutex> lock(controllers_mutex_);
356  discover();
357 
358  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
359  managed_controllers_)
360  {
361  names.push_back(managed_controller.first);
362  }
363  }
364 
369  void getActiveControllers(std::vector<std::string>& names) override
370  {
371  std::scoped_lock<std::mutex> lock(controllers_mutex_);
372  discover();
373 
374  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
375  managed_controllers_)
376  {
377  if (isActive(managed_controller.second))
378  names.push_back(managed_controller.first);
379  }
380  }
381 
387  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
388  {
389  std::scoped_lock<std::mutex> lock(controllers_mutex_);
390  ControllersMap::iterator it = managed_controllers_.find(name);
391  if (it != managed_controllers_.end())
392  {
393  for (const auto& required_resource : it->second.required_command_interfaces)
394  {
395  joints.push_back(required_resource);
396  }
397  }
398  }
399 
405  ControllerState getControllerState(const std::string& name) override
406  {
407  std::scoped_lock<std::mutex> lock(controllers_mutex_);
408  discover();
409 
411  ControllersMap::iterator it = managed_controllers_.find(name);
412  if (it != managed_controllers_.end())
413  {
414  c.active_ = isActive(it->second);
415  }
416  return c;
417  }
418 
426  bool switchControllers(const std::vector<std::string>& activate_base,
427  const std::vector<std::string>& deactivate_base) override
428  {
429  // add_all_dependencies traverses the provided dependency map and appends the results to the controllers vector.
430  auto add_all_dependencies = [](const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
431  const std::function<bool(const std::string&)>& should_include,
432  std::vector<std::string>& controllers) {
433  auto queue = controllers;
434  while (!queue.empty())
435  {
436  auto controller = queue.back();
437  queue.pop_back();
438  if (controller.size() > 1 && controller[0] == '/')
439  {
440  // Remove leading / from controller name
441  controller.erase(0, 1);
442  }
443  if (dependencies.find(controller) == dependencies.end())
444  {
445  continue;
446  }
447  for (const auto& dependency : dependencies.at(controller))
448  {
449  queue.push_back(dependency);
450  if (should_include(dependency))
451  {
452  controllers.push_back("/" + dependency);
453  }
454  }
455  }
456  };
457 
458  std::vector<std::string> activate = activate_base;
459  add_all_dependencies(
460  dependency_map_,
461  [this](const std::string& dependency) {
462  return active_controllers_.find(dependency) == active_controllers_.end();
463  },
464  activate);
465  std::vector<std::string> deactivate = deactivate_base;
466  add_all_dependencies(
467  dependency_map_reverse_,
468  [this](const std::string& dependency) {
469  return active_controllers_.find(dependency) != active_controllers_.end();
470  },
471  deactivate);
472 
473  // The dependencies for chained controller activation must be started first, but they are processed last, so the
474  // order needs to be flipped
475  std::reverse(activate.begin(), activate.end());
476 
477  std::scoped_lock<std::mutex> lock(controllers_mutex_);
478  discover(true);
479 
480  typedef boost::bimap<std::string, std::string> resources_bimap;
481 
482  resources_bimap claimed_resources;
483 
484  // fill bimap with active controllers and their resources
485  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
486  active_controllers_)
487  {
488  for (const auto& resource : active_controller.second.claimed_interfaces)
489  {
490  claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
491  }
492  }
493 
494  auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
495  for (const std::string& it : deactivate)
496  {
497  ControllersMap::iterator c = managed_controllers_.find(it);
498  if (c != managed_controllers_.end())
499  { // controller belongs to this manager
500  request->deactivate_controllers.push_back(c->second.name);
501  claimed_resources.right.erase(c->second.name); // remove resources
502  }
503  }
504 
505  // For each controller to activate, find conflicts between the interfaces required by that controller and the
506  // interfaces claimed by currently-active controllers.
507  for (const std::string& it : activate)
508  {
509  ControllersMap::iterator c = managed_controllers_.find(it);
510  if (c != managed_controllers_.end())
511  { // controller belongs to this manager
512  request->activate_controllers.push_back(c->second.name);
513  for (const auto& required_resource : c->second.required_command_interfaces)
514  {
515  resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
516  if (res != claimed_resources.right.end())
517  { // resource is claimed
518  if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
519  res->second) == request->deactivate_controllers.end())
520  {
521  request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
522  }
523  claimed_resources.left.erase(res->second); // remove claimed resources
524  }
525  }
526  }
527  }
528 
529  // ROS2 Control expects simplified controller activation/deactivation.
530  // E.g. a controller should not be stopped and started at the same time, rather it should be removed from both the
531  // activation and deactivation request.
532  deconflictControllerActivationLists(request->activate_controllers, request->deactivate_controllers);
533 
534  // Setting level to STRICT means that the controller switch will only be committed if all controllers are
535  // successfully activated or deactivated.
536  request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
537 
538  if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
539  { // something to switch?
540  auto result_future = switch_controller_service_->async_send_request(request);
541  if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
542  {
543  RCLCPP_ERROR_STREAM(LOGGER, "Couldn't switch controllers at " << switch_controller_service_->get_service_name()
544  << " within " << service_call_timeout_.count()
545  << " seconds");
546  return false;
547  }
548  discover(true);
549  return result_future.get()->ok;
550  }
551  return true;
552  }
558  bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
559  {
560  std::unordered_map<std::string, size_t> controller_name_map;
561  for (size_t i = 0; i < result->controller.size(); ++i)
562  {
563  controller_name_map[result->controller[i].name] = i;
564  }
565 
566  dependency_map_.clear();
567  dependency_map_reverse_.clear();
568  for (auto& controller : result->controller)
569  {
570  if (controller.chain_connections.size() > 1)
571  {
572  RCLCPP_ERROR_STREAM(LOGGER, "Controller with name %s chains to more than one controller. Chaining to more than "
573  "one controller is not supported.");
574  return false;
575  }
576  for (const auto& chained_controller : controller.chain_connections)
577  {
578  auto ind = controller_name_map[chained_controller.name];
579  dependency_map_[controller.name].push_back(chained_controller.name);
580  dependency_map_reverse_[chained_controller.name].push_back(controller.name);
581  std::copy(result->controller[ind].reference_interfaces.begin(),
582  result->controller[ind].reference_interfaces.end(),
583  std::back_inserter(controller.required_command_interfaces));
584  }
585  }
586 
587  return true;
588  }
589 };
595 {
596  typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
597  ControllerManagersMap controller_managers_;
598  rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
599  std::mutex controller_managers_mutex_;
600 
601  rclcpp::Node::SharedPtr node_;
602 
603  void initialize(const rclcpp::Node::SharedPtr& node) override
604  {
605  node_ = node;
606  }
611  void discover()
612  {
613  // Skip if last discovery is too new for discovery rate
614  if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
615  return;
616 
617  controller_managers_stamp_ = node_->now();
618 
619  const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
620 
621  for (const auto& service : services)
622  {
623  const auto& service_name = service.first;
624  std::size_t found = service_name.find("controller_manager/list_controllers");
625  if (found != std::string::npos)
626  {
627  std::string ns = service_name.substr(0, found);
628  if (controller_managers_.find(ns) == controller_managers_.end())
629  { // create Ros2ControlManager if it does not exist
630  RCLCPP_INFO_STREAM(LOGGER, "Adding controller_manager interface for node at namespace " << ns);
631  auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
632  controller_manager->initialize(node_);
633  controller_managers_.insert(std::make_pair(ns, controller_manager));
634  }
635  }
636  }
637  }
638 
644  static std::string getNamespace(const std::string& name)
645  {
646  size_t pos = name.find('/', 1);
647  if (pos == std::string::npos)
648  pos = 0;
649  return name.substr(0, pos + 1);
650  }
651 
652 public:
658  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
659  {
660  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
661 
662  std::string ns = getNamespace(name);
663  ControllerManagersMap::iterator it = controller_managers_.find(ns);
664  if (it != controller_managers_.end())
665  {
666  return it->second->getControllerHandle(name);
667  }
668  return moveit_controller_manager::MoveItControllerHandlePtr();
669  }
670 
675  void getControllersList(std::vector<std::string>& names) override
676  {
677  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
678  discover();
679 
680  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
681  controller_managers_)
682  {
683  controller_manager.second->getControllersList(names);
684  }
685  }
686 
691  void getActiveControllers(std::vector<std::string>& names) override
692  {
693  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
694  discover();
695 
696  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
697  controller_managers_)
698  {
699  controller_manager.second->getActiveControllers(names);
700  }
701  }
702 
708  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
709  {
710  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
711 
712  std::string ns = getNamespace(name);
713  ControllerManagersMap::iterator it = controller_managers_.find(ns);
714  if (it != controller_managers_.end())
715  {
716  it->second->getControllerJoints(name, joints);
717  }
718  }
719 
725  ControllerState getControllerState(const std::string& name) override
726  {
727  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
728 
729  std::string ns = getNamespace(name);
730  ControllerManagersMap::iterator it = controller_managers_.find(ns);
731  if (it != controller_managers_.end())
732  {
733  return it->second->getControllerState(name);
734  }
735  return ControllerState();
736  }
737 
744  bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
745  {
746  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
747 
748  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
749  controller_managers_)
750  {
751  if (!controller_manager.second->switchControllers(activate, deactivate))
752  return false;
753  }
754  return true;
755  }
756 };
757 
758 } // namespace moveit_ros_control_interface
759 
762 
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.