Skip to content

Commit 45cf718

Browse files
committed
Add validators to the parameters
1 parent ca39a5c commit 45cf718

File tree

1 file changed

+48
-12
lines changed

1 file changed

+48
-12
lines changed

controller_manager/src/controller_manager_parameters.yaml

Lines changed: 48 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -14,68 +14,104 @@ controller_manager:
1414
warn: {
1515
type: double,
1616
default_value: 5.0,
17-
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."
17+
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.",
18+
validation: {
19+
gt<>: 0.0,
20+
}
1821
}
1922
error: {
2023
type: double,
2124
default_value: 10.0,
22-
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."
25+
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.",
26+
validation: {
27+
gt<>: 0.0,
28+
}
2329
}
2430
standard_deviation:
2531
warn: {
2632
type: double,
2733
default_value: 5.0,
28-
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."
34+
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.",
35+
validation: {
36+
gt<>: 0.0,
37+
}
2938
}
3039
error: {
3140
type: double,
3241
default_value: 10.0,
33-
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."
42+
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.",
43+
validation: {
44+
gt<>: 0.0,
45+
}
3446
}
3547
controllers:
3648
periodicity:
3749
mean_error:
3850
warn: {
3951
type: double,
4052
default_value: 5.0,
41-
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."
53+
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.",
54+
validation: {
55+
gt<>: 0.0,
56+
}
4257
}
4358
error: {
4459
type: double,
4560
default_value: 10.0,
46-
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."
61+
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.",
62+
validation: {
63+
gt<>: 0.0,
64+
}
4765
}
4866
standard_deviation:
4967
warn: {
5068
type: double,
5169
default_value: 5.0,
52-
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."
70+
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.",
71+
validation: {
72+
gt<>: 0.0,
73+
}
5374
}
5475
error: {
5576
type: double,
5677
default_value: 10.0,
57-
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."
78+
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.",
79+
validation: {
80+
gt<>: 0.0,
81+
}
5882
}
5983
execution_time:
6084
mean_error:
6185
warn: {
6286
type: double,
6387
default_value: 1000.0,
64-
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"
88+
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",
89+
validation: {
90+
gt<>: 0.0,
91+
}
6592
}
6693
error: {
6794
type: double,
6895
default_value: 2000.0,
69-
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"
96+
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",
97+
validation: {
98+
gt<>: 0.0,
99+
}
70100
}
71101
standard_deviation:
72102
warn: {
73103
type: double,
74104
default_value: 100.0,
75-
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."
105+
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.",
106+
validation: {
107+
gt<>: 0.0,
108+
}
76109
}
77110
error: {
78111
type: double,
79112
default_value: 200.0,
80-
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."
113+
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.",
114+
validation: {
115+
gt<>: 0.0,
116+
}
81117
}

0 commit comments

Comments
 (0)