97 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
98 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
101 ControllersMap managed_controllers_;
103 ControllersMap active_controllers_;
105 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
106 AllocatorsMap allocators_;
108 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
111 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
116 std::mutex controllers_mutex_;
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_;
123 std::unordered_map<std::string , std::vector<std::string> > dependency_map_;
130 static bool isActive(
const controller_manager_msgs::msg::ControllerState& s)
132 return s.state == std::string(
"active");
141 void discover(
bool force =
false)
144 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
149 controllers_stamp_ = node_->now();
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)
155 RCLCPP_WARN_STREAM(getLogger(),
"Failed to read controllers from "
156 << list_controllers_service_->get_service_name() <<
" within "
157 << SERVICE_CALL_TIMEOUT <<
" seconds");
161 managed_controllers_.clear();
162 active_controllers_.clear();
164 auto result = result_future.get();
170 for (
const controller_manager_msgs::msg::ControllerState& controller : result->controller)
173 if (isActive(controller))
176 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
177 .first->second.claimed_interfaces;
180 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
181 [](
const std::string& claimed_interface) {
182 return parseJointNameFromResource(claimed_interface);
187 if (loader_.isClassAvailable(controller.type))
189 std::string absname = getAbsName(controller.name);
190 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first;
192 auto& required_interfaces = controller_it->second.required_command_interfaces;
195 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
196 [](
const std::string& required_interface) {
197 return parseJointNameFromResource(required_interface);
199 allocate(absname, controller_it->second);
210 void allocate(
const std::string& name,
const controller_manager_msgs::msg::ControllerState& controller)
212 if (handles_.find(name) == handles_.end())
214 const std::string& type = controller.type;
215 AllocatorsMap::iterator alloc_it = allocators_.find(type);
216 if (alloc_it == allocators_.end())
218 alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
221 std::vector<std::string> resources;
223 for (
const auto& resource : controller.claimed_interfaces)
228 moveit_controller_manager::MoveItControllerHandlePtr handle =
229 alloc_it->second->alloc(node_, name, resources);
231 handles_.insert(std::make_pair(name, handle));
240 std::string getAbsName(
const std::string& name)
250 : loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
259 : ns_(ns), loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
261 RCLCPP_INFO_STREAM(getLogger(),
"Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
264 void initialize(
const rclcpp::Node::SharedPtr& node)
override
269 if (!node_->has_parameter(
"ros_control_namespace"))
271 ns_ = node_->declare_parameter<std::string>(
"ros_control_namespace",
"/");
275 node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
278 else if (node->has_parameter(
"ros_control_namespace"))
280 node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
281 RCLCPP_INFO_STREAM(getLogger(),
"Namespace for controller manager was specified, namespace: " << ns_);
284 list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
285 getAbsName(
"controller_manager/list_controllers"));
286 switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
287 getAbsName(
"controller_manager/switch_controller"));
289 std::scoped_lock<std::mutex> lock(controllers_mutex_);
297 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
299 std::scoped_lock<std::mutex> lock(controllers_mutex_);
300 HandleMap::iterator it = handles_.find(name);
301 if (it != handles_.end())
305 return moveit_controller_manager::MoveItControllerHandlePtr();
314 std::scoped_lock<std::mutex> lock(controllers_mutex_);
317 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
318 managed_controllers_)
320 names.push_back(managed_controller.first);
330 std::scoped_lock<std::mutex> lock(controllers_mutex_);
333 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
334 managed_controllers_)
336 if (isActive(managed_controller.second))
337 names.push_back(managed_controller.first);
348 std::scoped_lock<std::mutex> lock(controllers_mutex_);
349 ControllersMap::iterator it = managed_controllers_.find(name);
350 if (it != managed_controllers_.end())
352 for (
const auto& required_resource : it->second.required_command_interfaces)
354 joints.push_back(required_resource);
366 std::scoped_lock<std::mutex> lock(controllers_mutex_);
370 ControllersMap::iterator it = managed_controllers_.find(name);
371 if (it != managed_controllers_.end())
373 c.
active_ = isActive(it->second);
386 const std::vector<std::string>& deactivate_base)
override
389 std::vector<std::string> activate = activate_base;
390 std::vector<std::string> deactivate = deactivate_base;
391 for (
auto controllers : { &activate, &deactivate })
393 auto queue = *controllers;
394 while (!queue.empty())
396 auto controller = queue.back();
397 controller.erase(0, 1);
399 for (
const auto& dependency : dependency_map_[controller])
401 queue.push_back(dependency);
402 controllers->push_back(
"/" + dependency);
407 std::reverse(activate.begin(), activate.end());
409 std::scoped_lock<std::mutex> lock(controllers_mutex_);
430 typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
432 resources_bimap claimed_resources;
435 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
438 for (
const auto& resource : active_controller.second.claimed_interfaces)
440 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
444 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
445 for (
const std::string& it : deactivate)
447 ControllersMap::iterator c = managed_controllers_.find(it);
448 if (c != managed_controllers_.end())
450 request->deactivate_controllers.push_back(c->second.name);
451 claimed_resources.left.erase(c->second.name);
457 for (
const std::string& it : activate)
459 ControllersMap::iterator c = managed_controllers_.find(it);
460 if (c != managed_controllers_.end())
462 request->activate_controllers.push_back(c->second.name);
463 for (
const auto& required_resource : c->second.required_command_interfaces)
465 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
466 if (res != claimed_resources.right.end())
468 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
469 res->second) == request->deactivate_controllers.end())
471 request->deactivate_controllers.push_back(res->second);
473 claimed_resources.left.erase(res->second);
481 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
483 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
485 auto result_future = switch_controller_service_->async_send_request(request);
486 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
488 RCLCPP_ERROR_STREAM(getLogger(),
"Couldn't switch controllers at "
489 << switch_controller_service_->get_service_name() <<
" within "
490 << SERVICE_CALL_TIMEOUT <<
" seconds");
494 return result_future.get()->ok;
505 std::unordered_map<std::string, size_t> controller_name_map;
506 for (
size_t i = 0; i < result->controller.size(); ++i)
508 controller_name_map[result->controller[i].name] = i;
510 for (
auto& controller : result->controller)
512 if (controller.chain_connections.size() > 1)
514 RCLCPP_ERROR_STREAM(getLogger(),
515 "Controller with name %s chains to more than one controller. Chaining to more than "
516 "one controller is not supported.");
519 dependency_map_[controller.name].clear();
520 for (
const auto& chained_controller : controller.chain_connections)
522 auto ind = controller_name_map[chained_controller.name];
523 dependency_map_[controller.name].push_back(chained_controller.name);
524 controller.required_command_interfaces = result->controller[ind].required_command_interfaces;
525 controller.claimed_interfaces = result->controller[ind].claimed_interfaces;
526 result->controller[ind].claimed_interfaces.clear();
527 result->controller[ind].required_command_interfaces.clear();
540 typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
541 ControllerManagersMap controller_managers_;
542 rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
543 std::mutex controller_managers_mutex_;
545 rclcpp::Node::SharedPtr node_;
547 void initialize(
const rclcpp::Node::SharedPtr& node)
override
558 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
561 controller_managers_stamp_ = node_->now();
563 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
565 for (
const auto& service : services)
567 const auto& service_name = service.first;
568 std::size_t found = service_name.find(
"controller_manager/list_controllers");
569 if (found != std::string::npos)
571 std::string ns = service_name.substr(0, found);
572 if (controller_managers_.find(ns) == controller_managers_.end())
574 RCLCPP_INFO_STREAM(getLogger(),
"Adding controller_manager interface for node at namespace " << ns);
575 auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
576 controller_manager->initialize(node_);
577 controller_managers_.insert(std::make_pair(ns, controller_manager));
588 static std::string getNamespace(
const std::string& name)
590 size_t pos = name.find(
'/', 1);
591 if (pos == std::string::npos)
593 return name.substr(0, pos + 1);
602 moveit_controller_manager::MoveItControllerHandlePtr
getControllerHandle(
const std::string& name)
override
604 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
606 std::string ns = getNamespace(name);
607 ControllerManagersMap::iterator it = controller_managers_.find(ns);
608 if (it != controller_managers_.end())
610 return it->second->getControllerHandle(name);
612 return moveit_controller_manager::MoveItControllerHandlePtr();
621 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
624 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
625 controller_managers_)
627 controller_manager.second->getControllersList(names);
637 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
640 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
641 controller_managers_)
643 controller_manager.second->getActiveControllers(names);
654 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
656 std::string ns = getNamespace(name);
657 ControllerManagersMap::iterator it = controller_managers_.find(ns);
658 if (it != controller_managers_.end())
660 it->second->getControllerJoints(name, joints);
671 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
673 std::string ns = getNamespace(name);
674 ControllerManagersMap::iterator it = controller_managers_.find(ns);
675 if (it != controller_managers_.end())
677 return it->second->getControllerState(name);
688 bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
override
690 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
692 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
693 controller_managers_)
695 if (!controller_manager.second->switchControllers(activate, deactivate))