Skip to content

Commit 89fd4ef

Browse files
authored
[Diagnostics] Add diagnostics of execution time and periodicity of the controllers and controller_manager (#1871)
1 parent dd84414 commit 89fd4ef

File tree

13 files changed

+703
-111
lines changed

13 files changed

+703
-111
lines changed

controller_interface/include/controller_interface/controller_interface_base.hpp

Lines changed: 22 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -71,6 +71,25 @@ struct ControllerUpdateStats
7171
unsigned int total_triggers;
7272
unsigned int failed_triggers;
7373
};
74+
75+
/**
76+
* Struct to store the status of the controller update method.
77+
* The status contains information if the update was triggered successfully, the result of the
78+
* update method and the execution duration of the update method. The status is used to provide
79+
* feedback to the controller_manager.
80+
* @var successful: true if the update was triggered successfully, false if not.
81+
* @var result: return_type::OK if update is successfully, otherwise return_type::ERROR.
82+
* @var execution_time: duration of the execution of the update method.
83+
* @var period: period of the update method.
84+
*/
85+
struct ControllerUpdateStatus
86+
{
87+
bool successful = true;
88+
return_type result = return_type::OK;
89+
std::optional<std::chrono::nanoseconds> execution_time = std::nullopt;
90+
std::optional<rclcpp::Duration> period = std::nullopt;
91+
};
92+
7493
/**
7594
* Base interface class for an controller. The interface may not be used to implement a controller.
7695
* The class provides definitions for `ControllerInterface` and `ChainableControllerInterface`
@@ -175,13 +194,11 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
175194
*
176195
* \param[in] time The time at the start of this control loop iteration
177196
* \param[in] period The measured time taken by the last control loop iteration
178-
* \returns A pair with the first element being a boolean indicating if the async callback method
179-
* was triggered and the second element being the last return value of the async function. For
180-
* more details check the AsyncFunctionHandler implementation in `realtime_tools` package.
197+
* \returns ControllerUpdateStatus. The status contains information if the update was triggered
198+
* successfully, the result of the update method and the execution duration of the update method.
181199
*/
182200
CONTROLLER_INTERFACE_PUBLIC
183-
std::pair<bool, return_type> trigger_update(
184-
const rclcpp::Time & time, const rclcpp::Duration & period);
201+
ControllerUpdateStatus trigger_update(const rclcpp::Time & time, const rclcpp::Duration & period);
185202

186203
CONTROLLER_INTERFACE_PUBLIC
187204
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> get_node();

controller_interface/src/controller_interface_base.cpp

Lines changed: 21 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -159,12 +159,14 @@ const rclcpp_lifecycle::State & ControllerInterfaceBase::get_lifecycle_state() c
159159
return node_->get_current_state();
160160
}
161161

162-
std::pair<bool, return_type> ControllerInterfaceBase::trigger_update(
162+
ControllerUpdateStatus ControllerInterfaceBase::trigger_update(
163163
const rclcpp::Time & time, const rclcpp::Duration & period)
164164
{
165+
ControllerUpdateStatus status;
165166
trigger_stats_.total_triggers++;
166167
if (is_async())
167168
{
169+
const rclcpp::Time last_trigger_time = async_handler_->get_current_callback_time();
168170
const auto result = async_handler_->trigger_async_callback(time, period);
169171
if (!result.first)
170172
{
@@ -174,12 +176,28 @@ std::pair<bool, return_type> ControllerInterfaceBase::trigger_update(
174176
"The controller missed %u update cycles out of %u total triggers.",
175177
trigger_stats_.failed_triggers, trigger_stats_.total_triggers);
176178
}
177-
return result;
179+
status.successful = result.first;
180+
status.result = result.second;
181+
const auto execution_time = async_handler_->get_last_execution_time();
182+
if (execution_time.count() > 0)
183+
{
184+
status.execution_time = execution_time;
185+
}
186+
if (last_trigger_time.get_clock_type() != RCL_CLOCK_UNINITIALIZED)
187+
{
188+
status.period = time - last_trigger_time;
189+
}
178190
}
179191
else
180192
{
181-
return std::make_pair(true, update(time, period));
193+
const auto start_time = std::chrono::steady_clock::now();
194+
status.successful = true;
195+
status.result = update(time, period);
196+
status.execution_time = std::chrono::duration_cast<std::chrono::nanoseconds>(
197+
std::chrono::steady_clock::now() - start_time);
198+
status.period = period;
182199
}
200+
return status;
183201
}
184202

185203
std::shared_ptr<rclcpp_lifecycle::LifecycleNode> ControllerInterfaceBase::get_node()

controller_manager/CMakeLists.txt

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1616
rclcpp
1717
realtime_tools
1818
std_msgs
19+
libstatistics_collector
20+
generate_parameter_library
1921
)
2022

