Struct HardwareComponentStatisticsCollector
Defined in File statistics_types.hpp
Struct Documentation
-
struct HardwareComponentStatisticsCollector
Data structure with two moving average statistics collectors. One for the execution time and the other for the periodicity.
Public Functions
-
inline HardwareComponentStatisticsCollector()
-
inline void reset_statistics()
Resets the internal statistics of the execution time and periodicity statistics collectors.
Public Members
-
std::shared_ptr<ros2_control::MovingAverageStatistics> execution_time = nullptr
Execution time statistics collector.
-
std::shared_ptr<ros2_control::MovingAverageStatistics> periodicity = nullptr
Periodicity statistics collector.
-
inline HardwareComponentStatisticsCollector()