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 <boost/bimap/unordered_multiset_of.hpp>
47 #include <rclcpp/client.hpp>
48 #include <rclcpp/duration.hpp>
49 #include <rclcpp/logger.hpp>
50 #include <rclcpp/logging.hpp>
51 #include <rclcpp/node.hpp>
52 #include <rclcpp/parameter_value.hpp>
53 #include <rclcpp/time.hpp>
54 #include <map>
55 #include <memory>
56 #include <queue>
57 #include <moveit/utils/logger.hpp>
58 
59 static const rclcpp::Duration CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1.0);
60 static const double SERVICE_CALL_TIMEOUT = 1.0;
61 
63 {
64 namespace
65 {
66 rclcpp::Logger getLogger()
67 {
68  return moveit::getLogger("ros_control_interface");
69 }
70 } // namespace
71 
78 std::string parseJointNameFromResource(const std::string& claimed_interface)
79 {
80  const auto index = claimed_interface.find('/');
81  if (index == std::string::npos)
82  return claimed_interface;
83  return claimed_interface.substr(0, index);
84 }
85 
86 MOVEIT_CLASS_FORWARD(Ros2ControlManager); // Defines Ros2ControlManagerPtr, ConstPtr, WeakPtr... etc
87 
95 {
96  std::string ns_;
97  pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
98  typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
99 
101  ControllersMap managed_controllers_;
103  ControllersMap active_controllers_;
104 
105  typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
106  AllocatorsMap allocators_;
107 
108  typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
109  HandleMap handles_;
110 
111  rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
112 
116  std::mutex controllers_mutex_;
117 
118  rclcpp::Node::SharedPtr node_;
119  rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
120  rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
121 
122  // Chained controllers have dependencies (other controllers which must be running)
123  std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
124 
130  static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
131  {
132  return s.state == std::string("active");
133  }
134 
141  void discover(bool force = false)
142  {
143  // Skip if controller stamp is too new for new discovery, enforce update if force==true
144  if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
145  {
146  return;
147  }
148 
149  controllers_stamp_ = node_->now();
150 
151  auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
152  auto result_future = list_controllers_service_->async_send_request(request);
153  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
154  {
155  RCLCPP_WARN_STREAM(getLogger(), "Failed to read controllers from "
156  << list_controllers_service_->get_service_name() << " within "
157  << SERVICE_CALL_TIMEOUT << " seconds");
158  return;
159  }
160 
161  managed_controllers_.clear();
162  active_controllers_.clear();
163 
164  auto result = result_future.get();
166  {
167  return;
168  }
169 
170  for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
171  {
172  // If the controller is active, add it to the map of active controllers.
173  if (isActive(controller))
174  {
175  // Get the names of the interfaces currently claimed by the active controller.
176  auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
177  .first->second.claimed_interfaces; // without namespace
178  // Modify the claimed interface names in-place to only include the name of the joint and not the command type
179  // (e.g. position, velocity, etc.).
180  std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
181  [](const std::string& claimed_interface) {
182  return parseJointNameFromResource(claimed_interface);
183  });
184  }
185 
186  // Instantiate a controller handle if one is available for this type of controller.
187  if (loader_.isClassAvailable(controller.type))
188  {
189  std::string absname = getAbsName(controller.name);
190  auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
191  // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
192  auto& required_interfaces = controller_it->second.required_command_interfaces;
193  // Modify the required interface names in-place to only include the name of the joint and not the command type
194  // (e.g. position, velocity, etc.).
195  std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
196  [](const std::string& required_interface) {
197  return parseJointNameFromResource(required_interface);
198  });
199  allocate(absname, controller_it->second);
200  }
201  }
202  }
203 
210  void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
211  {
212  if (handles_.find(name) == handles_.end())
213  {
214  const std::string& type = controller.type;
215  AllocatorsMap::iterator alloc_it = allocators_.find(type);
216  if (alloc_it == allocators_.end())
217  { // create allocator if needed
218  alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
219  }
220 
221  std::vector<std::string> resources;
222  // Collect claimed resources across different hardware interfaces
223  for (const auto& resource : controller.claimed_interfaces)
224  {
225  resources.push_back(parseJointNameFromResource(resource));
226  }
227 
228  moveit_controller_manager::MoveItControllerHandlePtr handle =
229  alloc_it->second->alloc(node_, name, resources); // allocate handle
230  if (handle)
231  handles_.insert(std::make_pair(name, handle));
232  }
233  }
234 
240  std::string getAbsName(const std::string& name)
241  {
242  return rclcpp::names::append(ns_, name);
243  }
244 
245 public:
250  : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
251  {
252  }
253 
258  [[deprecated("Ros2ControlManager constructor with namespace is deprecated. Set namespace via the "
259  "ros_control_namespace parameter.")]] Ros2ControlManager(const std::string& ns)
260  : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
261  {
262  RCLCPP_INFO_STREAM(getLogger(), "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
263  }
264 
265  void initialize(const rclcpp::Node::SharedPtr& node) override
266  {
267  node_ = node;
268  // Set the namespace from the ros_control_namespace parameter, or default to "/"
269  if (!node_->has_parameter("ros_control_namespace"))
270  {
271  ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
272  }
273  else
274  {
275  node_->get_parameter<std::string>("ros_control_namespace", ns_);
276  RCLCPP_INFO_STREAM(getLogger(), "Namespace for controller manager was specified, namespace: " << ns_);
277  }
278 
279  list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
280  getAbsName("controller_manager/list_controllers"));
281  switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
282  getAbsName("controller_manager/switch_controller"));
283 
284  std::scoped_lock<std::mutex> lock(controllers_mutex_);
285  discover(true);
286  }
292  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
293  {
294  std::scoped_lock<std::mutex> lock(controllers_mutex_);
295  HandleMap::iterator it = handles_.find(name);
296  if (it != handles_.end())
297  { // controller is manager by this interface
298  return it->second;
299  }
300  return moveit_controller_manager::MoveItControllerHandlePtr();
301  }
302 
307  void getControllersList(std::vector<std::string>& names) override
308  {
309  std::scoped_lock<std::mutex> lock(controllers_mutex_);
310  discover();
311 
312  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
313  managed_controllers_)
314  {
315  names.push_back(managed_controller.first);
316  }
317  }
318 
323  void getActiveControllers(std::vector<std::string>& names) override
324  {
325  std::scoped_lock<std::mutex> lock(controllers_mutex_);
326  discover();
327 
328  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
329  managed_controllers_)
330  {
331  if (isActive(managed_controller.second))
332  names.push_back(managed_controller.first);
333  }
334  }
335 
341  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
342  {
343  std::scoped_lock<std::mutex> lock(controllers_mutex_);
344  ControllersMap::iterator it = managed_controllers_.find(name);
345  if (it != managed_controllers_.end())
346  {
347  for (const auto& required_resource : it->second.required_command_interfaces)
348  {
349  joints.push_back(required_resource);
350  }
351  }
352  }
353 
359  ControllerState getControllerState(const std::string& name) override
360  {
361  std::scoped_lock<std::mutex> lock(controllers_mutex_);
362  discover();
363 
364  ControllerState c;
365  ControllersMap::iterator it = managed_controllers_.find(name);
366  if (it != managed_controllers_.end())
367  {
368  c.active_ = isActive(it->second);
369  }
370  return c;
371  }
372 
380  bool switchControllers(const std::vector<std::string>& activate_base,
381  const std::vector<std::string>& deactivate_base) override
382  {
383  // add controller dependencies
384  std::vector<std::string> activate = activate_base;
385  std::vector<std::string> deactivate = deactivate_base;
386  for (auto controllers : { &activate, &deactivate })
387  {
388  auto queue = *controllers;
389  while (!queue.empty())
390  {
391  auto controller = queue.back();
392  controller.erase(0, 1);
393  queue.pop_back();
394  for (const auto& dependency : dependency_map_[controller])
395  {
396  queue.push_back(dependency);
397  controllers->push_back("/" + dependency);
398  }
399  }
400  }
401  // activation dependencies must be started first, but they are processed last, so the order needs to be flipped
402  std::reverse(activate.begin(), activate.end());
403 
404  std::scoped_lock<std::mutex> lock(controllers_mutex_);
405  discover(true);
406 
407  // Holds the list of controllers that are currently active and their resources
408  // Example:
409  // controller1:
410  // - controller1_joint1
411  // - controller1_joint2
412  // ...
413  // controller2:
414  // - controller2_joint1
415  // - controller2_joint2
416  // ...
417  // ...
418  // The left type have to be an unordered_multiset_of, because each controller can claim multiple resources
419  // {{ "controller1", "controller1_joint1" },
420  // { "controller1", "controller1_joint2" },
421  // ...,
422  // { "controller2", "controller2_joint1" },
423  // { "controller2", "controller2_joint2" },
424  // ...}
425  typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
426 
427  resources_bimap claimed_resources;
428 
429  // fill bimap with active controllers and their resources
430  for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
431  active_controllers_)
432  {
433  for (const auto& resource : active_controller.second.claimed_interfaces)
434  {
435  claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
436  }
437  }
438 
439  auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
440  for (const std::string& it : deactivate)
441  {
442  ControllersMap::iterator c = managed_controllers_.find(it);
443  if (c != managed_controllers_.end())
444  { // controller belongs to this manager
445  request->deactivate_controllers.push_back(c->second.name);
446  claimed_resources.left.erase(c->second.name); // remove resources
447  }
448  }
449 
450  // For each controller to activate, find conflicts between the interfaces required by that controller and the
451  // interfaces claimed by currently-active controllers.
452  for (const std::string& it : activate)
453  {
454  ControllersMap::iterator c = managed_controllers_.find(it);
455  if (c != managed_controllers_.end())
456  { // controller belongs to this manager
457  request->activate_controllers.push_back(c->second.name);
458  for (const auto& required_resource : c->second.required_command_interfaces)
459  {
460  resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
461  if (res != claimed_resources.right.end())
462  { // resource is claimed
463  if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
464  res->second) == request->deactivate_controllers.end())
465  {
466  request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
467  }
468  claimed_resources.left.erase(res->second); // remove claimed resources
469  }
470  }
471  }
472  }
473 
474  // Setting level to STRICT means that the controller switch will only be committed if all controllers are
475  // successfully activated or deactivated.
476  request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
477 
478  if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
479  { // something to switch?
480  auto result_future = switch_controller_service_->async_send_request(request);
481  if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
482  {
483  RCLCPP_ERROR_STREAM(getLogger(), "Couldn't switch controllers at "
484  << switch_controller_service_->get_service_name() << " within "
485  << SERVICE_CALL_TIMEOUT << " seconds");
486  return false;
487  }
488  discover(true);
489  return result_future.get()->ok;
490  }
491  return true;
492  }
498  bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
499  {
500  std::unordered_map<std::string, size_t> controller_name_map;
501  for (size_t i = 0; i < result->controller.size(); ++i)
502  {
503  controller_name_map[result->controller[i].name] = i;
504  }
505  for (auto& controller : result->controller)
506  {
507  if (controller.chain_connections.size() > 1)
508  {
509  RCLCPP_ERROR_STREAM(getLogger(),
510  "Controller with name %s chains to more than one controller. Chaining to more than "
511  "one controller is not supported.");
512  return false;
513  }
514  dependency_map_[controller.name].clear();
515  for (const auto& chained_controller : controller.chain_connections)
516  {
517  auto ind = controller_name_map[chained_controller.name];
518  dependency_map_[controller.name].push_back(chained_controller.name);
519  controller.required_command_interfaces = result->controller[ind].required_command_interfaces;
520  controller.claimed_interfaces = result->controller[ind].claimed_interfaces;
521  result->controller[ind].claimed_interfaces.clear();
522  result->controller[ind].required_command_interfaces.clear();
523  }
524  }
525 
526  return true;
527  }
528 };
534 {
535  typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
536  ControllerManagersMap controller_managers_;
537  rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
538  std::mutex controller_managers_mutex_;
539 
540  rclcpp::Node::SharedPtr node_;
541 
542  void initialize(const rclcpp::Node::SharedPtr& node) override
543  {
544  node_ = node;
545  }
550  void discover()
551  {
552  // Skip if last discovery is too new for discovery rate
553  if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
554  return;
555 
556  controller_managers_stamp_ = node_->now();
557 
558  const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
559 
560  for (const auto& service : services)
561  {
562  const auto& service_name = service.first;
563  std::size_t found = service_name.find("controller_manager/list_controllers");
564  if (found != std::string::npos)
565  {
566  std::string ns = service_name.substr(0, found);
567  if (controller_managers_.find(ns) == controller_managers_.end())
568  { // create Ros2ControlManager if it does not exist
569  RCLCPP_INFO_STREAM(getLogger(), "Adding controller_manager interface for node at namespace " << ns);
570  auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
571  controller_manager->initialize(node_);
572  controller_managers_.insert(std::make_pair(ns, controller_manager));
573  }
574  }
575  }
576  }
577 
583  static std::string getNamespace(const std::string& name)
584  {
585  size_t pos = name.find('/', 1);
586  if (pos == std::string::npos)
587  pos = 0;
588  return name.substr(0, pos + 1);
589  }
590 
591 public:
597  moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
598  {
599  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
600 
601  std::string ns = getNamespace(name);
602  ControllerManagersMap::iterator it = controller_managers_.find(ns);
603  if (it != controller_managers_.end())
604  {
605  return it->second->getControllerHandle(name);
606  }
607  return moveit_controller_manager::MoveItControllerHandlePtr();
608  }
609 
614  void getControllersList(std::vector<std::string>& names) override
615  {
616  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
617  discover();
618 
619  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
620  controller_managers_)
621  {
622  controller_manager.second->getControllersList(names);
623  }
624  }
625 
630  void getActiveControllers(std::vector<std::string>& names) override
631  {
632  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
633  discover();
634 
635  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
636  controller_managers_)
637  {
638  controller_manager.second->getActiveControllers(names);
639  }
640  }
641 
647  void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
648  {
649  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
650 
651  std::string ns = getNamespace(name);
652  ControllerManagersMap::iterator it = controller_managers_.find(ns);
653  if (it != controller_managers_.end())
654  {
655  it->second->getControllerJoints(name, joints);
656  }
657  }
658 
664  ControllerState getControllerState(const std::string& name) override
665  {
666  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
667 
668  std::string ns = getNamespace(name);
669  ControllerManagersMap::iterator it = controller_managers_.find(ns);
670  if (it != controller_managers_.end())
671  {
672  return it->second->getControllerState(name);
673  }
674  return ControllerState();
675  }
676 
683  bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
684  {
685  std::unique_lock<std::mutex> lock(controller_managers_mutex_);
686 
687  for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
688  controller_managers_)
689  {
690  if (!controller_manager.second->switchControllers(activate, deactivate))
691  return false;
692  }
693  return true;
694  }
695 };
696 
697 } // namespace moveit_ros_control_interface
698 
701 
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)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
std::string append(const std::string &left, const std::string &right)
name
Definition: setup.py:7
Each controller known to MoveIt has a state. This structure describes that controller's state.
bool active_
A controller can be active or inactive. This means that MoveIt could activate the controller when nee...