2123
find_package(ament_cmake REQUIRED)
@@ -27,6 +29,10 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
2729
find_package(${Dependency} REQUIRED)
2830
endforeach()
2931

32+
generate_parameter_library(controller_manager_parameters
33+
src/controller_manager_parameters.yaml
34+
)
35+
3036
add_library(controller_manager SHARED
3137
src/controller_manager.cpp
3238
)
@@ -35,6 +41,9 @@ target_include_directories(controller_manager PUBLIC
3541
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
3642
$<INSTALL_INTERFACE:include/controller_manager>
3743
)
44+
target_link_libraries(controller_manager PUBLIC
45+
controller_manager_parameters
46+
)
3847
ament_target_dependencies(controller_manager PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
3948

4049
# Causes the visibility macros to use dllexport rather than dllimport,
@@ -236,7 +245,7 @@ install(
236245
DESTINATION include/controller_manager
237246
)
238247
install(
239-
TARGETS controller_manager
248+
TARGETS controller_manager controller_manager_parameters
240249
EXPORT export_controller_manager
241250
RUNTIME DESTINATION bin
242251
LIBRARY DESTINATION lib
Lines changed: 21 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
hardware_components_initial_state: |
2+
Map of parameters for controlled lifecycle management of hardware components.
3+
The names of the components are defined as attribute of ``<ros2_control>``-tag in ``robot_description``.
4+
Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated.
5+
Detailed explanation of each parameter is given below.
6+
The full structure of the map is given in the following example:
7+
8+
.. code-block:: yaml
9+
10+
hardware_components_initial_state:
11+
unconfigured:
12+
- "arm1"
13+
- "arm2"
14+
inactive:
15+
- "base3"
16+
17+
diagnostics.threshold.controllers.periodicity: |
18+
The ``periodicity`` 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.
19+
20+
diagnostics.threshold.controllers.execution_time: |
21+
The ``execution_time`` diagnostics will be published for all controllers. 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.

controller_manager/doc/userdoc.rst

Lines changed: 10 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -57,32 +57,6 @@ robot_description [std_msgs::msg::String]
5757
Parameters
5858
-----------
5959

60-
hardware_components_initial_state
61-
Map of parameters for controlled lifecycle management of hardware components.
62-
The names of the components are defined as attribute of ``<ros2_control>``-tag in ``robot_description``.
63-
Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated.
64-
Detailed explanation of each parameter is given below.
65-
The full structure of the map is given in the following example:
66-
67-
.. code-block:: yaml
68-
69-
hardware_components_initial_state:
70-
unconfigured:
71-
- "arm1"
72-
- "arm2"
73-
inactive:
74-
- "base3"
75-
76-
hardware_components_initial_state.unconfigured (optional; list<string>; default: empty)
77-
Defines which hardware components will be only loaded immediately when controller manager is started.
78-
79-
hardware_components_initial_state.inactive (optional; list<string>; default: empty)
80-
Defines which hardware components will be configured immediately when controller manager is started.
81-
82-
update_rate (mandatory; integer)
83-
The frequency of controller manager's real-time update loop.
84-
This loop reads states from hardware, updates controller and writes commands to hardware.
85-
8660
<controller_name>.type
8761
Name of a plugin exported using ``pluginlib`` for a controller.
8862
This is a class from which controller's instance with name "``controller_name``" is created.
@@ -99,6 +73,16 @@ update_rate (mandatory; integer)
9973
The fallback controllers activation is subject to the availability of the state and command interfaces at the time of activation.
10074
It is recommended to test the fallback strategy in simulation before deploying it on the real robot.
10175

76+
.. generate_parameter_library_details::
77+
../src/controller_manager_parameters.yaml
78+
parameters_context.yaml
79+
80+
**An example parameter file:**
81+
82+
.. generate_parameter_library_default::
83+
../src/controller_manager_parameters.yaml
84+
85+
10286
Handling Multiple Controller Managers
10387
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
10488

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,8 @@
5050

5151
namespace controller_manager
5252
{
53+
class ParamListener;
54+
class Params;
5355
using ControllersListIterator = std::vector<controller_manager::ControllerSpec>::const_iterator;
5456

5557
CONTROLLER_MANAGER_PUBLIC rclcpp::NodeOptions get_cm_node_options();
@@ -346,7 +348,7 @@ class ControllerManager : public rclcpp::Node
346348

347349
// Per controller update rate support
348350
unsigned int update_loop_counter_ = 0;
349-
unsigned int update_rate_ = 100;
351+
unsigned int update_rate_;
350352
std::vector<std::vector<std::string>> chained_controllers_configuration_;
351353

352354
std::unique_ptr<hardware_interface::ResourceManager> resource_manager_;
@@ -357,6 +359,8 @@ class ControllerManager : public rclcpp::Node
357359
const std::string & command_interface);
358360
void init_controller_manager();
359361

362+
void initialize_parameters();
363+
360364
/**
361365
* Clear request lists used when switching controllers. The lists are shared between "callback"
362366
* and "control loop" threads.
@@ -473,6 +477,8 @@ class ControllerManager : public rclcpp::Node
473477
*/
474478
rclcpp::NodeOptions determine_controller_node_options(const ControllerSpec & controller) const;
475479

480+
std::shared_ptr<controller_manager::ParamListener> cm_param_listener_;
481+
std::shared_ptr<controller_manager::Params> params_;
476482
diagnostic_updater::Updater diagnostics_updater_;
477483

478484
std::shared_ptr<rclcpp::Executor> executor_;
@@ -603,6 +609,8 @@ class ControllerManager : public rclcpp::Node
603609
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
604610
rclcpp::TimerBase::SharedPtr robot_description_notification_timer_;
605611

612+
controller_manager::MovingAverageStatistics periodicity_stats_;
613+
606614
struct SwitchParams
607615
{
608616
void reset()

controller_manager/include/controller_manager/controller_spec.hpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,13 @@
2424
#include <vector>
2525
#include "controller_interface/controller_interface_base.hpp"
2626
#include "hardware_interface/controller_info.hpp"
27+
#include "libstatistics_collector/moving_average_statistics/moving_average.hpp"
2728

2829
namespace controller_manager
2930
{
31+
32+
using MovingAverageStatistics =
33+
libstatistics_collector::moving_average_statistics::MovingAverageStatistics;
3034
/// Controller Specification
3135
/**
3236
* This struct contains both a pointer to a given controller, \ref c, as well
@@ -35,9 +39,18 @@ namespace controller_manager
3539
*/
3640
struct ControllerSpec
3741
{
42+
ControllerSpec()
43+
{
44+
last_update_cycle_time = std::make_shared<rclcpp::Time>(0, 0, RCL_CLOCK_UNINITIALIZED);
45+
execution_time_statistics = std::make_shared<MovingAverageStatistics>();
46+
periodicity_statistics = std::make_shared<MovingAverageStatistics>();
47+
}
48+
3849
hardware_interface::ControllerInfo info;
3950
controller_interface::ControllerInterfaceBaseSharedPtr c;
4051
std::shared_ptr<rclcpp::Time> last_update_cycle_time;
52+
std::shared_ptr<MovingAverageStatistics> execution_time_statistics;
53+
std::shared_ptr<MovingAverageStatistics> periodicity_statistics;
4154
};
4255

4356
struct ControllerChainSpec

controller_manager/package.xml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,8 @@
2828
<depend>ros2param</depend>
2929
<depend>ros2run</depend>
3030
<depend>std_msgs</depend>
31+
<depend>libstatistics_collector</depend>
32+
<depend>generate_parameter_library</depend>
3133

3234
<test_depend>ament_cmake_gmock</test_depend>
3335
<test_depend>ament_cmake_pytest</test_depend>

0 commit comments

Comments
 (0)