9
9
# * STRICT means that switching will fail if anything goes wrong (an invalid
10
10
# controller name, a controller that failed to activate, etc. )
11
11
# * BEST_EFFORT means that even when something goes wrong with on controller,
12
- # the service will still try to activate/stop the remaining controllers
12
+ # the service will still try to activate/deactivate the remaining controllers
13
+ # * AUTO means that the controller manager will automatically resolve the controller
14
+ # chain in order to activate and/or deactivate the specified controllers.
15
+ # This is useful in complex systems when you want all dependent controllers to start
16
+ # within the same update iteration.
17
+ # * FORCE_AUTO means that the controller manager will take all necessary steps to activate
18
+ # the specified controllers without requiring you to explicitly list the controllers
19
+ # to be deactivated. This is useful when the controller being activated depends on
20
+ # another unknown controller that is currently running. The controller manager will
21
+ # deactivate any controllers that block the activation of the requested controller,
22
+ # following the mutually exclusive joint interface switching principle. For example,
23
+ # to activate a controller that uses a joint's position interface, the controller manager
24
+ # will automatically deactivate any controllers that use conflicting interfaces for
25
+ # the same joint.
13
26
# * activate the controllers as soon as their hardware dependencies are ready, will
14
27
# wait for all interfaces to be ready otherwise
15
28
# * the timeout before aborting pending controllers. Zero for infinite
@@ -25,6 +38,8 @@ string[] deactivate_controllers
25
38
int32 strictness
26
39
int32 BEST_EFFORT=1
27
40
int32 STRICT=2
41
+ int32 AUTO=3
42
+ int32 FORCE_AUTO=4
28
43
bool activate_asap
29
44
builtin_interfaces/Duration timeout
30
45
---
0 commit comments