96 std::vector<std::string>& deactivate_controllers)
99 std::unordered_set activate_set(activate_controllers.begin(), activate_controllers.end());
100 std::unordered_set deactivate_set(deactivate_controllers.begin(), deactivate_controllers.end());
103 std::unordered_set<std::string> common_controllers;
104 for (
const auto& str : activate_set)
106 if (deactivate_set.count(str))
108 common_controllers.insert(str);
113 for (
const auto& controller_name : common_controllers)
115 activate_set.erase(controller_name);
116 deactivate_set.erase(controller_name);
120 activate_controllers.assign(activate_set.begin(), activate_set.end());
121 deactivate_controllers.assign(deactivate_set.begin(), deactivate_set.end());
135 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
136 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
139 ControllersMap managed_controllers_;
141 ControllersMap active_controllers_;
143 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
144 AllocatorsMap allocators_;
146 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
149 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
154 std::mutex controllers_mutex_;
156 rclcpp::Node::SharedPtr node_;
157 rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
158 rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
161 std::unordered_map<std::string , std::vector<std::string> > dependency_map_;
163 std::unordered_map<std::string , std::vector<std::string> >
164 dependency_map_reverse_;
171 static bool isActive(
const controller_manager_msgs::msg::ControllerState& s)
173 return s.state == std::string(
"active");
182 void discover(
bool force =
false)
185 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
190 controllers_stamp_ = node_->now();
192 auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
193 auto result_future = list_controllers_service_->async_send_request(request);
194 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
196 RCLCPP_WARN_STREAM(getLogger(),
"Failed to read controllers from "
197 << list_controllers_service_->get_service_name() <<
" within "
198 << SERVICE_CALL_TIMEOUT <<
" seconds");
202 managed_controllers_.clear();
203 active_controllers_.clear();
205 auto result = result_future.get();
211 for (
const controller_manager_msgs::msg::ControllerState& controller : result->controller)
214 if (isActive(controller))
217 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
218 .first->second.claimed_interfaces;
221 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
222 [](
const std::string& claimed_interface) {
223 return parseJointNameFromResource(claimed_interface);
228 if (loader_.isClassAvailable(controller.type))
230 std::string absname = getAbsName(controller.name);
231 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first;
233 auto& required_interfaces = controller_it->second.required_command_interfaces;
236 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
237 [](
const std::string& required_interface) {
238 return parseJointNameFromResource(required_interface);
240 allocate(absname, controller_it->second);
251 void allocate(
const std::string& name,
const controller_manager_msgs::msg::ControllerState& controller)
253 if (handles_.find(name) == handles_.end())
255 const std::string& type = controller.type;
256 AllocatorsMap::iterator alloc_it = allocators_.find(type);
257 if (alloc_it == allocators_.end())
259 alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
262 std::vector<std::string> resources;
264 for (
const auto& resource : controller.claimed_interfaces)
269 moveit_controller_manager::MoveItControllerHandlePtr handle =
270 alloc_it->second->alloc(node_, name, resources);
272 handles_.insert(std::make_pair(name, handle));
281 std::string getAbsName(
const std::string& name)
291 : loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
300 : ns_(ns), loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
302 RCLCPP_INFO_STREAM(getLogger(),
"Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
305 void initialize(
const rclcpp::Node::SharedPtr& node)
override
310 if (!node_->has_parameter(
"ros_control_namespace"))
312 ns_ = node_->declare_parameter<std::string>(
"ros_control_namespace",
"/");
316 node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
320 list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
321 getAbsName(
"controller_manager/list_controllers"));
322 switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
323 getAbsName(
"controller_manager/switch_controller"));
325 std::scoped_lock<std::mutex> lock(controllers_mutex_);
333 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
335 std::scoped_lock<std::mutex> lock(controllers_mutex_);
336 HandleMap::iterator it = handles_.find(name);
337 if (it != handles_.end())
341 return moveit_controller_manager::MoveItControllerHandlePtr();
350 std::scoped_lock<std::mutex> lock(controllers_mutex_);
353 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
354 managed_controllers_)
356 names.push_back(managed_controller.first);
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 if (isActive(managed_controller.second))
373 names.push_back(managed_controller.first);
384 std::scoped_lock<std::mutex> lock(controllers_mutex_);
385 ControllersMap::iterator it = managed_controllers_.find(name);
386 if (it != managed_controllers_.end())
388 for (
const auto& required_resource : it->second.required_command_interfaces)
390 joints.push_back(required_resource);
402 std::scoped_lock<std::mutex> lock(controllers_mutex_);
406 ControllersMap::iterator it = managed_controllers_.find(name);
407 if (it != managed_controllers_.end())
409 c.
active_ = isActive(it->second);
422 const std::vector<std::string>& deactivate_base)
override
425 auto add_all_dependencies = [](
const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
426 const std::function<bool(
const std::string&)>& should_include,
427 std::vector<std::string>& controllers) {
428 auto queue = controllers;
429 while (!queue.empty())
431 auto controller = queue.back();
433 if (controller.size() > 1 && controller[0] ==
'/')
436 controller.erase(0, 1);
438 if (dependencies.find(controller) == dependencies.end())
442 for (
const auto& dependency : dependencies.at(controller))
444 queue.push_back(dependency);
445 if (should_include(dependency))
447 controllers.push_back(
"/" + dependency);
453 std::vector<std::string> activate = activate_base;
454 add_all_dependencies(
456 [
this](
const std::string& dependency) {
457 return active_controllers_.find(dependency) == active_controllers_.end();
460 std::vector<std::string> deactivate = deactivate_base;
461 add_all_dependencies(
462 dependency_map_reverse_,
463 [
this](
const std::string& dependency) {
464 return active_controllers_.find(dependency) != active_controllers_.end();
470 std::reverse(activate.begin(), activate.end());
472 std::scoped_lock<std::mutex> lock(controllers_mutex_);
493 typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
495 resources_bimap claimed_resources;
498 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
501 for (
const auto& resource : active_controller.second.claimed_interfaces)
503 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
507 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
508 for (
const std::string& it : deactivate)
510 ControllersMap::iterator c = managed_controllers_.find(it);
511 if (c != managed_controllers_.end())
513 request->deactivate_controllers.push_back(c->second.name);
514 claimed_resources.left.erase(c->second.name);
520 for (
const std::string& it : activate)
522 ControllersMap::iterator c = managed_controllers_.find(it);
523 if (c != managed_controllers_.end())
525 request->activate_controllers.push_back(c->second.name);
526 for (
const auto& required_resource : c->second.required_command_interfaces)
528 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
529 if (res != claimed_resources.right.end())
531 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
532 res->second) == request->deactivate_controllers.end())
534 request->deactivate_controllers.push_back(res->second);
536 claimed_resources.left.erase(res->second);
549 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
551 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
553 auto result_future = switch_controller_service_->async_send_request(request);
554 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
556 RCLCPP_ERROR_STREAM(getLogger(),
"Couldn't switch controllers at "
557 << switch_controller_service_->get_service_name() <<
" within "
558 << SERVICE_CALL_TIMEOUT <<
" seconds");
562 return result_future.get()->ok;
573 std::unordered_map<std::string, size_t> controller_name_map;
574 for (
size_t i = 0; i < result->controller.size(); ++i)
576 controller_name_map[result->controller[i].name] = i;
579 dependency_map_.clear();
580 dependency_map_reverse_.clear();
581 for (
auto& controller : result->controller)
583 if (controller.chain_connections.size() > 1)
585 RCLCPP_ERROR_STREAM(getLogger(),
586 "Controller with name %s chains to more than one controller. Chaining to more than "
587 "one controller is not supported.");
590 for (
const auto& chained_controller : controller.chain_connections)
592 auto ind = controller_name_map[chained_controller.name];
593 dependency_map_[controller.name].push_back(chained_controller.name);
594 dependency_map_reverse_[chained_controller.name].push_back(controller.name);
595 std::copy(result->controller[ind].reference_interfaces.begin(),
596 result->controller[ind].reference_interfaces.end(),
597 std::back_inserter(controller.required_command_interfaces));
610 typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
611 ControllerManagersMap controller_managers_;
612 rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
613 std::mutex controller_managers_mutex_;
615 rclcpp::Node::SharedPtr node_;
617 void initialize(
const rclcpp::Node::SharedPtr& node)
override
628 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
631 controller_managers_stamp_ = node_->now();
633 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
635 for (
const auto& service : services)
637 const auto& service_name = service.first;
638 std::size_t found = service_name.find(
"controller_manager/list_controllers");
639 if (found != std::string::npos)
641 std::string ns = service_name.substr(0, found);
642 if (controller_managers_.find(ns) == controller_managers_.end())
644 RCLCPP_INFO_STREAM(getLogger(),
"Adding controller_manager interface for node at namespace " << ns);
645 auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
646 controller_manager->initialize(node_);
647 controller_managers_.insert(std::make_pair(ns, controller_manager));
658 static std::string getNamespace(
const std::string& name)
660 size_t pos = name.find(
'/', 1);
661 if (pos == std::string::npos)
663 return name.substr(0, pos + 1);
672 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
674 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
676 std::string ns = getNamespace(name);
677 ControllerManagersMap::iterator it = controller_managers_.find(ns);
678 if (it != controller_managers_.end())
680 return it->second->getControllerHandle(name);
682 return moveit_controller_manager::MoveItControllerHandlePtr();
691 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
694 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
695 controller_managers_)
697 controller_manager.second->getControllersList(names);
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->getActiveControllers(names);
724 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
726 std::string ns = getNamespace(name);
727 ControllerManagersMap::iterator it = controller_managers_.find(ns);
728 if (it != controller_managers_.end())
730 it->second->getControllerJoints(name, joints);
741 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
743 std::string ns = getNamespace(name);
744 ControllerManagersMap::iterator it = controller_managers_.find(ns);
745 if (it != controller_managers_.end())
747 return it->second->getControllerState(name);
758 bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
override
760 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
762 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
763 controller_managers_)
765 if (!controller_manager.second->switchControllers(activate, deactivate))