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>
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 static const double SERVICE_CALL_TIMEOUT = 1.0;
71 const auto index = claimed_interface.find(
'/');
72 if (index == std::string::npos)
73 return claimed_interface;
74 return claimed_interface.substr(0, index);
88 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
89 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
92 ControllersMap managed_controllers_;
94 ControllersMap active_controllers_;
96 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
97 AllocatorsMap allocators_;
99 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
102 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
107 std::mutex controllers_mutex_;
109 rclcpp::Node::SharedPtr node_;
110 rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
111 rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
114 std::unordered_map<std::string , std::vector<std::string> > dependency_map_;
121 static bool isActive(
const controller_manager_msgs::msg::ControllerState& s)
123 return s.state == std::string(
"active");
132 void discover(
bool force =
false)
135 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
138 controllers_stamp_ = node_->now();
140 auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
141 auto result_future = list_controllers_service_->async_send_request(request);
142 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
144 RCLCPP_WARN_STREAM(LOGGER,
"Failed to read controllers from " << list_controllers_service_->get_service_name()
145 <<
" within " << SERVICE_CALL_TIMEOUT
150 managed_controllers_.clear();
151 active_controllers_.clear();
153 auto result = result_future.get();
159 for (
const controller_manager_msgs::msg::ControllerState& controller : result->controller)
162 if (isActive(controller))
165 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
166 .first->second.claimed_interfaces;
169 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
170 [](
const std::string& claimed_interface) {
171 return parseJointNameFromResource(claimed_interface);
176 if (loader_.isClassAvailable(controller.type))
178 std::string absname = getAbsName(controller.name);
179 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first;
181 auto& required_interfaces = controller_it->second.required_command_interfaces;
184 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
185 [](
const std::string& required_interface) {
186 return parseJointNameFromResource(required_interface);
188 allocate(absname, controller_it->second);
199 void allocate(
const std::string&
name,
const controller_manager_msgs::msg::ControllerState& controller)
201 if (handles_.find(
name) == handles_.end())
203 const std::string&
type = controller.type;
204 AllocatorsMap::iterator alloc_it = allocators_.find(
type);
205 if (alloc_it == allocators_.end())
207 alloc_it = allocators_.insert(std::make_pair(
type, loader_.createUniqueInstance(
type))).first;
210 std::vector<std::string> resources;
212 for (
const auto& resource : controller.claimed_interfaces)
217 moveit_controller_manager::MoveItControllerHandlePtr handle =
218 alloc_it->second->alloc(node_,
name, resources);
220 handles_.insert(std::make_pair(
name, handle));
229 std::string getAbsName(
const std::string&
name)
239 : loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
241 RCLCPP_INFO_STREAM(LOGGER,
"Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
249 : ns_(ns), loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
253 void initialize(
const rclcpp::Node::SharedPtr& node)
override
258 if (!node_->has_parameter(
"ros_control_namespace"))
260 ns_ = node_->declare_parameter<std::string>(
"ros_control_namespace",
"/");
264 node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
267 else if (node->has_parameter(
"ros_control_namespace"))
269 node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
270 RCLCPP_INFO_STREAM(LOGGER,
"Namespace for controller manager was specified, namespace: " << ns_);
273 list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
274 getAbsName(
"controller_manager/list_controllers"));
275 switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
276 getAbsName(
"controller_manager/switch_controller"));
278 std::scoped_lock<std::mutex> lock(controllers_mutex_);
288 std::scoped_lock<std::mutex> lock(controllers_mutex_);
289 HandleMap::iterator it = handles_.find(
name);
290 if (it != handles_.end())
294 return moveit_controller_manager::MoveItControllerHandlePtr();
303 std::scoped_lock<std::mutex> lock(controllers_mutex_);
306 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
307 managed_controllers_)
309 names.push_back(managed_controller.first);
319 std::scoped_lock<std::mutex> lock(controllers_mutex_);
322 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
323 managed_controllers_)
325 if (isActive(managed_controller.second))
326 names.push_back(managed_controller.first);
337 std::scoped_lock<std::mutex> lock(controllers_mutex_);
338 ControllersMap::iterator it = managed_controllers_.find(
name);
339 if (it != managed_controllers_.end())
341 for (
const auto& required_resource : it->second.required_command_interfaces)
343 joints.push_back(required_resource);
355 std::scoped_lock<std::mutex> lock(controllers_mutex_);
359 ControllersMap::iterator it = managed_controllers_.find(
name);
360 if (it != managed_controllers_.end())
362 c.active_ = isActive(it->second);
375 const std::vector<std::string>& deactivate_base)
override
378 std::vector<std::string> activate = activate_base;
379 std::vector<std::string> deactivate = deactivate_base;
380 for (
auto controllers : { &activate, &deactivate })
382 auto queue = *controllers;
383 while (!queue.empty())
385 auto controller = queue.back();
386 controller.erase(0, 1);
388 for (
const auto& dependency : dependency_map_[controller])
390 queue.push_back(dependency);
391 controllers->push_back(
"/" + dependency);
396 std::reverse(activate.begin(), activate.end());
398 std::scoped_lock<std::mutex> lock(controllers_mutex_);
401 typedef boost::bimap<std::string, std::string> resources_bimap;
403 resources_bimap claimed_resources;
406 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
409 for (
const auto& resource : active_controller.second.claimed_interfaces)
411 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
415 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
416 for (
const std::string& it : deactivate)
418 ControllersMap::iterator
c = managed_controllers_.find(it);
419 if (
c != managed_controllers_.end())
421 request->deactivate_controllers.push_back(
c->second.name);
422 claimed_resources.right.erase(
c->second.name);
428 for (
const std::string& it : activate)
430 ControllersMap::iterator
c = managed_controllers_.find(it);
431 if (
c != managed_controllers_.end())
433 request->activate_controllers.push_back(
c->second.name);
434 for (
const auto& required_resource :
c->second.required_command_interfaces)
436 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
437 if (res != claimed_resources.right.end())
439 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
440 res->second) == request->deactivate_controllers.end())
442 request->deactivate_controllers.push_back(res->second);
444 claimed_resources.left.erase(res->second);
452 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
454 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
456 auto result_future = switch_controller_service_->async_send_request(request);
457 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
459 RCLCPP_ERROR_STREAM(LOGGER,
"Couldn't switch controllers at " << switch_controller_service_->get_service_name()
460 <<
" within " << SERVICE_CALL_TIMEOUT
465 return result_future.get()->ok;
476 std::unordered_map<std::string, size_t> controller_name_map;
477 for (
size_t i = 0; i < result->controller.size(); ++i)
479 controller_name_map[result->controller[i].name] = i;
481 for (
auto& controller : result->controller)
483 if (controller.chain_connections.size() > 1)
485 RCLCPP_ERROR_STREAM(LOGGER,
"Controller with name %s chains to more than one controller. Chaining to more than "
486 "one controller is not supported.");
489 dependency_map_[controller.name].clear();
490 for (
const auto& chained_controller : controller.chain_connections)
492 auto ind = controller_name_map[chained_controller.name];
493 dependency_map_[controller.name].push_back(chained_controller.name);
494 controller.required_command_interfaces = result->controller[ind].required_command_interfaces;
495 controller.claimed_interfaces = result->controller[ind].claimed_interfaces;
496 result->controller[ind].claimed_interfaces.clear();
497 result->controller[ind].required_command_interfaces.clear();
510 typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
511 ControllerManagersMap controller_managers_;
512 rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
513 std::mutex controller_managers_mutex_;
515 rclcpp::Node::SharedPtr node_;
517 void initialize(
const rclcpp::Node::SharedPtr& node)
override
528 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
531 controller_managers_stamp_ = node_->now();
533 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
535 for (
const auto& service : services)
537 const auto& service_name = service.first;
538 std::size_t found = service_name.find(
"controller_manager/list_controllers");
539 if (found != std::string::npos)
541 std::string ns = service_name.substr(0, found);
542 if (controller_managers_.find(ns) == controller_managers_.end())
544 RCLCPP_INFO_STREAM(LOGGER,
"Adding controller_manager interface for node at namespace " << ns);
545 auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
546 controller_manager->initialize(node_);
547 controller_managers_.insert(std::make_pair(ns, controller_manager));
558 static std::string getNamespace(
const std::string&
name)
560 size_t pos =
name.find(
'/', 1);
561 if (pos == std::string::npos)
563 return name.substr(0, pos + 1);
574 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
576 std::string ns = getNamespace(
name);
577 ControllerManagersMap::iterator it = controller_managers_.find(ns);
578 if (it != controller_managers_.end())
580 return it->second->getControllerHandle(
name);
582 return moveit_controller_manager::MoveItControllerHandlePtr();
591 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
594 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
595 controller_managers_)
597 controller_manager.second->getControllersList(names);
607 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
610 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
611 controller_managers_)
613 controller_manager.second->getActiveControllers(names);
624 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
626 std::string ns = getNamespace(
name);
627 ControllerManagersMap::iterator it = controller_managers_.find(ns);
628 if (it != controller_managers_.end())
630 it->second->getControllerJoints(
name, joints);
641 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
643 std::string ns = getNamespace(
name);
644 ControllerManagersMap::iterator it = controller_managers_.find(ns);
645 if (it != controller_managers_.end())
647 return it->second->getControllerState(
name);
658 bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
override
660 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
662 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
663 controller_managers_)
665 if (!controller_manager.second->switchControllers(activate, deactivate))
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)
std::string append(const std::string &left, const std::string &right)
const rclcpp::Logger LOGGER
Each controller known to MoveIt has a state. This structure describes that controller's state.