moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
controller_manager_plugin.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2015, Fraunhofer IPA
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Fraunhofer IPA nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Mathias Lüdtke */
36
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 <boost/bimap/unordered_multiset_of.hpp>
47#include <rclcpp/client.hpp>
48#include <rclcpp/duration.hpp>
49#include <rclcpp/logger.hpp>
50#include <rclcpp/logging.hpp>
51#include <rclcpp/node.hpp>
52#include <rclcpp/parameter_value.hpp>
53#include <rclcpp/time.hpp>
54#include <map>
55#include <memory>
56#include <queue>
58
59static const rclcpp::Duration CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Duration::from_seconds(1.0);
60static const double SERVICE_CALL_TIMEOUT = 1.0;
61
63{
64namespace
65{
66rclcpp::Logger getLogger()
67{
68 return moveit::getLogger("moveit.plugins.ros_control_interface");
69}
70} // namespace
71
78std::string parseJointNameFromResource(const std::string& claimed_interface)
79{
80 const auto index = claimed_interface.find('/');
81 if (index == std::string::npos)
82 return claimed_interface;
83 return claimed_interface.substr(0, index);
84}
85
95void deconflictControllerActivationLists(std::vector<std::string>& activate_controllers,
96 std::vector<std::string>& deactivate_controllers)
97{
98 // Convert vectors to sets for uniqueness
99 std::unordered_set activate_set(activate_controllers.begin(), activate_controllers.end());
100 std::unordered_set deactivate_set(deactivate_controllers.begin(), deactivate_controllers.end());
101
102 // Find common elements
103 std::unordered_set<std::string> common_controllers;
104 for (const auto& str : activate_set)
105 {
106 if (deactivate_set.count(str))
107 {
108 common_controllers.insert(str);
109 }
110 }
111
112 // Remove common elements from both sets
113 for (const auto& controller_name : common_controllers)
114 {
115 activate_set.erase(controller_name);
116 deactivate_set.erase(controller_name);
117 }
118
119 // Convert sets back to vectors
120 activate_controllers.assign(activate_set.begin(), activate_set.end());
121 deactivate_controllers.assign(deactivate_set.begin(), deactivate_set.end());
122}
123
124MOVEIT_CLASS_FORWARD(Ros2ControlManager); // Defines Ros2ControlManagerPtr, ConstPtr, WeakPtr... etc
125
133{
134 std::string ns_;
135 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
136 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
137
139 ControllersMap managed_controllers_;
141 ControllersMap active_controllers_;
142
143 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
144 AllocatorsMap allocators_;
145
146 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
147 HandleMap handles_;
148
149 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
150
154 std::mutex controllers_mutex_;
155
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_;
159
160 // Chained controllers have dependent controllers (other controllers which must be started if the chained controller is started)
161 std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
162 // Controllers may have preceding chained controllers (other chained controllers which must be shutdown if the controller is shutdown)
163 std::unordered_map<std::string /* controller name */, std::vector<std::string> /* reverse dependencies */>
164 dependency_map_reverse_;
165
171 static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
172 {
173 return s.state == std::string("active");
174 }
175
182 void discover(bool force = false)
183 {
184 // Skip if controller stamp is too new for new discovery, enforce update if force==true
185 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
186 {
187 return;
188 }
189
190 controllers_stamp_ = node_->now();
191
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)
195 {
196 RCLCPP_WARN_STREAM(getLogger(), "Failed to read controllers from "
197 << list_controllers_service_->get_service_name() << " within "
198 << SERVICE_CALL_TIMEOUT << " seconds");
199 return;
200 }
201
202 managed_controllers_.clear();
203 active_controllers_.clear();
204
205 auto result = result_future.get();
207 {
208 return;
209 }
210
211 for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
212 {
213 // If the controller is active, add it to the map of active controllers.
214 if (isActive(controller))
215 {
216 // Get the names of the interfaces currently claimed by the active controller.
217 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
218 .first->second.claimed_interfaces; // without namespace
219 // Modify the claimed interface names in-place to only include the name of the joint and not the command type
220 // (e.g. position, velocity, etc.).
221 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
222 [](const std::string& claimed_interface) {
223 return parseJointNameFromResource(claimed_interface);
224 });
225 }
226
227 // Instantiate a controller handle if one is available for this type of controller.
228 if (loader_.isClassAvailable(controller.type))
229 {
230 std::string absname = getAbsName(controller.name);
231 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
232 // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
233 auto& required_interfaces = controller_it->second.required_command_interfaces;
234 // Modify the required interface names in-place to only include the name of the joint and not the command type
235 // (e.g. position, velocity, etc.).
236 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
237 [](const std::string& required_interface) {
238 return parseJointNameFromResource(required_interface);
239 });
240 allocate(absname, controller_it->second);
241 }
242 }
243 }
244
251 void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
252 {
253 if (handles_.find(name) == handles_.end())
254 {
255 const std::string& type = controller.type;
256 AllocatorsMap::iterator alloc_it = allocators_.find(type);
257 if (alloc_it == allocators_.end())
258 { // create allocator if needed
259 alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
260 }
261
262 std::vector<std::string> resources;
263 // Collect claimed resources across different hardware interfaces
264 for (const auto& resource : controller.claimed_interfaces)
265 {
266 resources.push_back(parseJointNameFromResource(resource));
267 }
268
269 moveit_controller_manager::MoveItControllerHandlePtr handle =
270 alloc_it->second->alloc(node_, name, resources); // allocate handle
271 if (handle)
272 handles_.insert(std::make_pair(name, handle));
273 }
274 }
275
281 std::string getAbsName(const std::string& name)
282 {
283 return rclcpp::names::append(ns_, name);
284 }
285
286public:
291 : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
292 {
293 }
294
299 Ros2ControlManager(const std::string& ns)
300 : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
301 {
302 RCLCPP_INFO_STREAM(getLogger(), "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
303 }
304
305 void initialize(const rclcpp::Node::SharedPtr& node) override
306 {
307 node_ = node;
308 if (ns_.empty())
309 {
310 if (!node_->has_parameter("ros_control_namespace"))
311 {
312 ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
313 }
314 else
315 {
316 node_->get_parameter<std::string>("ros_control_namespace", ns_);
317 }
318 }
319
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"));
324
325 std::scoped_lock<std::mutex> lock(controllers_mutex_);
326 discover(true);
327 }
333 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
334 {
335 std::scoped_lock<std::mutex> lock(controllers_mutex_);
336 HandleMap::iterator it = handles_.find(name);
337 if (it != handles_.end())
338 { // controller is manager by this interface
339 return it->second;
340 }
341 return moveit_controller_manager::MoveItControllerHandlePtr();
342 }
343
348 void getControllersList(std::vector<std::string>& names) override
349 {
350 std::scoped_lock<std::mutex> lock(controllers_mutex_);
351 discover();
352
353 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
354 managed_controllers_)
355 {
356 names.push_back(managed_controller.first);
357 }
358 }
359
364 void getActiveControllers(std::vector<std::string>& names) override
365 {
366 std::scoped_lock<std::mutex> lock(controllers_mutex_);
367 discover();
368
369 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
370 managed_controllers_)
371 {
372 if (isActive(managed_controller.second))
373 names.push_back(managed_controller.first);
374 }
375 }
376
382 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
383 {
384 std::scoped_lock<std::mutex> lock(controllers_mutex_);
385 ControllersMap::iterator it = managed_controllers_.find(name);
386 if (it != managed_controllers_.end())
387 {
388 for (const auto& required_resource : it->second.required_command_interfaces)
389 {
390 joints.push_back(required_resource);
391 }
392 }
393 }
394
400 ControllerState getControllerState(const std::string& name) override
401 {
402 std::scoped_lock<std::mutex> lock(controllers_mutex_);
403 discover();
404
406 ControllersMap::iterator it = managed_controllers_.find(name);
407 if (it != managed_controllers_.end())
408 {
409 c.active_ = isActive(it->second);
410 }
411 return c;
412 }
413
421 bool switchControllers(const std::vector<std::string>& activate_base,
422 const std::vector<std::string>& deactivate_base) override
423 {
424 // add_all_dependencies traverses the provided dependency map and appends the results to the controllers vector.
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())
430 {
431 auto controller = queue.back();
432 queue.pop_back();
433 if (controller.size() > 1 && controller[0] == '/')
434 {
435 // Remove leading / from controller name
436 controller.erase(0, 1);
437 }
438 if (dependencies.find(controller) == dependencies.end())
439 {
440 continue;
441 }
442 for (const auto& dependency : dependencies.at(controller))
443 {
444 queue.push_back(dependency);
445 if (should_include(dependency))
446 {
447 controllers.push_back("/" + dependency);
448 }
449 }
450 }
451 };
452
453 std::vector<std::string> activate = activate_base;
454 add_all_dependencies(
455 dependency_map_,
456 [this](const std::string& dependency) {
457 return active_controllers_.find(dependency) == active_controllers_.end();
458 },
459 activate);
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();
465 },
466 deactivate);
467
468 // The dependencies for chained controller activation must be started first, but they are processed last, so the
469 // order needs to be flipped
470 std::reverse(activate.begin(), activate.end());
471
472 std::scoped_lock<std::mutex> lock(controllers_mutex_);
473 discover(true);
474
475 // Holds the list of controllers that are currently active and their resources
476 // Example:
477 // controller1:
478 // - controller1_joint1
479 // - controller1_joint2
480 // ...
481 // controller2:
482 // - controller2_joint1
483 // - controller2_joint2
484 // ...
485 // ...
486 // The left type have to be an unordered_multiset_of, because each controller can claim multiple resources
487 // {{ "controller1", "controller1_joint1" },
488 // { "controller1", "controller1_joint2" },
489 // ...,
490 // { "controller2", "controller2_joint1" },
491 // { "controller2", "controller2_joint2" },
492 // ...}
493 typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
494
495 resources_bimap claimed_resources;
496
497 // fill bimap with active controllers and their resources
498 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
499 active_controllers_)
500 {
501 for (const auto& resource : active_controller.second.claimed_interfaces)
502 {
503 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
504 }
505 }
506
507 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
508 for (const std::string& it : deactivate)
509 {
510 ControllersMap::iterator c = managed_controllers_.find(it);
511 if (c != managed_controllers_.end())
512 { // controller belongs to this manager
513 request->deactivate_controllers.push_back(c->second.name);
514 claimed_resources.left.erase(c->second.name); // remove resources
515 }
516 }
517
518 // For each controller to activate, find conflicts between the interfaces required by that controller and the
519 // interfaces claimed by currently-active controllers.
520 for (const std::string& it : activate)
521 {
522 ControllersMap::iterator c = managed_controllers_.find(it);
523 if (c != managed_controllers_.end())
524 { // controller belongs to this manager
525 request->activate_controllers.push_back(c->second.name);
526 for (const auto& required_resource : c->second.required_command_interfaces)
527 {
528 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
529 if (res != claimed_resources.right.end())
530 { // resource is claimed
531 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
532 res->second) == request->deactivate_controllers.end())
533 {
534 request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
535 }
536 claimed_resources.left.erase(res->second); // remove claimed resources
537 }
538 }
539 }
540 }
541
542 // ROS2 Control expects simplified controller activation/deactivation.
543 // E.g. a controller should not be stopped and started at the same time, rather it should be removed from both the
544 // activation and deactivation request.
545 deconflictControllerActivationLists(request->activate_controllers, request->deactivate_controllers);
546
547 // Setting level to STRICT means that the controller switch will only be committed if all controllers are
548 // successfully activated or deactivated.
549 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
550
551 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
552 { // something to switch?
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)
555 {
556 RCLCPP_ERROR_STREAM(getLogger(), "Couldn't switch controllers at "
557 << switch_controller_service_->get_service_name() << " within "
558 << SERVICE_CALL_TIMEOUT << " seconds");
559 return false;
560 }
561 discover(true);
562 return result_future.get()->ok;
563 }
564 return true;
565 }
571 bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
572 {
573 std::unordered_map<std::string, size_t> controller_name_map;
574 for (size_t i = 0; i < result->controller.size(); ++i)
575 {
576 controller_name_map[result->controller[i].name] = i;
577 }
578
579 dependency_map_.clear();
580 dependency_map_reverse_.clear();
581 for (auto& controller : result->controller)
582 {
583 if (controller.chain_connections.size() > 1)
584 {
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.");
588 return false;
589 }
590 for (const auto& chained_controller : controller.chain_connections)
591 {
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));
598 }
599 }
600
601 return true;
602 }
603};
609{
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_;
614
615 rclcpp::Node::SharedPtr node_;
616
617 void initialize(const rclcpp::Node::SharedPtr& node) override
618 {
619 node_ = node;
620 }
625 void discover()
626 {
627 // Skip if last discovery is too new for discovery rate
628 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
629 return;
630
631 controller_managers_stamp_ = node_->now();
632
633 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
634
635 for (const auto& service : services)
636 {
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)
640 {
641 std::string ns = service_name.substr(0, found);
642 if (controller_managers_.find(ns) == controller_managers_.end())
643 { // create Ros2ControlManager if it does not exist
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));
648 }
649 }
650 }
651 }
652
658 static std::string getNamespace(const std::string& name)
659 {
660 size_t pos = name.find('/', 1);
661 if (pos == std::string::npos)
662 pos = 0;
663 return name.substr(0, pos + 1);
664 }
665
666public:
672 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
673 {
674 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
675
676 std::string ns = getNamespace(name);
677 ControllerManagersMap::iterator it = controller_managers_.find(ns);
678 if (it != controller_managers_.end())
679 {
680 return it->second->getControllerHandle(name);
681 }
682 return moveit_controller_manager::MoveItControllerHandlePtr();
683 }
684
689 void getControllersList(std::vector<std::string>& names) override
690 {
691 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
692 discover();
693
694 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
695 controller_managers_)
696 {
697 controller_manager.second->getControllersList(names);
698 }
699 }
700
705 void getActiveControllers(std::vector<std::string>& names) override
706 {
707 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
708 discover();
709
710 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
711 controller_managers_)
712 {
713 controller_manager.second->getActiveControllers(names);
714 }
715 }
716
722 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
723 {
724 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
725
726 std::string ns = getNamespace(name);
727 ControllerManagersMap::iterator it = controller_managers_.find(ns);
728 if (it != controller_managers_.end())
729 {
730 it->second->getControllerJoints(name, joints);
731 }
732 }
733
739 ControllerState getControllerState(const std::string& name) override
740 {
741 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
742
743 std::string ns = getNamespace(name);
744 ControllerManagersMap::iterator it = controller_managers_.find(ns);
745 if (it != controller_managers_.end())
746 {
747 return it->second->getControllerState(name);
748 }
749 return ControllerState();
750 }
751
758 bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
759 {
760 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
761
762 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
763 controller_managers_)
764 {
765 if (!controller_manager.second->switchControllers(activate, deactivate))
766 return false;
767 }
768 return true;
769 }
770};
771
772} // namespace moveit_ros_control_interface
773
776
#define MOVEIT_CLASS_FORWARD(C)
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...
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....
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
std::string append(const std::string &left, const std::string &right)
Each controller known to MoveIt has a state. This structure describes that controller's state.
bool active_
A controller can be active or inactive. This means that MoveIt could activate the controller when nee...