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);
 
   62 static constexpr 
double DEFAULT_SERVICE_CALL_TIMEOUT = 3.0;
 
   72   const auto index = claimed_interface.find(
'/');
 
   73   if (index == std::string::npos)
 
   74     return claimed_interface;
 
   75   return claimed_interface.substr(0, index);
 
   88                                          std::vector<std::string>& deactivate_controllers)
 
   91   std::unordered_set activate_set(activate_controllers.begin(), activate_controllers.end());
 
   92   std::unordered_set deactivate_set(deactivate_controllers.begin(), deactivate_controllers.end());
 
   95   std::unordered_set<std::string> common_controllers;
 
   96   for (
const auto& str : activate_set)
 
   98     if (deactivate_set.count(str))
 
  100       common_controllers.insert(str);
 
  105   for (
const auto& controller_name : common_controllers)
 
  107     activate_set.erase(controller_name);
 
  108     deactivate_set.erase(controller_name);
 
  112   activate_controllers.assign(activate_set.begin(), activate_set.end());
 
  113   deactivate_controllers.assign(deactivate_set.begin(), deactivate_set.end());
 
  127   std::chrono::duration<double> service_call_timeout_;
 
  128   pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
 
  129   typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
 
  132   ControllersMap managed_controllers_;
 
  134   ControllersMap active_controllers_;
 
  136   typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
 
  137   AllocatorsMap allocators_;
 
  139   typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
 
  142   rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
 
  147   std::mutex controllers_mutex_;
 
  149   rclcpp::Node::SharedPtr node_;
 
  150   rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
 
  151   rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
 
  154   std::unordered_map<std::string , std::vector<std::string> > dependency_map_;
 
  156   std::unordered_map<std::string , std::vector<std::string> >
 
  157       dependency_map_reverse_;
 
  164   static bool isActive(
const controller_manager_msgs::msg::ControllerState& s)
 
  166     return s.state == std::string(
"active");
 
  175   void discover(
bool force = 
false)
 
  178     if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
 
  181     controllers_stamp_ = node_->now();
 
  183     auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
 
  184     auto result_future = list_controllers_service_->async_send_request(request);
 
  185     if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
 
  187       RCLCPP_WARN_STREAM(LOGGER, 
"Failed to read controllers from " << list_controllers_service_->get_service_name()
 
  188                                                                     << 
" within " << service_call_timeout_.count()
 
  193     managed_controllers_.clear();
 
  194     active_controllers_.clear();
 
  196     auto result = result_future.get();
 
  202     for (
const controller_manager_msgs::msg::ControllerState& controller : result->controller)
 
  205       if (isActive(controller))
 
  208         auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
 
  209                                        .first->second.claimed_interfaces;  
 
  212         std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
 
  213                        [](
const std::string& claimed_interface) {
 
  214                          return parseJointNameFromResource(claimed_interface);
 
  219       if (loader_.isClassAvailable(controller.type))
 
  221         std::string absname = getAbsName(controller.name);
 
  222         auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first;  
 
  224         auto& required_interfaces = controller_it->second.required_command_interfaces;
 
  227         std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
 
  228                        [](
const std::string& required_interface) {
 
  229                          return parseJointNameFromResource(required_interface);
 
  231         allocate(absname, controller_it->second);
 
  242   void allocate(
const std::string& 
name, 
const controller_manager_msgs::msg::ControllerState& controller)
 
  244     if (handles_.find(
name) == handles_.end())
 
  246       const std::string& 
type = controller.type;
 
  247       AllocatorsMap::iterator alloc_it = allocators_.find(
type);
 
  248       if (alloc_it == allocators_.end())
 
  250         alloc_it = allocators_.insert(std::make_pair(
type, loader_.createUniqueInstance(
type))).first;
 
  253       std::vector<std::string> resources;
 
  255       for (
const auto& resource : controller.claimed_interfaces)
 
  260       moveit_controller_manager::MoveItControllerHandlePtr handle =
 
  261           alloc_it->second->alloc(node_, 
name, resources);  
 
  263         handles_.insert(std::make_pair(
name, handle));
 
  272   std::string getAbsName(
const std::string& 
name)
 
  282     : loader_(
"moveit_ros_control_interface", 
"moveit_ros_control_interface::ControllerHandleAllocator")
 
  284     RCLCPP_INFO_STREAM(LOGGER, 
"Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
 
  292     : ns_(ns), loader_(
"moveit_ros_control_interface", 
"moveit_ros_control_interface::ControllerHandleAllocator")
 
  296   void initialize(
const rclcpp::Node::SharedPtr& node)
 override 
  301       if (!node_->has_parameter(
"ros_control_namespace"))
 
  303         ns_ = node_->declare_parameter<std::string>(
"ros_control_namespace", 
"/");
 
  307         node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
 
  311     double timeout_seconds;
 
  312     if (!node_->has_parameter(
"controller_service_call_timeout"))
 
  315           node_->declare_parameter<
double>(
"controller_service_call_timeout", DEFAULT_SERVICE_CALL_TIMEOUT);
 
  319       node_->get_parameter(
"controller_service_call_timeout", timeout_seconds);
 
  321     service_call_timeout_ = std::chrono::duration<double>(timeout_seconds);
 
  323     RCLCPP_INFO_STREAM(LOGGER, 
"Using service call timeout " << service_call_timeout_.count() << 
" seconds");
 
  325     list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
 
  326         getAbsName(
"controller_manager/list_controllers"));
 
  327     switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
 
  328         getAbsName(
"controller_manager/switch_controller"));
 
  330     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  340     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  341     HandleMap::iterator it = handles_.find(
name);
 
  342     if (it != handles_.end())
 
  346     return moveit_controller_manager::MoveItControllerHandlePtr();
 
  355     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  358     for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
 
  359          managed_controllers_)
 
  361       names.push_back(managed_controller.first);
 
  371     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  374     for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
 
  375          managed_controllers_)
 
  377       if (isActive(managed_controller.second))
 
  378         names.push_back(managed_controller.first);
 
  389     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  390     ControllersMap::iterator it = managed_controllers_.find(
name);
 
  391     if (it != managed_controllers_.end())
 
  393       for (
const auto& required_resource : it->second.required_command_interfaces)
 
  395         joints.push_back(required_resource);
 
  407     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  411     ControllersMap::iterator it = managed_controllers_.find(
name);
 
  412     if (it != managed_controllers_.end())
 
  414       c.active_ = isActive(it->second);
 
  427                          const std::vector<std::string>& deactivate_base)
 override 
  430     auto add_all_dependencies = [](
const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
 
  431                                    const std::function<bool(
const std::string&)>& should_include,
 
  432                                    std::vector<std::string>& controllers) {
 
  433       auto queue = controllers;
 
  434       while (!queue.empty())
 
  436         auto controller = queue.back();
 
  438         if (controller.size() > 1 && controller[0] == 
'/')
 
  441           controller.erase(0, 1);
 
  443         if (dependencies.find(controller) == dependencies.end())
 
  447         for (
const auto& dependency : dependencies.at(controller))
 
  449           queue.push_back(dependency);
 
  450           if (should_include(dependency))
 
  452             controllers.push_back(
"/" + dependency);
 
  458     std::vector<std::string> activate = activate_base;
 
  459     add_all_dependencies(
 
  461         [
this](
const std::string& dependency) {
 
  462           return active_controllers_.find(dependency) == active_controllers_.end();
 
  465     std::vector<std::string> deactivate = deactivate_base;
 
  466     add_all_dependencies(
 
  467         dependency_map_reverse_,
 
  468         [
this](
const std::string& dependency) {
 
  469           return active_controllers_.find(dependency) != active_controllers_.end();
 
  475     std::reverse(activate.begin(), activate.end());
 
  477     std::scoped_lock<std::mutex> lock(controllers_mutex_);
 
  480     typedef boost::bimap<std::string, std::string> resources_bimap;
 
  482     resources_bimap claimed_resources;
 
  485     for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
 
  488       for (
const auto& resource : active_controller.second.claimed_interfaces)
 
  490         claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
 
  494     auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
 
  495     for (
const std::string& it : deactivate)
 
  497       ControllersMap::iterator 
c = managed_controllers_.find(it);
 
  498       if (
c != managed_controllers_.end())
 
  500         request->deactivate_controllers.push_back(
c->second.name);
 
  501         claimed_resources.right.erase(
c->second.name);  
 
  507     for (
const std::string& it : activate)
 
  509       ControllersMap::iterator 
c = managed_controllers_.find(it);
 
  510       if (
c != managed_controllers_.end())
 
  512         request->activate_controllers.push_back(
c->second.name);
 
  513         for (
const auto& required_resource : 
c->second.required_command_interfaces)
 
  515           resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
 
  516           if (res != claimed_resources.right.end())
 
  518             if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
 
  519                           res->second) == request->deactivate_controllers.end())
 
  521               request->deactivate_controllers.push_back(res->second);  
 
  523             claimed_resources.left.erase(res->second);  
 
  536     request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
 
  538     if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
 
  540       auto result_future = switch_controller_service_->async_send_request(request);
 
  541       if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
 
  543         RCLCPP_ERROR_STREAM(LOGGER, 
"Couldn't switch controllers at " << switch_controller_service_->get_service_name()
 
  544                                                                       << 
" within " << service_call_timeout_.count()
 
  549       return result_future.get()->ok;
 
  560     std::unordered_map<std::string, size_t> controller_name_map;
 
  561     for (
size_t i = 0; i < result->controller.size(); ++i)
 
  563       controller_name_map[result->controller[i].name] = i;
 
  566     dependency_map_.clear();
 
  567     dependency_map_reverse_.clear();
 
  568     for (
auto& controller : result->controller)
 
  570       if (controller.chain_connections.size() > 1)
 
  572         RCLCPP_ERROR_STREAM(LOGGER, 
"Controller with name %s chains to more than one controller. Chaining to more than " 
  573                                     "one controller is not supported.");
 
  576       for (
const auto& chained_controller : controller.chain_connections)
 
  578         auto ind = controller_name_map[chained_controller.name];
 
  579         dependency_map_[controller.name].push_back(chained_controller.name);
 
  580         dependency_map_reverse_[chained_controller.name].push_back(controller.name);
 
  581         std::copy(result->controller[ind].reference_interfaces.begin(),
 
  582                   result->controller[ind].reference_interfaces.end(),
 
  583                   std::back_inserter(controller.required_command_interfaces));
 
  596   typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
 
  597   ControllerManagersMap controller_managers_;
 
  598   rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
 
  599   std::mutex controller_managers_mutex_;
 
  601   rclcpp::Node::SharedPtr node_;
 
  603   void initialize(
const rclcpp::Node::SharedPtr& node)
 override 
  614     if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
 
  617     controller_managers_stamp_ = node_->now();
 
  619     const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
 
  621     for (
const auto& service : services)
 
  623       const auto& service_name = service.first;
 
  624       std::size_t found = service_name.find(
"controller_manager/list_controllers");
 
  625       if (found != std::string::npos)
 
  627         std::string ns = service_name.substr(0, found);
 
  628         if (controller_managers_.find(ns) == controller_managers_.end())
 
  630           RCLCPP_INFO_STREAM(LOGGER, 
"Adding controller_manager interface for node at namespace " << ns);
 
  631           auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
 
  632           controller_manager->initialize(node_);
 
  633           controller_managers_.insert(std::make_pair(ns, controller_manager));
 
  644   static std::string getNamespace(
const std::string& 
name)
 
  646     size_t pos = 
name.find(
'/', 1);
 
  647     if (pos == std::string::npos)
 
  649     return name.substr(0, pos + 1);
 
  660     std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  662     std::string ns = getNamespace(
name);
 
  663     ControllerManagersMap::iterator it = controller_managers_.find(ns);
 
  664     if (it != controller_managers_.end())
 
  666       return it->second->getControllerHandle(
name);
 
  668     return moveit_controller_manager::MoveItControllerHandlePtr();
 
  677     std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  680     for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
 
  681          controller_managers_)
 
  683       controller_manager.second->getControllersList(names);
 
  693     std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  696     for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
 
  697          controller_managers_)
 
  699       controller_manager.second->getActiveControllers(names);
 
  710     std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  712     std::string ns = getNamespace(
name);
 
  713     ControllerManagersMap::iterator it = controller_managers_.find(ns);
 
  714     if (it != controller_managers_.end())
 
  716       it->second->getControllerJoints(
name, joints);
 
  727     std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  729     std::string ns = getNamespace(
name);
 
  730     ControllerManagersMap::iterator it = controller_managers_.find(ns);
 
  731     if (it != controller_managers_.end())
 
  733       return it->second->getControllerState(
name);
 
  744   bool switchControllers(
const std::vector<std::string>& activate, 
const std::vector<std::string>& deactivate)
 override 
  746     std::unique_lock<std::mutex> lock(controller_managers_mutex_);
 
  748     for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
 
  749          controller_managers_)
 
  751       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)
 
void deconflictControllerActivationLists(std::vector< std::string > &activate_controllers, std::vector< std::string > &deactivate_controllers)
Modifies controller activation/deactivation lists to conform to ROS 2 control expectations....
 
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.