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);
60 static constexpr
double 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 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
128 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
131 ControllersMap managed_controllers_;
133 ControllersMap active_controllers_;
135 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
136 AllocatorsMap allocators_;
138 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
141 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
146 std::mutex controllers_mutex_;
148 rclcpp::Node::SharedPtr node_;
149 rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
150 rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
153 std::unordered_map<std::string , std::vector<std::string> > dependency_map_;
155 std::unordered_map<std::string , std::vector<std::string> >
156 dependency_map_reverse_;
163 static bool isActive(
const controller_manager_msgs::msg::ControllerState& s)
165 return s.state == std::string(
"active");
174 void discover(
bool force =
false)
177 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
180 controllers_stamp_ = node_->now();
182 auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
183 auto result_future = list_controllers_service_->async_send_request(request);
184 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
186 RCLCPP_WARN_STREAM(LOGGER,
"Failed to read controllers from " << list_controllers_service_->get_service_name()
187 <<
" within " << SERVICE_CALL_TIMEOUT
192 managed_controllers_.clear();
193 active_controllers_.clear();
195 auto result = result_future.get();
201 for (
const controller_manager_msgs::msg::ControllerState& controller : result->controller)
204 if (isActive(controller))
207 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
208 .first->second.claimed_interfaces;
211 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
212 [](
const std::string& claimed_interface) {
213 return parseJointNameFromResource(claimed_interface);
218 if (loader_.isClassAvailable(controller.type))
220 std::string absname = getAbsName(controller.name);
221 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first;
223 auto& required_interfaces = controller_it->second.required_command_interfaces;
226 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
227 [](
const std::string& required_interface) {
228 return parseJointNameFromResource(required_interface);
230 allocate(absname, controller_it->second);
241 void allocate(
const std::string&
name,
const controller_manager_msgs::msg::ControllerState& controller)
243 if (handles_.find(
name) == handles_.end())
245 const std::string&
type = controller.type;
246 AllocatorsMap::iterator alloc_it = allocators_.find(
type);
247 if (alloc_it == allocators_.end())
249 alloc_it = allocators_.insert(std::make_pair(
type, loader_.createUniqueInstance(
type))).first;
252 std::vector<std::string> resources;
254 for (
const auto& resource : controller.claimed_interfaces)
259 moveit_controller_manager::MoveItControllerHandlePtr handle =
260 alloc_it->second->alloc(node_,
name, resources);
262 handles_.insert(std::make_pair(
name, handle));
271 std::string getAbsName(
const std::string&
name)
281 : loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
283 RCLCPP_INFO_STREAM(LOGGER,
"Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
291 : ns_(ns), loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
295 void initialize(
const rclcpp::Node::SharedPtr& node)
override
300 if (!node_->has_parameter(
"ros_control_namespace"))
302 ns_ = node_->declare_parameter<std::string>(
"ros_control_namespace",
"/");
306 node_->get_parameter<std::string>(
"ros_control_namespace", ns_);
310 list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
311 getAbsName(
"controller_manager/list_controllers"));
312 switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
313 getAbsName(
"controller_manager/switch_controller"));
315 std::scoped_lock<std::mutex> lock(controllers_mutex_);
325 std::scoped_lock<std::mutex> lock(controllers_mutex_);
326 HandleMap::iterator it = handles_.find(
name);
327 if (it != handles_.end())
331 return moveit_controller_manager::MoveItControllerHandlePtr();
340 std::scoped_lock<std::mutex> lock(controllers_mutex_);
343 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
344 managed_controllers_)
346 names.push_back(managed_controller.first);
356 std::scoped_lock<std::mutex> lock(controllers_mutex_);
359 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
360 managed_controllers_)
362 if (isActive(managed_controller.second))
363 names.push_back(managed_controller.first);
374 std::scoped_lock<std::mutex> lock(controllers_mutex_);
375 ControllersMap::iterator it = managed_controllers_.find(
name);
376 if (it != managed_controllers_.end())
378 for (
const auto& required_resource : it->second.required_command_interfaces)
380 joints.push_back(required_resource);
392 std::scoped_lock<std::mutex> lock(controllers_mutex_);
396 ControllersMap::iterator it = managed_controllers_.find(
name);
397 if (it != managed_controllers_.end())
399 c.active_ = isActive(it->second);
412 const std::vector<std::string>& deactivate_base)
override
415 auto add_all_dependencies = [](
const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
416 const std::function<bool(
const std::string&)>& should_include,
417 std::vector<std::string>& controllers) {
418 auto queue = controllers;
419 while (!queue.empty())
421 auto controller = queue.back();
423 if (controller.size() > 1 && controller[0] ==
'/')
426 controller.erase(0, 1);
428 if (dependencies.find(controller) == dependencies.end())
432 for (
const auto& dependency : dependencies.at(controller))
434 queue.push_back(dependency);
435 if (should_include(dependency))
437 controllers.push_back(
"/" + dependency);
443 std::vector<std::string> activate = activate_base;
444 add_all_dependencies(
446 [
this](
const std::string& dependency) {
447 return active_controllers_.find(dependency) == active_controllers_.end();
450 std::vector<std::string> deactivate = deactivate_base;
451 add_all_dependencies(
452 dependency_map_reverse_,
453 [
this](
const std::string& dependency) {
454 return active_controllers_.find(dependency) != active_controllers_.end();
460 std::reverse(activate.begin(), activate.end());
462 std::scoped_lock<std::mutex> lock(controllers_mutex_);
465 typedef boost::bimap<std::string, std::string> resources_bimap;
467 resources_bimap claimed_resources;
470 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
473 for (
const auto& resource : active_controller.second.claimed_interfaces)
475 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
479 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
480 for (
const std::string& it : deactivate)
482 ControllersMap::iterator
c = managed_controllers_.find(it);
483 if (
c != managed_controllers_.end())
485 request->deactivate_controllers.push_back(
c->second.name);
486 claimed_resources.right.erase(
c->second.name);
492 for (
const std::string& it : activate)
494 ControllersMap::iterator
c = managed_controllers_.find(it);
495 if (
c != managed_controllers_.end())
497 request->activate_controllers.push_back(
c->second.name);
498 for (
const auto& required_resource :
c->second.required_command_interfaces)
500 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
501 if (res != claimed_resources.right.end())
503 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
504 res->second) == request->deactivate_controllers.end())
506 request->deactivate_controllers.push_back(res->second);
508 claimed_resources.left.erase(res->second);
521 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
523 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
525 auto result_future = switch_controller_service_->async_send_request(request);
526 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
528 RCLCPP_ERROR_STREAM(LOGGER,
"Couldn't switch controllers at " << switch_controller_service_->get_service_name()
529 <<
" within " << SERVICE_CALL_TIMEOUT
534 return result_future.get()->ok;
545 std::unordered_map<std::string, size_t> controller_name_map;
546 for (
size_t i = 0; i < result->controller.size(); ++i)
548 controller_name_map[result->controller[i].name] = i;
551 dependency_map_.clear();
552 dependency_map_reverse_.clear();
553 for (
auto& controller : result->controller)
555 if (controller.chain_connections.size() > 1)
557 RCLCPP_ERROR_STREAM(LOGGER,
"Controller with name %s chains to more than one controller. Chaining to more than "
558 "one controller is not supported.");
561 for (
const auto& chained_controller : controller.chain_connections)
563 auto ind = controller_name_map[chained_controller.name];
564 dependency_map_[controller.name].push_back(chained_controller.name);
565 dependency_map_reverse_[chained_controller.name].push_back(controller.name);
566 std::copy(result->controller[ind].reference_interfaces.begin(),
567 result->controller[ind].reference_interfaces.end(),
568 std::back_inserter(controller.required_command_interfaces));
581 typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
582 ControllerManagersMap controller_managers_;
583 rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
584 std::mutex controller_managers_mutex_;
586 rclcpp::Node::SharedPtr node_;
588 void initialize(
const rclcpp::Node::SharedPtr& node)
override
599 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
602 controller_managers_stamp_ = node_->now();
604 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
606 for (
const auto& service : services)
608 const auto& service_name = service.first;
609 std::size_t found = service_name.find(
"controller_manager/list_controllers");
610 if (found != std::string::npos)
612 std::string ns = service_name.substr(0, found);
613 if (controller_managers_.find(ns) == controller_managers_.end())
615 RCLCPP_INFO_STREAM(LOGGER,
"Adding controller_manager interface for node at namespace " << ns);
616 auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
617 controller_manager->initialize(node_);
618 controller_managers_.insert(std::make_pair(ns, controller_manager));
629 static std::string getNamespace(
const std::string&
name)
631 size_t pos =
name.find(
'/', 1);
632 if (pos == std::string::npos)
634 return name.substr(0, pos + 1);
645 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
647 std::string ns = getNamespace(
name);
648 ControllerManagersMap::iterator it = controller_managers_.find(ns);
649 if (it != controller_managers_.end())
651 return it->second->getControllerHandle(
name);
653 return moveit_controller_manager::MoveItControllerHandlePtr();
662 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
665 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
666 controller_managers_)
668 controller_manager.second->getControllersList(names);
678 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
681 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
682 controller_managers_)
684 controller_manager.second->getActiveControllers(names);
695 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
697 std::string ns = getNamespace(
name);
698 ControllerManagersMap::iterator it = controller_managers_.find(ns);
699 if (it != controller_managers_.end())
701 it->second->getControllerJoints(
name, joints);
712 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
714 std::string ns = getNamespace(
name);
715 ControllerManagersMap::iterator it = controller_managers_.find(ns);
716 if (it != controller_managers_.end())
718 return it->second->getControllerState(
name);
729 bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
override
731 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
733 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
734 controller_managers_)
736 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.