-
Notifications
You must be signed in to change notification settings - Fork 299
/
controller_manager.cpp
2564 lines (2316 loc) · 98.5 KB
/
controller_manager.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright 2020 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "controller_manager/controller_manager.hpp"
#include <list>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "controller_interface/controller_interface_base.hpp"
#include "controller_manager_msgs/msg/hardware_component_state.hpp"
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/state.hpp"
namespace // utility
{
static constexpr const char * kControllerInterfaceNamespace = "controller_interface";
static constexpr const char * kControllerInterfaceClassName =
"controller_interface::ControllerInterface";
static constexpr const char * kChainableControllerInterfaceClassName =
"controller_interface::ChainableControllerInterface";
// Changed services history QoS to keep all so we don't lose any client service calls
// \note The versions conditioning is added here to support the source-compatibility with Humble
#if RCLCPP_VERSION_MAJOR >= 17
rclcpp::QoS qos_services =
rclcpp::QoS(rclcpp::QoSInitialization(RMW_QOS_POLICY_HISTORY_KEEP_ALL, 1))
.reliable()
.durability_volatile();
#else
static const rmw_qos_profile_t qos_services = {
RMW_QOS_POLICY_HISTORY_KEEP_ALL,
1, // message queue depth
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false};
#endif
inline bool is_controller_inactive(const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE;
}
inline bool is_controller_inactive(
const controller_interface::ControllerInterfaceBaseSharedPtr & controller)
{
return is_controller_inactive(*controller);
}
inline bool is_controller_active(const controller_interface::ControllerInterfaceBase & controller)
{
return controller.get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE;
}
inline bool is_controller_active(
const controller_interface::ControllerInterfaceBaseSharedPtr & controller)
{
return is_controller_active(*controller);
}
bool controller_name_compare(const controller_manager::ControllerSpec & a, const std::string & name)
{
return a.info.name == name;
}
/// Checks if a command interface belongs to a controller based on its prefix.
/**
* A command interface can be provided by a controller in which case is called "reference"
* interface.
* This means that the @interface_name starts with the name of a controller.
*
* \param[in] interface_name to be found in the map.
* \param[in] controllers list of controllers to compare their names to interface's prefix.
* \param[out] following_controller_it iterator to the following controller that reference interface
* @interface_name belongs to.
* \return true if interface has a controller name as prefix, false otherwise.
*/
bool command_interface_is_reference_interface_of_controller(
const std::string interface_name,
const std::vector<controller_manager::ControllerSpec> & controllers,
controller_manager::ControllersListIterator & following_controller_it)
{
auto split_pos = interface_name.find_first_of('/');
if (split_pos == std::string::npos) // '/' exist in the string (should be always false)
{
RCLCPP_FATAL(
rclcpp::get_logger("ControllerManager::utils"),
"Character '/', was not find in the interface name '%s'. This should never happen. "
"Stop the controller manager immediately and restart it.",
interface_name.c_str());
throw std::runtime_error("Mismatched interface name. See the FATAL message above.");
}
auto interface_prefix = interface_name.substr(0, split_pos);
following_controller_it = std::find_if(
controllers.begin(), controllers.end(),
std::bind(controller_name_compare, std::placeholders::_1, interface_prefix));
RCLCPP_DEBUG(
rclcpp::get_logger("ControllerManager::utils"),
"Deduced interface prefix '%s' - searching for the controller with the same name.",
interface_prefix.c_str());
if (following_controller_it == controllers.end())
{
RCLCPP_DEBUG(
rclcpp::get_logger("ControllerManager::utils"),
"Required command interface '%s' with prefix '%s' is not reference interface.",
interface_name.c_str(), interface_prefix.c_str());
return false;
}
return true;
}
template <typename T>
void add_element_to_list(std::vector<T> & list, const T & element)
{
if (std::find(list.begin(), list.end(), element) == list.end())
{
// Only add to the list if it doesn't exist
list.push_back(element);
}
}
template <typename T>
void remove_element_from_list(std::vector<T> & list, const T & element)
{
auto itr = std::find(list.begin(), list.end(), element);
if (itr != list.end())
{
list.erase(itr);
}
}
void controller_chain_spec_cleanup(
std::unordered_map<std::string, controller_manager::ControllerChainSpec> & ctrl_chain_spec,
const std::string & controller)
{
const auto following_controllers = ctrl_chain_spec[controller].following_controllers;
const auto preceding_controllers = ctrl_chain_spec[controller].preceding_controllers;
for (const auto & flwg_ctrl : following_controllers)
{
remove_element_from_list(ctrl_chain_spec[flwg_ctrl].preceding_controllers, controller);
}
for (const auto & preced_ctrl : preceding_controllers)
{
remove_element_from_list(ctrl_chain_spec[preced_ctrl].following_controllers, controller);
}
ctrl_chain_spec.erase(controller);
}
} // namespace
namespace controller_manager
{
rclcpp::NodeOptions get_cm_node_options()
{
rclcpp::NodeOptions node_options;
// Required for getting types of controllers to be loaded via service call
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);
return node_options;
}
ControllerManager::ControllerManager(
std::shared_ptr<rclcpp::Executor> executor, const std::string & manager_node_name,
const std::string & node_namespace, const rclcpp::NodeOptions & options)
: rclcpp::Node(manager_node_name, node_namespace, options),
resource_manager_(std::make_unique<hardware_interface::ResourceManager>(
update_rate_, this->get_node_clock_interface())),
diagnostics_updater_(this),
executor_(executor),
loader_(std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
chainable_loader_(
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
{
if (!get_parameter("update_rate", update_rate_))
{
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
}
robot_description_ = "";
// TODO(destogl): remove support at the end of 2023
get_parameter("robot_description", robot_description_);
if (robot_description_.empty())
{
subscribe_to_robot_description_topic();
}
else
{
RCLCPP_WARN(
get_logger(),
"[Deprecated] Passing the robot description parameter directly to the control_manager node "
"is deprecated. Use the 'robot_description' topic from 'robot_state_publisher' instead.");
init_resource_manager(robot_description_);
init_services();
}
diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
}
ControllerManager::ControllerManager(
std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
std::shared_ptr<rclcpp::Executor> executor, const std::string & manager_node_name,
const std::string & node_namespace, const rclcpp::NodeOptions & options)
: rclcpp::Node(manager_node_name, node_namespace, options),
resource_manager_(std::move(resource_manager)),
diagnostics_updater_(this),
executor_(executor),
loader_(std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
chainable_loader_(
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
{
if (!get_parameter("update_rate", update_rate_))
{
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
}
if (resource_manager_->is_urdf_already_loaded())
{
init_services();
}
subscribe_to_robot_description_topic();
diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
}
void ControllerManager::subscribe_to_robot_description_topic()
{
// set QoS to transient local to get messages that have already been published
// (if robot state publisher starts before controller manager)
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
"robot_description", rclcpp::QoS(1).transient_local(),
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
RCLCPP_INFO(
get_logger(), "Subscribing to '%s' topic for robot description.",
robot_description_subscription_->get_topic_name());
}
void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description)
{
RCLCPP_INFO(get_logger(), "Received robot description from topic.");
RCLCPP_DEBUG(
get_logger(), "'Content of robot description file: %s", robot_description.data.c_str());
// TODO(mamueluth): errors should probably be caught since we don't want controller_manager node
// to die if a non valid urdf is passed. However, should maybe be fine tuned.
try
{
robot_description_ = robot_description.data;
if (resource_manager_->is_urdf_already_loaded())
{
RCLCPP_WARN(
get_logger(),
"ResourceManager has already loaded an urdf file. Ignoring attempt to reload a robot "
"description file.");
return;
}
init_resource_manager(robot_description_);
init_services();
}
catch (std::runtime_error & e)
{
RCLCPP_ERROR_STREAM(
get_logger(),
"The published robot description file (urdf) seems not to be genuine. The following error "
"was caught:"
<< e.what());
}
}
void ControllerManager::init_resource_manager(const std::string & robot_description)
{
// TODO(destogl): manage this when there is an error - CM should not die because URDF is wrong...
resource_manager_->load_urdf(robot_description);
// Get all components and if they are not defined in parameters activate them automatically
auto components_to_activate = resource_manager_->get_components_status();
using lifecycle_msgs::msg::State;
auto set_components_to_state =
[&](const std::string & parameter_name, rclcpp_lifecycle::State state)
{
std::vector<std::string> components_to_set = std::vector<std::string>({});
if (get_parameter(parameter_name, components_to_set))
{
for (const auto & component : components_to_set)
{
if (component.empty())
{
continue;
}
if (components_to_activate.find(component) == components_to_activate.end())
{
RCLCPP_WARN(
get_logger(), "Hardware component '%s' is unknown, therefore not set in '%s' state.",
component.c_str(), state.label().c_str());
}
else
{
RCLCPP_INFO(
get_logger(), "Setting component '%s' to '%s' state.", component.c_str(),
state.label().c_str());
resource_manager_->set_component_state(component, state);
components_to_activate.erase(component);
}
}
}
};
// unconfigured (loaded only)
set_components_to_state(
"hardware_components_initial_state.unconfigured",
rclcpp_lifecycle::State(
State::PRIMARY_STATE_UNCONFIGURED, hardware_interface::lifecycle_state_names::UNCONFIGURED));
// inactive (configured)
set_components_to_state(
"hardware_components_initial_state.inactive",
rclcpp_lifecycle::State(
State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE));
// activate all other components
for (const auto & [component, state] : components_to_activate)
{
rclcpp_lifecycle::State active_state(
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
resource_manager_->set_component_state(component, active_state);
}
}
void ControllerManager::init_services()
{
// TODO(anyone): Due to issues with the MutliThreadedExecutor, this control loop does not rely on
// the executor (see issue #260).
// deterministic_callback_group_ = create_callback_group(
// rclcpp::CallbackGroupType::MutuallyExclusive);
best_effort_callback_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
using namespace std::placeholders;
list_controllers_service_ = create_service<controller_manager_msgs::srv::ListControllers>(
"~/list_controllers", std::bind(&ControllerManager::list_controllers_srv_cb, this, _1, _2),
qos_services, best_effort_callback_group_);
list_controller_types_service_ =
create_service<controller_manager_msgs::srv::ListControllerTypes>(
"~/list_controller_types",
std::bind(&ControllerManager::list_controller_types_srv_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
load_controller_service_ = create_service<controller_manager_msgs::srv::LoadController>(
"~/load_controller", std::bind(&ControllerManager::load_controller_service_cb, this, _1, _2),
qos_services, best_effort_callback_group_);
configure_controller_service_ = create_service<controller_manager_msgs::srv::ConfigureController>(
"~/configure_controller",
std::bind(&ControllerManager::configure_controller_service_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
reload_controller_libraries_service_ =
create_service<controller_manager_msgs::srv::ReloadControllerLibraries>(
"~/reload_controller_libraries",
std::bind(&ControllerManager::reload_controller_libraries_service_cb, this, _1, _2),
qos_services, best_effort_callback_group_);
switch_controller_service_ = create_service<controller_manager_msgs::srv::SwitchController>(
"~/switch_controller",
std::bind(&ControllerManager::switch_controller_service_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
unload_controller_service_ = create_service<controller_manager_msgs::srv::UnloadController>(
"~/unload_controller",
std::bind(&ControllerManager::unload_controller_service_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
list_hardware_components_service_ =
create_service<controller_manager_msgs::srv::ListHardwareComponents>(
"~/list_hardware_components",
std::bind(&ControllerManager::list_hardware_components_srv_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
list_hardware_interfaces_service_ =
create_service<controller_manager_msgs::srv::ListHardwareInterfaces>(
"~/list_hardware_interfaces",
std::bind(&ControllerManager::list_hardware_interfaces_srv_cb, this, _1, _2), qos_services,
best_effort_callback_group_);
set_hardware_component_state_service_ =
create_service<controller_manager_msgs::srv::SetHardwareComponentState>(
"~/set_hardware_component_state",
std::bind(&ControllerManager::set_hardware_component_state_srv_cb, this, _1, _2),
qos_services, best_effort_callback_group_);
}
controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_controller(
const std::string & controller_name, const std::string & controller_type)
{
RCLCPP_INFO(get_logger(), "Loading controller '%s'", controller_name.c_str());
if (
!loader_->isClassAvailable(controller_type) &&
!chainable_loader_->isClassAvailable(controller_type))
{
RCLCPP_ERROR(
get_logger(), "Loader for controller '%s' (type '%s') not found.", controller_name.c_str(),
controller_type.c_str());
RCLCPP_INFO(get_logger(), "Available classes:");
for (const auto & available_class : loader_->getDeclaredClasses())
{
RCLCPP_INFO(get_logger(), " %s", available_class.c_str());
}
for (const auto & available_class : chainable_loader_->getDeclaredClasses())
{
RCLCPP_INFO(get_logger(), " %s", available_class.c_str());
}
return nullptr;
}
RCLCPP_DEBUG(get_logger(), "Loader for controller '%s' found.", controller_name.c_str());
controller_interface::ControllerInterfaceBaseSharedPtr controller;
try
{
if (loader_->isClassAvailable(controller_type))
{
controller = loader_->createSharedInstance(controller_type);
}
if (chainable_loader_->isClassAvailable(controller_type))
{
controller = chainable_loader_->createSharedInstance(controller_type);
}
}
catch (const pluginlib::CreateClassException & e)
{
RCLCPP_ERROR(
get_logger(), "Error happened during creation of controller '%s' with type '%s':\n%s",
controller_name.c_str(), controller_type.c_str(), e.what());
return nullptr;
}
ControllerSpec controller_spec;
controller_spec.c = controller;
controller_spec.info.name = controller_name;
controller_spec.info.type = controller_type;
controller_spec.next_update_cycle_time = std::make_shared<rclcpp::Time>(
0, 0, this->get_node_clock_interface()->get_clock()->get_clock_type());
// We have to fetch the parameters_file at the time of loading the controller, because this way we
// can load them at the creation of the LifeCycleNode and this helps in using the features such as
// read_only params, dynamic maps lists etc
// Now check if the parameters_file parameter exist
const std::string param_name = controller_name + ".params_file";
std::string parameters_file;
// Check if parameter has been declared
if (!has_parameter(param_name))
{
declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_STRING);
}
if (get_parameter(param_name, parameters_file) && !parameters_file.empty())
{
controller_spec.info.parameters_file = parameters_file;
}
return add_controller_impl(controller_spec);
}
controller_interface::ControllerInterfaceBaseSharedPtr ControllerManager::load_controller(
const std::string & controller_name)
{
const std::string param_name = controller_name + ".type";
std::string controller_type;
// We cannot declare the parameters for the controllers that will be loaded in the future,
// because they are plugins and we cannot be aware of all of them.
// So when we're told to load a controller by name, we need to declare the parameter if
// we haven't done so, and then read it.
// Check if parameter has been declared
if (!has_parameter(param_name))
{
declare_parameter(param_name, rclcpp::ParameterType::PARAMETER_STRING);
}
if (!get_parameter(param_name, controller_type))
{
RCLCPP_ERROR(
get_logger(), "The 'type' param was not defined for '%s'.", controller_name.c_str());
return nullptr;
}
return load_controller(controller_name, controller_type);
}
controller_interface::return_type ControllerManager::unload_controller(
const std::string & controller_name)
{
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
std::vector<ControllerSpec> & to = rt_controllers_wrapper_.get_unused_list(guard);
const std::vector<ControllerSpec> & from = rt_controllers_wrapper_.get_updated_list(guard);
// Transfers the active controllers over, skipping the one to be removed and the active ones.
to = from;
auto found_it = std::find_if(
to.begin(), to.end(),
std::bind(controller_name_compare, std::placeholders::_1, controller_name));
if (found_it == to.end())
{
// Fails if we could not remove the controllers
to.clear();
RCLCPP_ERROR(
get_logger(),
"Could not unload controller with name '%s' because no controller with this name exists",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
auto & controller = *found_it;
if (is_controller_active(*controller.c))
{
to.clear();
RCLCPP_ERROR(
get_logger(), "Could not unload controller with name '%s' because it is still active",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
if (controller.c->is_async())
{
RCLCPP_DEBUG(
get_logger(), "Removing controller '%s' from the list of async controllers",
controller_name.c_str());
async_controller_threads_.erase(controller_name);
}
RCLCPP_DEBUG(get_logger(), "Cleanup controller");
controller_chain_spec_cleanup(controller_chain_spec_, controller_name);
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
if (is_controller_inactive(*controller.c))
{
RCLCPP_DEBUG(
get_logger(), "Controller '%s' is cleaned-up before unloading!", controller_name.c_str());
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
const auto new_state = controller.c->get_node()->cleanup();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
RCLCPP_WARN(
get_logger(), "Failed to clean-up the controller '%s' before unloading!",
controller_name.c_str());
}
}
executor_->remove_node(controller.c->get_node()->get_node_base_interface());
to.erase(found_it);
// Destroys the old controllers list when the realtime thread is finished with it.
RCLCPP_DEBUG(get_logger(), "Realtime switches over to new controller list");
rt_controllers_wrapper_.switch_updated_list(guard);
std::vector<ControllerSpec> & new_unused_list = rt_controllers_wrapper_.get_unused_list(guard);
RCLCPP_DEBUG(get_logger(), "Destruct controller");
new_unused_list.clear();
RCLCPP_DEBUG(get_logger(), "Destruct controller finished");
RCLCPP_DEBUG(get_logger(), "Successfully unloaded controller '%s'", controller_name.c_str());
return controller_interface::return_type::OK;
}
std::vector<ControllerSpec> ControllerManager::get_loaded_controllers() const
{
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
return rt_controllers_wrapper_.get_updated_list(guard);
}
controller_interface::return_type ControllerManager::configure_controller(
const std::string & controller_name)
{
RCLCPP_INFO(get_logger(), "Configuring controller '%s'", controller_name.c_str());
const auto & controllers = get_loaded_controllers();
auto found_it = std::find_if(
controllers.begin(), controllers.end(),
std::bind(controller_name_compare, std::placeholders::_1, controller_name));
if (found_it == controllers.end())
{
RCLCPP_ERROR(
get_logger(),
"Could not configure controller with name '%s' because no controller with this name exists",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
auto controller = found_it->c;
auto state = controller->get_state();
if (
state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE ||
state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED)
{
RCLCPP_ERROR(
get_logger(), "Controller '%s' can not be configured from '%s' state.",
controller_name.c_str(), state.label().c_str());
return controller_interface::return_type::ERROR;
}
auto new_state = controller->get_state();
if (state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
RCLCPP_DEBUG(
get_logger(), "Controller '%s' is cleaned-up before configuring", controller_name.c_str());
// TODO(destogl): remove reference interface if chainable; i.e., add a separate method for
// cleaning-up controllers?
new_state = controller->get_node()->cleanup();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
{
RCLCPP_ERROR(
get_logger(), "Controller '%s' can not be cleaned-up before configuring",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
}
new_state = controller->configure();
if (new_state.id() != lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE)
{
RCLCPP_ERROR(
get_logger(), "After configuring, controller '%s' is in state '%s' , expected inactive.",
controller_name.c_str(), new_state.label().c_str());
return controller_interface::return_type::ERROR;
}
// ASYNCHRONOUS CONTROLLERS: Start background thread for update
if (controller->is_async())
{
async_controller_threads_.emplace(
controller_name, std::make_unique<ControllerThreadWrapper>(controller, update_rate_));
}
const auto controller_update_rate = controller->get_update_rate();
const auto cm_update_rate = get_update_rate();
if (controller_update_rate > cm_update_rate)
{
RCLCPP_WARN(
get_logger(),
"The controller : %s update rate : %d Hz should be less than or equal to controller "
"manager's update rate : %d Hz!. The controller will be updated at controller_manager's "
"update rate.",
controller_name.c_str(), controller_update_rate, cm_update_rate);
}
else if (cm_update_rate % controller_update_rate != 0)
{
RCLCPP_WARN(
get_logger(),
"The controller : %s update cycles won't be triggered at a constant period : %f sec, as the "
"controller's update rate : %d Hz is not a perfect divisor of the controller manager's "
"update rate : %d Hz!.",
controller_name.c_str(), 1.0 / controller_update_rate, controller_update_rate,
cm_update_rate);
}
// CHAINABLE CONTROLLERS: get reference interfaces from chainable controllers
if (controller->is_chainable())
{
RCLCPP_DEBUG(
get_logger(),
"Controller '%s' is chainable. Interfaces are being exported to resource manager.",
controller_name.c_str());
auto interfaces = controller->export_reference_interfaces();
if (interfaces.empty())
{
// TODO(destogl): Add test for this!
RCLCPP_ERROR(
get_logger(), "Controller '%s' is chainable, but does not export any reference interfaces.",
controller_name.c_str());
return controller_interface::return_type::ERROR;
}
resource_manager_->import_controller_reference_interfaces(controller_name, interfaces);
}
// let's update the list of following and preceding controllers
const auto cmd_itfs = controller->command_interface_configuration().names;
const auto state_itfs = controller->state_interface_configuration().names;
for (const auto & cmd_itf : cmd_itfs)
{
controller_manager::ControllersListIterator ctrl_it;
if (command_interface_is_reference_interface_of_controller(cmd_itf, controllers, ctrl_it))
{
add_element_to_list(
controller_chain_spec_[controller_name].following_controllers, ctrl_it->info.name);
add_element_to_list(
controller_chain_spec_[ctrl_it->info.name].preceding_controllers, controller_name);
}
}
// This is needed when we start exporting the state interfaces from the controllers
for (const auto & state_itf : state_itfs)
{
controller_manager::ControllersListIterator ctrl_it;
if (command_interface_is_reference_interface_of_controller(state_itf, controllers, ctrl_it))
{
add_element_to_list(
controller_chain_spec_[controller_name].preceding_controllers, ctrl_it->info.name);
add_element_to_list(
controller_chain_spec_[ctrl_it->info.name].following_controllers, controller_name);
}
}
// Now let's reorder the controllers
// lock controllers
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
std::vector<ControllerSpec> & to = rt_controllers_wrapper_.get_unused_list(guard);
const std::vector<ControllerSpec> & from = rt_controllers_wrapper_.get_updated_list(guard);
// Copy all controllers from the 'from' list to the 'to' list
to = from;
std::vector<ControllerSpec> sorted_list;
// clear the list before reordering it again
ordered_controllers_names_.clear();
for (const auto & [ctrl_name, chain_spec] : controller_chain_spec_)
{
auto it =
std::find(ordered_controllers_names_.begin(), ordered_controllers_names_.end(), ctrl_name);
if (it == ordered_controllers_names_.end())
{
update_list_with_controller_chain(ctrl_name, ordered_controllers_names_.end(), false);
}
}
std::vector<ControllerSpec> new_list;
for (const auto & ctrl : ordered_controllers_names_)
{
auto controller_it = std::find_if(
to.begin(), to.end(), std::bind(controller_name_compare, std::placeholders::_1, ctrl));
if (controller_it != to.end())
{
new_list.push_back(*controller_it);
}
}
to = new_list;
RCLCPP_DEBUG(get_logger(), "Reordered controllers list is:");
for (const auto & ctrl : to)
{
RCLCPP_DEBUG(this->get_logger(), "\t%s", ctrl.info.name.c_str());
}
// switch lists
rt_controllers_wrapper_.switch_updated_list(guard);
// clear unused list
rt_controllers_wrapper_.get_unused_list(guard).clear();
return controller_interface::return_type::OK;
}
void ControllerManager::clear_requests()
{
deactivate_request_.clear();
activate_request_.clear();
// Set these interfaces as unavailable when clearing requests to avoid leaving them in available
// state without the controller being in active state
for (const auto & controller_name : to_chained_mode_request_)
{
resource_manager_->make_controller_reference_interfaces_unavailable(controller_name);
}
to_chained_mode_request_.clear();
from_chained_mode_request_.clear();
activate_command_interface_request_.clear();
deactivate_command_interface_request_.clear();
}
controller_interface::return_type ControllerManager::switch_controller(
const std::vector<std::string> & activate_controllers,
const std::vector<std::string> & deactivate_controllers, int strictness, bool activate_asap,
const rclcpp::Duration & timeout)
{
switch_params_ = SwitchParams();
if (!deactivate_request_.empty() || !activate_request_.empty())
{
RCLCPP_FATAL(
get_logger(),
"The internal deactivate and activate request lists are not empty at the beginning of the "
"switch_controller() call. This should never happen.");
throw std::runtime_error("CM's internal state is not correct. See the FATAL message above.");
}
if (
!deactivate_command_interface_request_.empty() || !activate_command_interface_request_.empty())
{
RCLCPP_FATAL(
get_logger(),
"The internal deactivate and activat requests command interface lists are not empty at the "
"switch_controller() call. This should never happen.");
throw std::runtime_error("CM's internal state is not correct. See the FATAL message above.");
}
if (!from_chained_mode_request_.empty() || !to_chained_mode_request_.empty())
{
RCLCPP_FATAL(
get_logger(),
"The internal 'from' and 'to' chained mode requests are not empty at the "
"switch_controller() call. This should never happen.");
throw std::runtime_error("CM's internal state is not correct. See the FATAL message above.");
}
if (strictness == 0)
{
RCLCPP_WARN(
get_logger(),
"Controller Manager: to switch controllers you need to specify a "
"strictness level of controller_manager_msgs::SwitchController::STRICT "
"(%d) or ::BEST_EFFORT (%d). Defaulting to ::BEST_EFFORT",
controller_manager_msgs::srv::SwitchController::Request::STRICT,
controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT);
strictness = controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT;
}
RCLCPP_DEBUG(get_logger(), "Activating controllers:");
for (const auto & controller : activate_controllers)
{
RCLCPP_DEBUG(get_logger(), " - %s", controller.c_str());
}
RCLCPP_DEBUG(get_logger(), "Deactivating controllers:");
for (const auto & controller : deactivate_controllers)
{
RCLCPP_DEBUG(get_logger(), " - %s", controller.c_str());
}
const auto list_controllers = [this, strictness](
const std::vector<std::string> & controller_list,
std::vector<std::string> & request_list,
const std::string & action)
{
// lock controllers
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
// list all controllers to (de)activate
for (const auto & controller : controller_list)
{
const auto & updated_controllers = rt_controllers_wrapper_.get_updated_list(guard);
auto found_it = std::find_if(
updated_controllers.begin(), updated_controllers.end(),
std::bind(controller_name_compare, std::placeholders::_1, controller));
if (found_it == updated_controllers.end())
{
RCLCPP_WARN(
get_logger(),
"Could not '%s' controller with name '%s' because no controller with this name exists",
action.c_str(), controller.c_str());
if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT)
{
RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! ('STRICT' switch)");
return controller_interface::return_type::ERROR;
}
}
else
{
RCLCPP_DEBUG(
get_logger(), "Found controller '%s' that needs to be %sed in list of controllers",
controller.c_str(), action.c_str());
request_list.push_back(controller);
}
}
RCLCPP_DEBUG(
get_logger(), "'%s' request vector has size %i", action.c_str(), (int)request_list.size());
return controller_interface::return_type::OK;
};
// list all controllers to deactivate (check if all controllers exist)
auto ret = list_controllers(deactivate_controllers, deactivate_request_, "deactivate");
if (ret != controller_interface::return_type::OK)
{
deactivate_request_.clear();
return ret;
}
// list all controllers to activate (check if all controllers exist)
ret = list_controllers(activate_controllers, activate_request_, "activate");
if (ret != controller_interface::return_type::OK)
{
deactivate_request_.clear();
activate_request_.clear();
return ret;
}
// lock controllers
std::lock_guard<std::recursive_mutex> guard(rt_controllers_wrapper_.controllers_lock_);
const std::vector<ControllerSpec> & controllers = rt_controllers_wrapper_.get_updated_list(guard);
// if a preceding controller is deactivated, all first-level controllers should be switched 'from'
// chained mode
propagate_deactivation_of_chained_mode(controllers);
// check if controllers should be switched 'to' chained mode when controllers are activated
for (auto ctrl_it = activate_request_.begin(); ctrl_it != activate_request_.end(); ++ctrl_it)
{
auto controller_it = std::find_if(
controllers.begin(), controllers.end(),
std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it));
controller_interface::return_type status = controller_interface::return_type::OK;
// if controller is not inactive then do not do any following-controllers checks
if (!is_controller_inactive(controller_it->c))
{
RCLCPP_WARN(
get_logger(),
"Controller with name '%s' is not inactive so its following "
"controllers do not have to be checked, because it cannot be activated.",
controller_it->info.name.c_str());
status = controller_interface::return_type::ERROR;
}
else
{
status = check_following_controllers_for_activate(controllers, strictness, controller_it);
}
if (status != controller_interface::return_type::OK)
{
RCLCPP_WARN(
get_logger(),
"Could not activate controller with name '%s'. Check above warnings for more details. "
"Check the state of the controllers and their required interfaces using "
"`ros2 control list_controllers -v` CLI to get more information.",
(*ctrl_it).c_str());
if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT)
{
// TODO(destogl): automatic manipulation of the chain:
// || strictness ==
// controller_manager_msgs::srv::SwitchController::Request::MANIPULATE_CONTROLLERS_CHAIN);
// remove controller that can not be activated from the activation request and step-back
// iterator to correctly step to the next element in the list in the loop
activate_request_.erase(ctrl_it);
--ctrl_it;
}
if (strictness == controller_manager_msgs::srv::SwitchController::Request::STRICT)
{
RCLCPP_ERROR(get_logger(), "Aborting, no controller is switched! (::STRICT switch)");
// reset all lists
clear_requests();
return controller_interface::return_type::ERROR;
}
}
}
// check if controllers should be deactivated if used in chained mode
for (auto ctrl_it = deactivate_request_.begin(); ctrl_it != deactivate_request_.end(); ++ctrl_it)
{
auto controller_it = std::find_if(
controllers.begin(), controllers.end(),
std::bind(controller_name_compare, std::placeholders::_1, *ctrl_it));
controller_interface::return_type status = controller_interface::return_type::OK;
// if controller is not active then skip preceding-controllers checks
if (!is_controller_active(controller_it->c))
{
RCLCPP_WARN(
get_logger(), "Controller with name '%s' can not be deactivated since it is not active.",
controller_it->info.name.c_str());
status = controller_interface::return_type::ERROR;
}
else
{
status = check_preceeding_controllers_for_deactivate(controllers, strictness, controller_it);
}
if (status != controller_interface::return_type::OK)
{
RCLCPP_WARN(
get_logger(),
"Could not deactivate controller with name '%s'. Check above warnings for more details. "
"Check the state of the controllers and their required interfaces using "
"`ros2 control list_controllers -v` CLI to get more information.",
(*ctrl_it).c_str());
if (strictness == controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT)
{
// remove controller that can not be activated from the activation request and step-back
// iterator to correctly step to the next element in the list in the loop
deactivate_request_.erase(ctrl_it);
--ctrl_it;