97                                         std::vector<std::string>& deactivate_controllers)
 
  100  std::unordered_set activate_set(activate_controllers.begin(), activate_controllers.end());
 
  101  std::unordered_set deactivate_set(deactivate_controllers.begin(), deactivate_controllers.end());
 
  104  std::unordered_set<std::string> common_controllers;
 
  105  for (
const auto& str : activate_set)
 
  107    if (deactivate_set.count(str))
 
  109      common_controllers.insert(str);
 
  114  for (
const auto& controller_name : common_controllers)
 
  116    activate_set.erase(controller_name);
 
  117    deactivate_set.erase(controller_name);
 
  121  activate_controllers.assign(activate_set.begin(), activate_set.end());
 
  122  deactivate_controllers.assign(deactivate_set.begin(), deactivate_set.end());
 
 
  136  std::chrono::duration<double> service_call_timeout_;
 
  137  pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
 
  138  typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
 
  141  ControllersMap managed_controllers_;
 
  143  ControllersMap active_controllers_;
 
  145  typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
 
  146  AllocatorsMap allocators_;
 
  148  typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
 
  151  rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
 
  156  std::mutex controllers_mutex_;
 
  158  rclcpp::Node::SharedPtr node_;
 
  159  rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
 
  160  rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
 
  163  std::unordered_map<std::string , std::vector<std::string> > dependency_map_;
 
  165  std::unordered_map<std::string , std::vector<std::string> >
 
  166      dependency_map_reverse_;
 
  173  static bool isActive(
const controller_manager_msgs::msg::ControllerState& s)
 
  175    return s.state == std::string(
"active");
 
  184  void discover(
bool force = 
false)
 
  187    if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
 
  192    controllers_stamp_ = node_->now();
 
  194    auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
 
  195    auto result_future = list_controllers_service_->async_send_request(request);
 
  196    if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
 
  198      RCLCPP_WARN_STREAM(getLogger(), 
"Failed to read controllers from " 
  199                                          << list_controllers_service_->get_service_name() << 
" within " 
  200                                          << service_call_timeout_.count() << 
" seconds");
 
  204    managed_controllers_.clear();
 
  205    active_controllers_.clear();
 
  207    auto result = result_future.get();
 
  213    for (
const controller_manager_msgs::msg::ControllerState& controller : result->controller)
 
  216      if (isActive(controller))
 
  219        auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
 
  220                                       .first->second.claimed_interfaces;  
 
  223        std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
 
  224                       [](
const std::string& claimed_interface) {
 
  225                         return parseJointNameFromResource(claimed_interface);
 
  230      if (loader_.isClassAvailable(controller.type))
 
  232        std::string absname = getAbsName(controller.name);
 
  233        auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first;  
 
  235        auto& required_interfaces = controller_it->second.required_command_interfaces;
 
  238        std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
 
  239                       [](
const std::string& required_interface) {
 
  240                         return parseJointNameFromResource(required_interface);
 
  242        allocate(absname, controller_it->second);
 
  253  void allocate(
const std::string& name, 
const controller_manager_msgs::msg::ControllerState& controller)
 
  255    if (handles_.find(name) == handles_.end())
 
  257      const std::string& type = controller.type;
 
  258      AllocatorsMap::iterator alloc_it = allocators_.find(type);
 
  259      if (alloc_it == allocators_.end())
 
  261        alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
 
  264      std::vector<std::string> resources;
 
  266      for (
const auto& resource : controller.claimed_interfaces)
 
  271      moveit_controller_manager::MoveItControllerHandlePtr handle =
 
  272          alloc_it->second->alloc(node_, name, resources);  
 
  274        handles_.insert(std::make_pair(name, handle));
 
  283  std::string getAbsName(
const std::string& name)
 
  293    : loader_(
"moveit_ros_control_interface", 
"moveit_ros_control_interface::ControllerHandleAllocator")
 
 
  302    : ns_(ns), loader_(
"moveit_ros_control_interface", 
"moveit_ros_control_interface::ControllerHandleAllocator")
 
  304    RCLCPP_INFO_STREAM(getLogger(), 
"Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
 
 
  307  void initialize(
const rclcpp::Node::SharedPtr& node)
 override 
  312      if (!node_->has_parameter(
"ros_control_namespace"))
 
  314        ns_ = node_->declare_parameter<std::string>(
"ros_control_namespace", 
"/");
 
  318        node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
 
  322    double timeout_seconds;
 
  323    if (!node_->has_parameter(
"controller_service_call_timeout"))
 
  326          node_->declare_parameter<
double>(
"controller_service_call_timeout", DEFAULT_SERVICE_CALL_TIMEOUT);
 
  330      node_->get_parameter(
"controller_service_call_timeout", timeout_seconds);
 
  332    service_call_timeout_ = std::chrono::duration<double>(timeout_seconds);
 
  334    RCLCPP_INFO_STREAM(getLogger(), 
"Using service call timeout " << service_call_timeout_.count() << 
" seconds");
 
  336    list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
 
  337        getAbsName(
"controller_manager/list_controllers"));
 
  338    switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
 
  339        getAbsName(
"controller_manager/switch_controller"));
 
  341    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
 
  349  moveit_controller_manager::MoveItControllerHandlePtr 
getControllerHandle(
const std::string& name)
 override 
  351    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  352    HandleMap::iterator it = handles_.find(name);
 
  353    if (it != handles_.end())
 
  357    return moveit_controller_manager::MoveItControllerHandlePtr();
 
 
  366    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  369    for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
 
  370         managed_controllers_)
 
  372      names.push_back(managed_controller.first);
 
 
  382    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  385    for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
 
  386         managed_controllers_)
 
  388      if (isActive(managed_controller.second))
 
  389        names.push_back(managed_controller.first);
 
 
  400    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  401    ControllersMap::iterator it = managed_controllers_.find(name);
 
  402    if (it != managed_controllers_.end())
 
  404      for (
const auto& required_resource : it->second.required_command_interfaces)
 
  406        joints.push_back(required_resource);
 
 
  418    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  422    ControllersMap::iterator it = managed_controllers_.find(name);
 
  423    if (it != managed_controllers_.end())
 
  425      c.
