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
86MOVEIT_CLASS_FORWARD(Ros2ControlManager); // Defines Ros2ControlManagerPtr, ConstPtr, WeakPtr... etc
87
95{
96 std::string ns_;
97 pluginlib::ClassLoader<ControllerHandleAllocator> loader_;
98 typedef std::map<std::string, controller_manager_msgs::msg::ControllerState> ControllersMap;
99
101 ControllersMap managed_controllers_;
103 ControllersMap active_controllers_;
104
105 typedef std::map<std::string, ControllerHandleAllocatorPtr> AllocatorsMap;
106 AllocatorsMap allocators_;
107
108 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> HandleMap;
109 HandleMap handles_;
110
111 rclcpp::Time controllers_stamp_{ 0, 0, RCL_ROS_TIME };
112
116 std::mutex controllers_mutex_;
117
118 rclcpp::Node::SharedPtr node_;
119 rclcpp::Client<controller_manager_msgs::srv::ListControllers>::SharedPtr list_controllers_service_;
120 rclcpp::Client<controller_manager_msgs::srv::SwitchController>::SharedPtr switch_controller_service_;
121
122 // Chained controllers have dependencies (other controllers which must be running)
123 std::unordered_map<std::string /* controller name */, std::vector<std::string> /* dependencies */> dependency_map_;
124
130 static bool isActive(const controller_manager_msgs::msg::ControllerState& s)
131 {
132 return s.state == std::string("active");
133 }
134
141 void discover(bool force = false)
142 {
143 // Skip if controller stamp is too new for new discovery, enforce update if force==true
144 if (!force && ((node_->now() - controllers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE))
145 {
146 return;
147 }
148
149 controllers_stamp_ = node_->now();
150
151 auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
152 auto result_future = list_controllers_service_->async_send_request(request);
153 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
154 {
155 RCLCPP_WARN_STREAM(getLogger(), "Failed to read controllers from "
156 << list_controllers_service_->get_service_name() << " within "
157 << SERVICE_CALL_TIMEOUT << " seconds");
158 return;
159 }
160
161 managed_controllers_.clear();
162 active_controllers_.clear();
163
164 auto result = result_future.get();
166 {
167 return;
168 }
169
170 for (const controller_manager_msgs::msg::ControllerState& controller : result->controller)
171 {
172 // If the controller is active, add it to the map of active controllers.
173 if (isActive(controller))
174 {
175 // Get the names of the interfaces currently claimed by the active controller.
176 auto& claimed_interfaces = active_controllers_.insert(std::make_pair(controller.name, controller))
177 .first->second.claimed_interfaces; // without namespace
178 // Modify the claimed interface names in-place to only include the name of the joint and not the command type
179 // (e.g. position, velocity, etc.).
180 std::transform(claimed_interfaces.cbegin(), claimed_interfaces.cend(), claimed_interfaces.begin(),
181 [](const std::string& claimed_interface) {
182 return parseJointNameFromResource(claimed_interface);
183 });
184 }
185
186 // Instantiate a controller handle if one is available for this type of controller.
187 if (loader_.isClassAvailable(controller.type))
188 {
189 std::string absname = getAbsName(controller.name);
190 auto controller_it = managed_controllers_.insert(std::make_pair(absname, controller)).first; // with namespace
191 // Get the names of the interfaces that would be claimed by this currently-inactive controller if it was activated.
192 auto& required_interfaces = controller_it->second.required_command_interfaces;
193 // Modify the required interface names in-place to only include the name of the joint and not the command type
194 // (e.g. position, velocity, etc.).
195 std::transform(required_interfaces.cbegin(), required_interfaces.cend(), required_interfaces.begin(),
196 [](const std::string& required_interface) {
197 return parseJointNameFromResource(required_interface);
198 });
199 allocate(absname, controller_it->second);
200 }
201 }
202 }
203
210 void allocate(const std::string& name, const controller_manager_msgs::msg::ControllerState& controller)
211 {
212 if (handles_.find(name) == handles_.end())
213 {
214 const std::string& type = controller.type;
215 AllocatorsMap::iterator alloc_it = allocators_.find(type);
216 if (alloc_it == allocators_.end())
217 { // create allocator if needed
218 alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
219 }
220
221 std::vector<std::string> resources;
222 // Collect claimed resources across different hardware interfaces
223 for (const auto& resource : controller.claimed_interfaces)
224 {
225 resources.push_back(parseJointNameFromResource(resource));
226 }
227
228 moveit_controller_manager::MoveItControllerHandlePtr handle =
229 alloc_it->second->alloc(node_, name, resources); // allocate handle
230 if (handle)
231 handles_.insert(std::make_pair(name, handle));
232 }
233 }
234
240 std::string getAbsName(const std::string& name)
241 {
242 return rclcpp::names::append(ns_, name);
243 }
244
245public:
250 : loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
251 {
252 }
253
258 Ros2ControlManager(const std::string& ns)
259 : ns_(ns), loader_("moveit_ros_control_interface", "moveit_ros_control_interface::ControllerHandleAllocator")
260 {
261 RCLCPP_INFO_STREAM(getLogger(), "Started moveit_ros_control_interface::Ros2ControlManager for namespace " << ns_);
262 }
263
264 void initialize(const rclcpp::Node::SharedPtr& node) override
265 {
266 node_ = node;
267 if (!ns_.empty())
268 {
269 if (!node_->has_parameter("ros_control_namespace"))
270 {
271 ns_ = node_->declare_parameter<std::string>("ros_control_namespace", "/");
272 }
273 else
274 {
275 node_->get_parameter<std::string>("ros_control_namespace", ns_);
276 }
277 }
278 else if (node->has_parameter("ros_control_namespace"))
279 {
280 node_->get_parameter<std::string>("ros_control_namespace", ns_);
281 RCLCPP_INFO_STREAM(getLogger(), "Namespace for controller manager was specified, namespace: " << ns_);
282 }
283
284 list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
285 getAbsName("controller_manager/list_controllers"));
286 switch_controller_service_ = node_->create_client<controller_manager_msgs::srv::SwitchController>(
287 getAbsName("controller_manager/switch_controller"));
288
289 std::scoped_lock<std::mutex> lock(controllers_mutex_);
290 discover(true);
291 }
297 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
298 {
299 std::scoped_lock<std::mutex> lock(controllers_mutex_);
300 HandleMap::iterator it = handles_.find(name);
301 if (it != handles_.end())
302 { // controller is manager by this interface
303 return it->second;
304 }
305 return moveit_controller_manager::MoveItControllerHandlePtr();
306 }
307
312 void getControllersList(std::vector<std::string>& names) override
313 {
314 std::scoped_lock<std::mutex> lock(controllers_mutex_);
315 discover();
316
317 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
318 managed_controllers_)
319 {
320 names.push_back(managed_controller.first);
321 }
322 }
323
328 void getActiveControllers(std::vector<std::string>& names) override
329 {
330 std::scoped_lock<std::mutex> lock(controllers_mutex_);
331 discover();
332
333 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& managed_controller :
334 managed_controllers_)
335 {
336 if (isActive(managed_controller.second))
337 names.push_back(managed_controller.first);
338 }
339 }
340
346 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
347 {
348 std::scoped_lock<std::mutex> lock(controllers_mutex_);
349 ControllersMap::iterator it = managed_controllers_.find(name);
350 if (it != managed_controllers_.end())
351 {
352 for (const auto& required_resource : it->second.required_command_interfaces)
353 {
354 joints.push_back(required_resource);
355 }
356 }
357 }
358
364 ControllerState getControllerState(const std::string& name) override
365 {
366 std::scoped_lock<std::mutex> lock(controllers_mutex_);
367 discover();
368
370 ControllersMap::iterator it = managed_controllers_.find(name);
371 if (it != managed_controllers_.end())
372 {
373 c.active_ = isActive(it->second);
374 }
375 return c;
376 }
377
385 bool switchControllers(const std::vector<std::string>& activate_base,
386 const std::vector<std::string>& deactivate_base) override
387 {
388 // add controller dependencies
389 std::vector<std::string> activate = activate_base;
390 std::vector<std::string> deactivate = deactivate_base;
391 for (auto controllers : { &activate, &deactivate })
392 {
393 auto queue = *controllers;
394 while (!queue.empty())
395 {
396 auto controller = queue.back();
397 controller.erase(0, 1);
398 queue.pop_back();
399 for (const auto& dependency : dependency_map_[controller])
400 {
401 queue.push_back(dependency);
402 controllers->push_back("/" + dependency);
403 }
404 }
405 }
406 // activation dependencies must be started first, but they are processed last, so the order needs to be flipped
407 std::reverse(activate.begin(), activate.end());
408
409 std::scoped_lock<std::mutex> lock(controllers_mutex_);
410 discover(true);
411
412 // Holds the list of controllers that are currently active and their resources
413 // Example:
414 // controller1:
415 // - controller1_joint1
416 // - controller1_joint2
417 // ...
418 // controller2:
419 // - controller2_joint1
420 // - controller2_joint2
421 // ...
422 // ...
423 // The left type have to be an unordered_multiset_of, because each controller can claim multiple resources
424 // {{ "controller1", "controller1_joint1" },
425 // { "controller1", "controller1_joint2" },
426 // ...,
427 // { "controller2", "controller2_joint1" },
428 // { "controller2", "controller2_joint2" },
429 // ...}
430 typedef boost::bimap<boost::bimaps::unordered_multiset_of<std::string>, std::string> resources_bimap;
431
432 resources_bimap claimed_resources;
433
434 // fill bimap with active controllers and their resources
435 for (std::pair<const std::string, controller_manager_msgs::msg::ControllerState>& active_controller :
436 active_controllers_)
437 {
438 for (const auto& resource : active_controller.second.claimed_interfaces)
439 {
440 claimed_resources.insert(resources_bimap::value_type(active_controller.second.name, resource));
441 }
442 }
443
444 auto request = std::make_shared<controller_manager_msgs::srv::SwitchController::Request>();
445 for (const std::string& it : deactivate)
446 {
447 ControllersMap::iterator c = managed_controllers_.find(it);
448 if (c != managed_controllers_.end())
449 { // controller belongs to this manager
450 request->deactivate_controllers.push_back(c->second.name);
451 claimed_resources.left.erase(c->second.name); // remove resources
452 }
453 }
454
455 // For each controller to activate, find conflicts between the interfaces required by that controller and the
456 // interfaces claimed by currently-active controllers.
457 for (const std::string& it : activate)
458 {
459 ControllersMap::iterator c = managed_controllers_.find(it);
460 if (c != managed_controllers_.end())
461 { // controller belongs to this manager
462 request->activate_controllers.push_back(c->second.name);
463 for (const auto& required_resource : c->second.required_command_interfaces)
464 {
465 resources_bimap::right_const_iterator res = claimed_resources.right.find(required_resource);
466 if (res != claimed_resources.right.end())
467 { // resource is claimed
468 if (std::find(request->deactivate_controllers.begin(), request->deactivate_controllers.end(),
469 res->second) == request->deactivate_controllers.end())
470 {
471 request->deactivate_controllers.push_back(res->second); // add claiming controller to stop list
472 }
473 claimed_resources.left.erase(res->second); // remove claimed resources
474 }
475 }
476 }
477 }
478
479 // Setting level to STRICT means that the controller switch will only be committed if all controllers are
480 // successfully activated or deactivated.
481 request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
482
483 if (!request->activate_controllers.empty() || !request->deactivate_controllers.empty())
484 { // something to switch?
485 auto result_future = switch_controller_service_->async_send_request(request);
486 if (result_future.wait_for(std::chrono::duration<double>(SERVICE_CALL_TIMEOUT)) == std::future_status::timeout)
487 {
488 RCLCPP_ERROR_STREAM(getLogger(), "Couldn't switch controllers at "
489 << switch_controller_service_->get_service_name() << " within "
490 << SERVICE_CALL_TIMEOUT << " seconds");
491 return false;
492 }
493 discover(true);
494 return result_future.get()->ok;
495 }
496 return true;
497 }
503 bool fixChainedControllers(std::shared_ptr<controller_manager_msgs::srv::ListControllers::Response>& result)
504 {
505 std::unordered_map<std::string, size_t> controller_name_map;
506 for (size_t i = 0; i < result->controller.size(); ++i)
507 {
508 controller_name_map[result->controller[i].name] = i;
509 }
510 for (auto& controller : result->controller)
511 {
512 if (controller.chain_connections.size() > 1)
513 {
514 RCLCPP_ERROR_STREAM(getLogger(),
515 "Controller with name %s chains to more than one controller. Chaining to more than "
516 "one controller is not supported.");
517 return false;
518 }
519 dependency_map_[controller.name].clear();
520 for (const auto& chained_controller : controller.chain_connections)
521 {
522 auto ind = controller_name_map[chained_controller.name];
523 dependency_map_[controller.name].push_back(chained_controller.name);
524 controller.required_command_interfaces = result->controller[ind].required_command_interfaces;
525 controller.claimed_interfaces = result->controller[ind].claimed_interfaces;
526 result->controller[ind].claimed_interfaces.clear();
527 result->controller[ind].required_command_interfaces.clear();
528 }
529 }
530
531 return true;
532 }
533};
539{
540 typedef std::map<std::string, moveit_ros_control_interface::Ros2ControlManagerPtr> ControllerManagersMap;
541 ControllerManagersMap controller_managers_;
542 rclcpp::Time controller_managers_stamp_{ 0, 0, RCL_ROS_TIME };
543 std::mutex controller_managers_mutex_;
544
545 rclcpp::Node::SharedPtr node_;
546
547 void initialize(const rclcpp::Node::SharedPtr& node) override
548 {
549 node_ = node;
550 }
555 void discover()
556 {
557 // Skip if last discovery is too new for discovery rate
558 if ((node_->now() - controller_managers_stamp_) < CONTROLLER_INFORMATION_VALIDITY_AGE)
559 return;
560
561 controller_managers_stamp_ = node_->now();
562
563 const std::map<std::string, std::vector<std::string>> services = node_->get_service_names_and_types();
564
565 for (const auto& service : services)
566 {
567 const auto& service_name = service.first;
568 std::size_t found = service_name.find("controller_manager/list_controllers");
569 if (found != std::string::npos)
570 {
571 std::string ns = service_name.substr(0, found);
572 if (controller_managers_.find(ns) == controller_managers_.end())
573 { // create Ros2ControlManager if it does not exist
574 RCLCPP_INFO_STREAM(getLogger(), "Adding controller_manager interface for node at namespace " << ns);
575 auto controller_manager = std::make_shared<moveit_ros_control_interface::Ros2ControlManager>(ns);
576 controller_manager->initialize(node_);
577 controller_managers_.insert(std::make_pair(ns, controller_manager));
578 }
579 }
580 }
581 }
582
588 static std::string getNamespace(const std::string& name)
589 {
590 size_t pos = name.find('/', 1);
591 if (pos == std::string::npos)
592 pos = 0;
593 return name.substr(0, pos + 1);
594 }
595
596public:
602 moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string& name) override
603 {
604 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
605
606 std::string ns = getNamespace(name);
607 ControllerManagersMap::iterator it = controller_managers_.find(ns);
608 if (it != controller_managers_.end())
609 {
610 return it->second->getControllerHandle(name);
611 }
612 return moveit_controller_manager::MoveItControllerHandlePtr();
613 }
614
619 void getControllersList(std::vector<std::string>& names) override
620 {
621 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
622 discover();
623
624 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
625 controller_managers_)
626 {
627 controller_manager.second->getControllersList(names);
628 }
629 }
630
635 void getActiveControllers(std::vector<std::string>& names) override
636 {
637 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
638 discover();
639
640 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
641 controller_managers_)
642 {
643 controller_manager.second->getActiveControllers(names);
644 }
645 }
646
652 void getControllerJoints(const std::string& name, std::vector<std::string>& joints) override
653 {
654 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
655
656 std::string ns = getNamespace(name);
657 ControllerManagersMap::iterator it = controller_managers_.find(ns);
658 if (it != controller_managers_.end())
659 {
660 it->second->getControllerJoints(name, joints);
661 }
662 }
663
669 ControllerState getControllerState(const std::string& name) override
670 {
671 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
672
673 std::string ns = getNamespace(name);
674 ControllerManagersMap::iterator it = controller_managers_.find(ns);
675 if (it != controller_managers_.end())
676 {
677 return it->second->getControllerState(name);
678 }
679 return ControllerState();
680 }
681
688 bool switchControllers(const std::vector<std::string>& activate, const std::vector<std::string>& deactivate) override
689 {
690 std::unique_lock<std::mutex> lock(controller_managers_mutex_);
691
692 for (std::pair<const std::string, moveit_ros_control_interface::Ros2ControlManagerPtr>& controller_manager :
693 controller_managers_)
694 {
695 if (!controller_manager.second->switchControllers(activate, deactivate))
696 return false;
697 }
698 return true;
699 }
700};
701
702} // namespace moveit_ros_control_interface
703
706
#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...
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...