-
Notifications
You must be signed in to change notification settings - Fork 336
/
Copy pathcontroller_manager_parameters.yaml
145 lines (141 loc) · 7.37 KB
/
controller_manager_parameters.yaml
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
controller_manager:
update_rate: {
type: int,
default_value: 100,
read_only: true,
description: "The frequency of controller manager's real-time update loop. This loop reads states from hardware, updates controllers and writes commands to hardware."
}
hardware_components_initial_state:
not_loaded: {
type: string_array,
default_value: [],
description: "Defines which hardware components should not be loaded activated when controller manager is started. If later used, these hardware components will need to be loaded, configured and activated manually or via a hardware spawner.",
validation: {
unique<>: null,
}
}
unconfigured: {
type: string_array,
default_value: [],
description: "Defines which hardware components will be only loaded when controller manager is started. These hardware components will need to be configured and activated manually or via a hardware spawner.",
validation: {
unique<>: null,
}
}
inactive: {
type: string_array,
default_value: [],
description: "Defines which hardware components will be configured when controller manager is started. These hardware components will need to be activated manually or via a hardware spawner.",
validation: {
unique<>: null,
}
}
diagnostics:
threshold:
controller_manager:
periodicity:
mean_error:
warn: {
type: double,
default_value: 5.0,
description: "The warning threshold for the mean error of the controller manager's periodicity. If the mean error exceeds this threshold, a warning diagnostic will be published.",
validation: {
gt<>: 0.0,
}
}
error: {
type: double,
default_value: 10.0,
description: "The error threshold for the mean error of the controller manager's periodicity. If the mean error exceeds this threshold, an error diagnostic will be published.",
validation: {
gt<>: 0.0,
}
}
standard_deviation:
warn: {
type: double,
default_value: 5.0,
description: "The warning threshold for the standard deviation of the controller manager's periodicity. If the standard deviation exceeds this threshold, a warning diagnostic will be published.",
validation: {
gt<>: 0.0,
}
}
error: {
type: double,
default_value: 10.0,
description: "The error threshold for the standard deviation of the controller manager's periodicity. If the standard deviation exceeds this threshold, an error diagnostic will be published.",
validation: {
gt<>: 0.0,
}
}
controllers:
periodicity:
mean_error:
warn: {
type: double,
default_value: 5.0,
description: "The warning threshold for the mean error of the controller update loop. If the mean error exceeds this threshold, a warning diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.",
validation: {
gt<>: 0.0,
}
}
error: {
type: double,
default_value: 10.0,
description: "The error threshold for the mean error of the controller update loop. If the mean error exceeds this threshold, an error diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.",
validation: {
gt<>: 0.0,
}
}
standard_deviation:
warn: {
type: double,
default_value: 5.0,
description: "The warning threshold for the standard deviation of the controller update loop. If the standard deviation exceeds this threshold, a warning diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.",
validation: {
gt<>: 0.0,
}
}
error: {
type: double,
default_value: 10.0,
description: "The error threshold for the standard deviation of the controller update loop. If the standard deviation exceeds this threshold, an error diagnostic will be published. This diagnostics will be published only for the asynchronous controllers, because any affect to the synchronous controllers will be reflected directly in the controller manager's periodicity.",
validation: {
gt<>: 0.0,
}
}
execution_time:
mean_error:
warn: {
type: double,
default_value: 1000.0,
description: "The warning threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, a warning diagnostic will be published. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle",
validation: {
gt<>: 0.0,
}
}
error: {
type: double,
default_value: 2000.0,
description: "The error threshold for the mean error of the controller's update cycle execution time in microseconds. If the mean error exceeds this threshold, an error diagnostic will be published. The ``mean_error`` for a synchronous controller will be computed against zero, as it should be as low as possible. However, the ``mean_error`` for an asynchronous controller will be computed against the controller's desired update period, as the controller can take a maximum of the desired period cycle to execute it's update cycle",
validation: {
gt<>: 0.0,
}
}
standard_deviation:
warn: {
type: double,
default_value: 100.0,
description: "The warning threshold for the standard deviation of the controller's update cycle execution time. If the standard deviation exceeds this threshold, a warning diagnostic will be published.",
validation: {
gt<>: 0.0,
}
}
error: {
type: double,
default_value: 200.0,
description: "The error threshold for the standard deviation of the controller's update cycle execution time. If the standard deviation exceeds this threshold, an error diagnostic will be published.",
validation: {
gt<>: 0.0,
}
}