active_ = isActive(it->second);
 
 
  438                         const std::vector<std::string>& deactivate_base)
 override 
  441    auto add_all_dependencies = [](
const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
 
  442                                   const std::function<bool(
const std::string&)>& should_include,
 
  443                                   std::vector<std::string>& controllers) {
 
  444      auto queue = controllers;
 
  445      while (!queue.empty())
 
  447        auto controller = queue.back();
 
  449        if (controller.size() > 1 && controller[0] == 
'/')
 
  452          controller.erase(0, 1);
 
  454        if (dependencies.find(controller) == dependencies.end())
 
  458        for (
const auto& dependency : dependencies.at(controller))
 
  460          queue.push_back(dependency);
 
  461          if (should_include(dependency))
 
  463            controllers.push_back(
"/" + dependency);
 
  469    std::vector<std::string> activate = activate_base;
 
  470    add_all_dependencies(
 
  472        [
this](
const std::string& dependency) {
 
  473          return active_controllers_.find(dependency) == active_controllers_.end();
 
  476    std::vector<std::string> deactivate = deactivate_base;
 
  477    add_all_dependencies(
 
  478        dependency_map_reverse_,
 
  479        [
this](
const std::string& dependency) {
 
  480          return active_controllers_.find(dependency) != active_controllers_.end();
 
  486    std::reverse(activate.begin(), activate.end());
 
  488    std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  509    typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
 
  511    resources_bimap claimed_resources;
 
  514    for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
 
  517      for (
const auto& resource : active_controller.second.claimed_interfaces)
 
  519        claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
 
  523    auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
 
  524    for (
const std::string& it : deactivate)
 
  526      ControllersMap::iterator c = managed_controllers_.find(it);
 
  527      if (c != managed_controllers_.end())
 
  529        request->deactivate_controllers.push_back(c->second.name);
 
  530        claimed_resources.left.erase(c->second.name);  
 
  536    for (
const std::string& it : activate)
 
  538      ControllersMap::iterator c = managed_controllers_.find(it);
 
  539      if (c != managed_controllers_.end())
 
  541        request->activate_controllers.push_back(c->second.name);
 
  542        for (
const auto& required_resource : c->second.required_command_interfaces)
 
  544          resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
 
  545          if (res != claimed_resources.right.end())
 
  547            if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
 
  548                          res->second) == request->deactivate_controllers.end())
 
  550              request->deactivate_controllers.push_back(res->second);  
 
  552            claimed_resources.left.erase(res->second);  
 
  565    request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
 
  567    if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
 
  569      auto result_future = switch_controller_service_->async_send_request(request);
 
  570      if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
 
  572        RCLCPP_ERROR_STREAM(getLogger(), 
"Couldn't switch controllers at " 
  573                                             << switch_controller_service_->get_service_name() << 
" within " 
  574                                             << service_call_timeout_.count() << 
" seconds");
 
  578      return result_future.get()->ok;
 
 
  589    std::unordered_map<std::string, size_t> controller_name_map;
 
  590    for (
size_t i = 0; i < result->controller.size(); ++i)
 
  592      controller_name_map[result->controller[i].name] = i;
 
  595    dependency_map_.clear();
 
  596    dependency_map_reverse_.clear();
 
  597    for (
auto& controller : result->controller)
 
  599      if (controller.chain_connections.size() > 1)
 
  601        RCLCPP_ERROR_STREAM(getLogger(),
 
  602                            "Controller with name %s chains to more than one controller. Chaining to more than " 
  603                            "one controller is not supported.");
 
  606      for (
const auto& chained_controller : controller.chain_connections)
 
  608        auto ind = controller_name_map[chained_controller.name];
 
  609        dependency_map_[controller.name].push_back(chained_controller.name);
 
  610        dependency_map_reverse_[chained_controller.name].push_back(controller.name);
 
  611        std::copy(result->controller[ind].reference_interfaces.begin(),
 
  612                  result->controller[ind].reference_interfaces.end(),
 
  613                  std::back_inserter(controller.required_command_interfaces));
 
 
 
  626  typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
 
  627  ControllerManagersMap controller_managers_;
 
  628  rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
 
  629  std::mutex controller_managers_mutex_;
 
  631  rclcpp::Node::SharedPtr node_;
 
  633  void initialize(
const rclcpp::Node::SharedPtr& node)
 override 
  644    if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
 
  647    controller_managers_stamp_ = node_->now();
 
  649    const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
 
  651    for (
const auto& service : services)
 
  653      const auto& service_name = service.first;
 
  654      std::size_t found = service_name.find(
"controller_manager/list_controllers");
 
  655      if (found != std::string::npos)
 
  657        std::string ns = service_name.substr(0, found);
 
  658        if (controller_managers_.find(ns) == controller_managers_.end())
 
  660          RCLCPP_INFO_STREAM(getLogger(), 
"Adding controller_manager interface for node at namespace " << ns);
 
  661          auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
 
  662          controller_manager->initialize(node_);
 
  663          controller_managers_.insert(std::make_pair(ns, controller_manager));
 
  674  static std::string getNamespace(
const std::string& name)
 
  676    size_t pos = name.find(
'/', 1);
 
  677    if (pos == std::string::npos)
 
  679    return name.substr(0, pos + 1);
 
  688  moveit_controller_manager::MoveItControllerHandlePtr 
getControllerHandle(
const std::string& name)
 override 
  690    std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  692    std::string ns = getNamespace(name);
 
  693    ControllerManagersMap::iterator it = controller_managers_.find(ns);
 
  694    if (it != controller_managers_.end())
 
  696      return it->second->getControllerHandle(name);
 
  698    return moveit_controller_manager::MoveItControllerHandlePtr();
 
 
  707    std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  710    for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
 
  711         controller_managers_)
 
  713      controller_manager.second->getControllersList(names);
 
 
  723    std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  726    for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
 
  727         controller_managers_)
 
  729      controller_manager.second->getActiveControllers(names);
 
 
  740    std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  742    std::string ns = getNamespace(name);
 
  743    ControllerManagersMap::iterator it = controller_managers_.find(ns);
 
  744    if (it != controller_managers_.end())
 
  746      it->second->getControllerJoints(name, joints);
 
 
  757    std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  759    std::string ns = getNamespace(name);
 
  760    ControllerManagersMap::iterator it = controller_managers_.find(ns);
 
  761    if (it != controller_managers_.end())
 
  763      return it->second->getControllerState(name);
 
 
  774  bool switchControllers(
const std::vector<std::string>& activate, 
const std::vector<std::string>& deactivate)
 override 
  776    std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  778    for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
 
  779         controller_managers_)
 
  781      if (!controller_manager.second->switchControllers(activate, deactivate))