15 #ifndef RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_
16 #define RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_
23 #include "libstatistics_collector/collector/generate_statistics_message.hpp"
24 #include "libstatistics_collector/moving_average_statistics/types.hpp"
25 #include "libstatistics_collector/topic_statistics_collector/constants.hpp"
26 #include "libstatistics_collector/topic_statistics_collector/received_message_age.hpp"
27 #include "libstatistics_collector/topic_statistics_collector/received_message_period.hpp"
34 #include "statistics_msgs/msg/metrics_message.hpp"
38 namespace topic_statistics
44 using libstatistics_collector::collector::GenerateStatisticMessage;
45 using statistics_msgs::msg::MetricsMessage;
46 using libstatistics_collector::moving_average_statistics::StatisticData;
54 template<
typename CallbackMessageT>
57 using TopicStatsCollector =
58 libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector<
60 using ReceivedMessageAge =
61 libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector<
63 using ReceivedMessagePeriod =
64 libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector<
83 : node_name_(node_name),
84 publisher_(
std::move(publisher))
88 if (
nullptr == publisher_) {
108 const CallbackMessageT & received_message,
112 for (
const auto & collector : subscriber_statistics_collectors_) {
113 collector->OnMessageReceived(received_message, now_nanoseconds.
nanoseconds());
123 publisher_timer_ = publisher_timer;
133 rclcpp::Time window_end{get_current_nanoseconds_since_epoch()};
137 for (
auto & collector : subscriber_statistics_collectors_) {
138 const auto collected_stats = collector->GetStatisticsResults();
140 auto message = libstatistics_collector::collector::GenerateStatisticMessage(
142 collector->GetMetricName(),
143 collector->GetMetricUnit(),
151 for (
auto & msg : msgs) {
154 window_start_ = window_end;
168 for (
const auto & collector : subscriber_statistics_collectors_) {
169 data.
push_back(collector->GetStatisticsResults());
181 auto received_message_age = std::make_unique<ReceivedMessageAge>();
182 received_message_age->Start();
185 auto received_message_period = std::make_unique<ReceivedMessagePeriod>();
186 received_message_period->Start();
192 window_start_ =
rclcpp::Time(get_current_nanoseconds_since_epoch());
203 for (
auto & collector : subscriber_statistics_collectors_) {
207 subscriber_statistics_collectors_.clear();
210 if (publisher_timer_) {
211 publisher_timer_->cancel();
212 publisher_timer_.reset();
222 int64_t get_current_nanoseconds_since_epoch()
const
225 return std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count();
237 rclcpp::TimerBase::SharedPtr publisher_timer_;
244 #endif // RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_