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);
60
62{
63static constexpr double DEFAULT_SERVICE_CALL_TIMEOUT = 3.0;
64
65namespace
66{
67rclcpp::Logger getLogger()
68{
69 return moveit::getLogger("moveit.plugins.ros_control_interface");
70}
71} // namespace
72
79std::string parseJointNameFromResource(const std::string& claimed_interface)
80{
81 const auto index = claimed_interface.find('/');
82 if (index == std::string::npos)
83 return claimed_interface;
84 return claimed_interface.substr(0, index);
85}
86
96void deconflictControllerActivationLists(std::vector<std::string>& activate_controllers,
97 std::vector<std::string>& deactivate_controllers)
98{
99 // Convert vectors to sets for uniqueness
100 std::unordered_set activate_set(activate_controllers.begin(), activate_controllers.end());
101 std::unordered_set deactivate_set(deactivate_controllers.begin(), deactivate_controllers.end());
102
103 // Find common elements
104 std::unordered_set<std::string> common_controllers;
105 for (const auto& str : activate_set)
106 {
107 if (deactivate_set.count(str))
108 {
109 common_controllers.insert(str);
110 }
111 }
112
113 // Remove common elements from both sets
114 for (const auto& controller_name : common_controllers)
115 {
116 activate_set.erase(controller_name);
117 deactivate_set.erase(controller_name);
118 }
119
120 // Convert sets back to vectors
121 activate_controllers.assign(activate_set.begin(), activate_set.end());
122 deactivate_controllers.assign(deactivate_set.begin(), deactivate_set.end());
123}
124
125MOVEIT_CLASS_FORWARD(Ros2ControlManager); // Defines Ros2ControlManagerPtr, ConstPtr, WeakPtr... etc
126
134{
135 std::string ns_;
136 std::chrono::duration<double> service_call_timeout_;
137 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
138 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
139
141 ControllersMap managed_controllers_;
143 ControllersMap active_controllers_;
144
145 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
146 AllocatorsMap allocators_;
147
148 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
149 HandleMap handles_;
150
151 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
152
156 std::mutex controllers_mutex_;
157
158 rclcpp::Node::SharedPtr node_;
159 rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
160 rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
161
162 // Chained controllers have dependent controllers (other controllers which must be started if the chained controller is started)
163 std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
164 // Controllers may have preceding chained controllers (other chained controllers which must be shutdown if the controller is shutdown)
165 std::unordered_map<std::string /* controller name */, std::vector<std::string> /* reverse dependencies */>
166 dependency_map_reverse_;
167
173 static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
174 {
175 return s.state == std::string("active");
176 }
177
184 void discover(bool force = false)
185 {
186 // Skip if controller stamp is too new for new discovery, enforce update if force==true
187 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
188 {
189 return;
190 }
191
192 controllers_stamp_ = node_->now();
193
194 auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
195 auto result_future = list_controllers_service_->async_send_request(request);
196 if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
197 {
198 RCLCPP_WARN_STREAM(getLogger(), "Failed to read controllers from "
199 << list_controllers_service_->get_service_name() << " within "
200 << service_call_timeout_.count() << " seconds");
201 return;
202 }
203
204 managed_controllers_.clear();
205 active_controllers_.clear();
206
207 auto result = result_future.get();
209 {
210 return;
211 }
212
213 for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
214 {
215 // If the controller is active, add it to the map of active controllers.
216 if (isActive(controller))
217 {
218 // Get the names of the interfaces currently claimed by the active controller.
219 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
220 .first->second.claimed_interfaces; // without namespace
221 // Modify the claimed interface names in-place to only include the name of the joint and not the command type
222 // (e.g. position, velocity, etc.).
223 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
224 [](const std::string& claimed_interface) {
225 return parseJointNameFromResource(claimed_interface);
226 });
227 }
228
229 // Instantiate a controller handle if one is available for this type of controller.
230 if (loader_.isClassAvailable(controller.type))
231 {
232 std::string absname = getAbsName(controller.name);
233 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
234 // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
235 auto& required_interfaces = controller_it->second.required_command_interfaces;
236 // Modify the required interface names in-place to only include the name of the joint and not the command type
237 // (e.g. position, velocity, etc.).
238 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
239 [](const std::string& required_interface) {
240 return parseJointNameFromResource(required_interface);
241 });
242 allocate(absname, controller_it->second);
243 }
244 }
245 }
246
253 void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
254 {
255 if (handles_.find(name) == handles_.end())
256 {
257 const std::string& type = controller.type;
258 AllocatorsMap::iterator alloc_it = allocators_.find(type);
259 if (alloc_it == allocators_.end())
260 { // create allocator if needed
261 alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
262 }
263
264 std::vector<std::string> resources;
265 // Collect claimed resources across different hardware interfaces
266 for (const auto& resource : controller.claimed_interfaces)
267 {
268 resources.push_back(parseJointNameFromResource(resource));
269 }
270
271 moveit_controller_manager::MoveItControllerHandlePtr handle =
272 alloc_it->second->alloc(node_, name, resources); // allocate handle
273 if (handle)
274 handles_.insert(std::make_pair(name, handle));
275 }
276 }
277
283 std::string getAbsName(const std::string& name)
284 {
285 return rclcpp::names::append(ns_, name);
286 }
287
288public:
293 : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
294 {
295 }
296
301 Ros2ControlManager(const std::string& ns)
302 : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
303 {
304 RCLCPP_INFO_STREAM(getLogger(), "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
305 }
306
307 void initialize(const rclcpp::Node::SharedPtr& node) override
308 {
309 node_ = node;
310 if (ns_.empty())
311 {
312 if (!node_->has_parameter("ros_control_namespace"))
313 {
314 ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
315 }
316 else
317 {
318 node_->get_parameter<std::string>("ros_control_namespace", ns_);
319 }
320 }
321
322 double timeout_seconds;
323 if (!node_->has_parameter("controller_service_call_timeout"))
324 {
325 timeout_seconds =
326 node_->declare_parameter<double>("controller_service_call_timeout", DEFAULT_SERVICE_CALL_TIMEOUT);
327 }
328 else
329 {
330 node_->get_parameter("controller_service_call_timeout", timeout_seconds);
331 }
332 service_call_timeout_ = std::chrono::duration<double>(timeout_seconds);
333
334 RCLCPP_INFO_STREAM(getLogger(), "Using service call timeout " << service_call_timeout_.count() << " seconds");
335
336 list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
337 getAbsName("controller_manager/list_controllers"));
338 switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
339 getAbsName("controller_manager/switch_controller"));
340
341 std::scoped_lock<std::mutex> lock(controllers_mutex_);
342 discover(true);
343 }
349 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
350 {
351 std::scoped_lock<std::mutex> lock(controllers_mutex_);
352 HandleMap::iterator it = handles_.find(name);
353 if (it != handles_.end())
354 { // controller is manager by this interface
355 return it->second;
356 }
357 return moveit_controller_manager::MoveItControllerHandlePtr();
358 }
359
364 void getControllersList(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 names.push_back(managed_controller.first);
373 }
374 }
375
380 void getActiveControllers(std::vector<std::string>& names) override
381 {
382 std::scoped_lock<std::mutex> lock(controllers_mutex_);
383 discover();
384
385 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
386 managed_controllers_)
387 {
388 if (isActive(managed_controller.second))
389 names.push_back(managed_controller.first);
390 }
391 }
392
398 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
399 {
400 std::scoped_lock<std::mutex> lock(controllers_mutex_);
401 ControllersMap::iterator it = managed_controllers_.find(name);
402 if (it != managed_controllers_.end())
403 {
404 for (const auto& required_resource : it->second.required_command_interfaces)
405 {
406 joints.push_back(required_resource);
407 }
408 }
409 }
410
416 ControllerState getControllerState(const std::string& name) override
417 {
418 std::scoped_lock<std::mutex> lock(controllers_mutex_);
419 discover();
420
422 ControllersMap::iterator it = managed_controllers_.find(name);
423 if (it != managed_controllers_.end())
424 {
425 c.active_ = isActive(it->second);
426 }
427 return c;
428 }
429
437 bool switchControllers(const std::vector<std::string>& activate_base,
438 const std::vector<std::string>& deactivate_base) override
439 {
440 // add_all_dependencies traverses the provided dependency map and appends the results to the controllers vector.
441 auto add_all_dependencies = [](const std::unordered_map<std::string, std::vector<std::string>>& dependencies,
442 const std::function<bool(const std::string&)>& should_include,
443 std::vector<std::string>& controllers) {
444 auto queue = controllers;
445 while (!queue.empty())
446 {
447 auto controller = queue.back();
448 queue.pop_back();
449 if (controller.size() > 1 && controller[0] == '/')
450 {
451 // Remove leading / from controller name
452 controller.erase(0, 1);
453 }
454 if (dependencies.find(controller) == dependencies.end())
455 {
456 continue;
457 }
458 for (const auto& dependency : dependencies.at(controller))
459 {
460 queue.push_back(dependency);
461 if (should_include(dependency))
462 {
463 controllers.push_back("/" + dependency);
464 }
465 }
466 }
467 };
468
469 std::vector<std::string> activate = activate_base;
470 add_all_dependencies(
471 dependency_map_,
472 [this](const std::string& dependency) {
473 return active_controllers_.find(dependency) == active_controllers_.end();
474 },
475 activate);
476 std::vector<std::string> deactivate = deactivate_base;
477 add_all_dependencies(
478 dependency_map_reverse_,
479 [this](const std::string& dependency) {
480 return active_controllers_.find(dependency) != active_controllers_.end();
481 },
482 deactivate);
483
484 // The dependencies for chained controller activation must be started first, but they are processed last, so the
485 // order needs to be flipped
486 std::reverse(activate.begin(), activate.end());
487
488 std::scoped_lock<std::mutex> lock(controllers_mutex_);
489 discover(true);
490
491 // Holds the list of controllers that are currently active and their resources
492 // Example:
493 // controller1:
494 // - controller1_joint1
495 // - controller1_joint2
496 // ...
497 // controller2:
498 // - controller2_joint1
499 // - controller2_joint2
500 // ...
501 // ...
502 // The left type have to be an unordered_multiset_of, because each controller can claim multiple resources
503 // {{ "controller1", "controller1_joint1" },
504 // { "controller1", "controller1_joint2" },
505 // ...,
506 // { "controller2", "controller2_joint1" },
507 // { "controller2", "controller2_joint2" },
508 // ...}
509 typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
510
511 resources_bimap claimed_resources;
512
513 // fill bimap with active controllers and their resources
514 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
515 active_controllers_)
516 {
517 for (const auto& resource : active_controller.second.claimed_interfaces)
518 {
519 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
520 }
521 }
522
523 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
524 for (const std::string& it : deactivate)
525 {
526 ControllersMap::iterator c = managed_controllers_.find(it);
527 if (c != managed_controllers_.end())
528 { // controller belongs to this manager
529 request->deactivate_controllers.push_back(c->second.name);
530 claimed_resources.left.erase(c->second.name); // remove resources
531 }
532 }
533
534 // For each controller to activate, find conflicts between the interfaces required by that controller and the
535 // interfaces claimed by currently-active controllers.
536 for (const std::string& it : activate)
537 {
538 ControllersMap::iterator c = managed_controllers_.find(it);
539 if (c != managed_controllers_.end())
540 { // controller belongs to this manager
541 request->activate_controllers.push_back(c->second.name);
542 for (const auto& required_resource : c->second.required_command_interfaces)
543 {
544 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
545 if (res != claimed_resources.right.end())
546 { // resource is claimed
547 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
548 res->second) == request->deactivate_controllers.end())
549 {
550 request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
551 }
552 claimed_resources.left.erase(res->second); // remove claimed resources
553 }
554 }
555 }
556 }
557
558 // ROS2 Control expects simplified controller activation/deactivation.
559 // E.g. a controller should not be stopped and started at the same time, rather it should be removed from both the
560 // activation and deactivation request.
561 deconflictControllerActivationLists(request->activate_controllers, request->deactivate_controllers);
562
563 // Setting level to STRICT means that the controller switch will only be committed if all controllers are
564 // successfully activated or deactivated.
565 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
566
567 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
568 { // something to switch?
569 auto result_future = switch_controller_service_->async_send_request(request);
570 if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
571 {
572 RCLCPP_ERROR_STREAM(getLogger(), "Couldn't switch controllers at "
573 << switch_controller_service_->get_service_name() << " within "
574 << service_call_timeout_.count() << " seconds");
575 return false;
576 }
577 discover(true);
578 return result_future.get()->ok;
579 }
580 return true;
581 }
587 bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
588 {
589 std::unordered_map<std::string, size_t> controller_name_map;
590 for (size_t i = 0; i < result->controller.size(); ++i)
591 {
592 controller_name_map[result->controller[i].name] = i;
593 }
594
595 dependency_map_.clear();
596 dependency_map_reverse_.clear();
597 for (auto& controller : result->controller)
598 {
599 if (controller.chain_connections.size() > 1)
600 {
601 RCLCPP_ERROR_STREAM(getLogger(),
602 "Controller with name %s chains to more than one controller. Chaining to more than "
603 "one controller is not supported.");
604 return false;
605 }
606 for (const auto& chained_controller : controller.chain_connections)
607 {
608 auto ind = controller_name_map[chained_controller.name];
609 dependency_map_[controller.name].push_back(chained_controller.name);
610 dependency_map_reverse_[chained_controller.name].push_back(controller.name);
611 std::copy(result->controller[ind].reference_interfaces.begin(),
612 result->controller[ind].reference_interfaces.end(),
613 std::back_inserter(controller.required_command_interfaces));
614 }
615 }
616
617 return true;
618 }
619};
625{
626 typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
627 ControllerManagersMap controller_managers_;
628 rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
629 std::mutex controller_managers_mutex_;
630
631 rclcpp::Node::SharedPtr node_;
632
633 void initialize(const rclcpp::Node::SharedPtr& node) override
634 {
635 node_ = node;
636 }
641 void discover()
642 {
643 // Skip if last discovery is too new for discovery rate
644 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
645 return;
646
647 controller_managers_stamp_ = node_->now();
648
649 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
650
651 for (const auto& service : services)
652 {
653 const auto& service_name = service.first;
654 std::size_t found = service_name.find("controller_manager/list_controllers");
655 if (found != std::string::npos)
656 {
657 std::string ns = service_name.substr(0, found);
658 if (controller_managers_.find(ns) == controller_managers_.end())
659 { // create Ros2ControlManager if it does not exist
660 RCLCPP_INFO_STREAM(getLogger(), "Adding controller_manager interface for node at namespace " << ns);
661 auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
662 controller_manager->initialize(node_);
663 controller_managers_.insert(std::make_pair(ns, controller_manager));
664 }
665 }
666 }
667 }
668
674 static std::string getNamespace(const std::string& name)
675 {
676 size_t pos = name.find('/', 1);
677 if (pos == std::string::npos)
678 pos = 0;
679 return name.substr(0, pos + 1);
680 }
681
682public:
688 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
689 {
690 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
691
692 std::string ns = getNamespace(name);
693 ControllerManagersMap::iterator it = controller_managers_.find(ns);
694 if (it != controller_managers_.end())
695 {
696 return it->second->getControllerHandle(name);
697 }
698 return moveit_controller_manager::MoveItControllerHandlePtr();
699 }
700
705 void getControllersList(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->getControllersList(names);
714 }
715 }
716
721 void getActiveControllers(std::vector<std::string>& names) override
722 {
723 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
724 discover();
725
726 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
727 controller_managers_)
728 {
729 controller_manager.second->getActiveControllers(names);
730 }
731 }
732
738 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
739 {
740 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
741
742 std::string ns = getNamespace(name);
743 ControllerManagersMap::iterator it = controller_managers_.find(ns);
744 if (it != controller_managers_.end())
745 {
746 it->second->getControllerJoints(name, joints);
747 }
748 }
749
755 ControllerState getControllerState(const std::string& name) override
756 {
757 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
758
759 std::string ns = getNamespace(name);
760 ControllerManagersMap::iterator it = controller_managers_.find(ns);
761 if (it != controller_managers_.end())
762 {
763 return it->second->getControllerState(name);
764 }
765 return ControllerState();
766 }
767
774 bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
775 {
776 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
777
778 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
779 controller_managers_)
780 {
781 if (!controller_manager.second->switchControllers(activate, deactivate))
782 return false;
783 }
784 return true;
785 }
786};
787
788} // namespace moveit_ros_control_interface
789
792
#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...