Skip to content

Commit 2ce3fe0

Browse files
committed
Add first version of the GPL configuration
1 parent 12efdef commit 2ce3fe0

File tree

4 files changed

+94
-1
lines changed

4 files changed

+94
-1
lines changed

controller_manager/CMakeLists.txt

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1717
realtime_tools
1818
std_msgs
1919
libstatistics_collector
20+
generate_parameter_library
2021
)
2122

2223
find_package(ament_cmake REQUIRED)
@@ -28,6 +29,10 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
2829
find_package(${Dependency} REQUIRED)
2930
endforeach()
3031

32+
generate_parameter_library(controller_manager_parameters
33+
src/controller_manager_parameters.yaml
34+
)
35+
3136
add_library(controller_manager SHARED
3237
src/controller_manager.cpp
3338
)
@@ -36,6 +41,9 @@ target_include_directories(controller_manager PUBLIC
3641
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
3742
$<INSTALL_INTERFACE:include/controller_manager>
3843
)
44+
target_link_libraries(controller_manager PUBLIC
45+
controller_manager_parameters
46+
)
3947
ament_target_dependencies(controller_manager PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
4048

4149
# Causes the visibility macros to use dllexport rather than dllimport,
@@ -234,7 +242,7 @@ install(
234242
DESTINATION include/controller_manager
235243
)
236244
install(
237-
TARGETS controller_manager
245+
TARGETS controller_manager controller_manager_parameters
238246
EXPORT export_controller_manager
239247
RUNTIME DESTINATION bin
240248
LIBRARY DESTINATION lib

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,8 @@
4848
#include "rclcpp/node.hpp"
4949
#include "std_msgs/msg/string.hpp"
5050

51+
#include "controller_manager_parameters.hpp"
52+
5153
namespace controller_manager
5254
{
5355
using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator;
@@ -473,6 +475,7 @@ class ControllerManager : public rclcpp::Node
473475
*/
474476
rclcpp::NodeOptions determine_controller_node_options(const ControllerSpec & controller) const;
475477

478+
std::shared_ptr<controller_manager::ParamListener> cm_param_listener_;
476479
diagnostic_updater::Updater diagnostics_updater_;
477480

478481
std::shared_ptr<rclcpp::Executor> executor_;

controller_manager/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
<depend>ros2run</depend>
3030
<depend>std_msgs</depend>
3131
<depend>libstatistics_collector</depend>
32+
<depend>generate_parameter_library</depend>
3233

3334
<test_depend>ament_cmake_gmock</test_depend>
3435
<test_depend>ament_cmake_pytest</test_depend>
Lines changed: 81 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
controller_manager:
2+
update_rate: {
3+
type: int,
4+
default_value: 100,
5+
read_only: true,
6+
description: "The frequency of controller manager's real-time update loop. This loop reads states from hardware, updates controller and writes commands to hardware."
7+
}
8+
9+
diagnostics:
10+
threshold:
11+
controller_manager:
12+
periodicity:
13+
mean_error:
14+
warn: {
15+
type: double,
16+
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."
18+
}
19+
error: {
20+
type: double,
21+
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."
23+
}
24+
standard_deviation:
25+
warn: {
26+
type: double,
27+
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."
29+
}
30+
error: {
31+
type: double,
32+
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."
34+
}
35+
controllers:
36+
periodicity:
37+
mean_error:
38+
warn: {
39+
type: double,
40+
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."
42+
}
43+
error: {
44+
type: double,
45+
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."
47+
}
48+
standard_deviation:
49+
warn: {
50+
type: double,
51+
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."
53+
}
54+
error: {
55+
type: double,
56+
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."
58+
}
59+
execution_time:
60+
mean_error:
61+
warn: {
62+
type: double,
63+
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"
65+
}
66+
error: {
67+
type: double,
68+
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"
70+
}
71+
standard_deviation:
72+
warn: {
73+
type: double,
74+
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."
76+
}
77+
error: {
78+
type: double,
79+
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."
81+
}

0 commit comments

Comments
 (0)