|
| 1 | +// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_ |
| 16 | +#define RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_ |
| 17 | + |
| 18 | +#include <memory> |
| 19 | +#include <string> |
| 20 | +#include <utility> |
| 21 | +#include <vector> |
| 22 | + |
| 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_period.hpp" |
| 27 | + |
| 28 | +#include "rcl/time.h" |
| 29 | +#include "rclcpp/time.hpp" |
| 30 | +#include "rclcpp/publisher.hpp" |
| 31 | +#include "rclcpp/timer.hpp" |
| 32 | + |
| 33 | +#include "statistics_msgs/msg/metrics_message.hpp" |
| 34 | + |
| 35 | +namespace rclcpp |
| 36 | +{ |
| 37 | +namespace topic_statistics |
| 38 | +{ |
| 39 | + |
| 40 | +constexpr const char kDefaultPublishTopicName[]{"/statistics"}; |
| 41 | +constexpr const std::chrono::milliseconds kDefaultPublishingPeriod{std::chrono::seconds(1)}; |
| 42 | + |
| 43 | +using libstatistics_collector::collector::GenerateStatisticMessage; |
| 44 | +using statistics_msgs::msg::MetricsMessage; |
| 45 | +using libstatistics_collector::moving_average_statistics::StatisticData; |
| 46 | + |
| 47 | +/** |
| 48 | + * Class used to collect, measure, and publish topic statistics data. Current statistics |
| 49 | + * supported for subscribers are received message age and received message period. |
| 50 | + * |
| 51 | + * \tparam CallbackMessageT the subscribed message type |
| 52 | + */ |
| 53 | +template<typename CallbackMessageT> |
| 54 | +class SubscriptionTopicStatistics |
| 55 | +{ |
| 56 | + using TopicStatsCollector = |
| 57 | + libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector< |
| 58 | + CallbackMessageT>; |
| 59 | + using ReceivedMessagePeriod = |
| 60 | + libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector< |
| 61 | + CallbackMessageT>; |
| 62 | + |
| 63 | +public: |
| 64 | + /// Construct a SubscriptionTopicStatistics object. |
| 65 | + /** |
| 66 | + * This object wraps utilities, defined in libstatistics_collector, to collect, |
| 67 | + * measure, and publish topic statistics data. This throws an invalid_argument |
| 68 | + * if the input publisher is null. |
| 69 | + * |
| 70 | + * \param node_name the name of the node, which created this instance, in order to denote |
| 71 | + * topic source |
| 72 | + * \param publisher instance constructed by the node in order to publish statistics data. |
| 73 | + * This class owns the publisher. |
| 74 | + */ |
| 75 | + SubscriptionTopicStatistics( |
| 76 | + const std::string & node_name, |
| 77 | + rclcpp::Publisher<statistics_msgs::msg::MetricsMessage>::SharedPtr publisher) |
| 78 | + : node_name_(node_name), |
| 79 | + publisher_(std::move(publisher)) |
| 80 | + { |
| 81 | + // TODO(dbbonnie): ros-tooling/aws-roadmap/issues/226, received message age |
| 82 | + |
| 83 | + if (nullptr == publisher_) { |
| 84 | + throw std::invalid_argument("publisher pointer is nullptr"); |
| 85 | + } |
| 86 | + |
| 87 | + bring_up(); |
| 88 | + } |
| 89 | + |
| 90 | + virtual ~SubscriptionTopicStatistics() |
| 91 | + { |
| 92 | + tear_down(); |
| 93 | + } |
| 94 | + |
| 95 | + /// Handle a message received by the subscription to collect statistics. |
| 96 | + /** |
| 97 | + * \param received_message the message received by the subscription |
| 98 | + * \param now_nanoseconds current time in nanoseconds |
| 99 | + */ |
| 100 | + virtual void handle_message( |
| 101 | + const CallbackMessageT & received_message, |
| 102 | + const rclcpp::Time now_nanoseconds) const |
| 103 | + { |
| 104 | + for (const auto & collector : subscriber_statistics_collectors_) { |
| 105 | + collector->OnMessageReceived(received_message, now_nanoseconds.nanoseconds()); |
| 106 | + } |
| 107 | + } |
| 108 | + |
| 109 | + /// Set the timer used to publish statistics messages. |
| 110 | + /** |
| 111 | + * \param measurement_timer the timer to fire the publisher, created by the node |
| 112 | + */ |
| 113 | + void set_publisher_timer(rclcpp::TimerBase::SharedPtr publisher_timer) |
| 114 | + { |
| 115 | + publisher_timer_ = publisher_timer; |
| 116 | + } |
| 117 | + |
| 118 | + /// Publish a populated MetricsStatisticsMessage. |
| 119 | + virtual void publish_message() |
| 120 | + { |
| 121 | + rclcpp::Time window_end{get_current_nanoseconds_since_epoch()}; |
| 122 | + |
| 123 | + for (auto & collector : subscriber_statistics_collectors_) { |
| 124 | + const auto collected_stats = collector->GetStatisticsResults(); |
| 125 | + |
| 126 | + auto message = libstatistics_collector::collector::GenerateStatisticMessage( |
| 127 | + node_name_, |
| 128 | + collector->GetMetricName(), |
| 129 | + collector->GetMetricUnit(), |
| 130 | + window_start_, |
| 131 | + window_end, |
| 132 | + collected_stats); |
| 133 | + publisher_->publish(message); |
| 134 | + } |
| 135 | + window_start_ = window_end; |
| 136 | + } |
| 137 | + |
| 138 | +protected: |
| 139 | + /// Return a vector of all the currently collected data. |
| 140 | + /** |
| 141 | + * \return a vector of all the collected data |
| 142 | + */ |
| 143 | + std::vector<StatisticData> get_current_collector_data() const |
| 144 | + { |
| 145 | + std::vector<StatisticData> data; |
| 146 | + for (const auto & collector : subscriber_statistics_collectors_) { |
| 147 | + data.push_back(collector->GetStatisticsResults()); |
| 148 | + } |
| 149 | + return data; |
| 150 | + } |
| 151 | + |
| 152 | +private: |
| 153 | + /// Construct and start all collectors and set window_start_. |
| 154 | + void bring_up() |
| 155 | + { |
| 156 | + auto received_message_period = std::make_unique<ReceivedMessagePeriod>(); |
| 157 | + received_message_period->Start(); |
| 158 | + subscriber_statistics_collectors_.emplace_back(std::move(received_message_period)); |
| 159 | + |
| 160 | + window_start_ = rclcpp::Time(get_current_nanoseconds_since_epoch()); |
| 161 | + } |
| 162 | + |
| 163 | + /// Stop all collectors, clear measurements, stop publishing timer, and reset publisher. |
| 164 | + void tear_down() |
| 165 | + { |
| 166 | + for (auto & collector : subscriber_statistics_collectors_) { |
| 167 | + collector->Stop(); |
| 168 | + } |
| 169 | + |
| 170 | + subscriber_statistics_collectors_.clear(); |
| 171 | + |
| 172 | + if (publisher_timer_) { |
| 173 | + publisher_timer_->cancel(); |
| 174 | + publisher_timer_.reset(); |
| 175 | + } |
| 176 | + |
| 177 | + publisher_.reset(); |
| 178 | + } |
| 179 | + |
| 180 | + /// Return the current nanoseconds (count) since epoch. |
| 181 | + /** |
| 182 | + * \return the current nanoseconds (count) since epoch |
| 183 | + */ |
| 184 | + int64_t get_current_nanoseconds_since_epoch() const |
| 185 | + { |
| 186 | + const auto now = std::chrono::system_clock::now(); |
| 187 | + return std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count(); |
| 188 | + } |
| 189 | + |
| 190 | + /// Collection of statistics collectors |
| 191 | + std::vector<std::unique_ptr<TopicStatsCollector>> subscriber_statistics_collectors_{}; |
| 192 | + /// Node name used to generate topic statistics messages to be published |
| 193 | + const std::string node_name_; |
| 194 | + /// Publisher, created by the node, used to publish topic statistics messages |
| 195 | + rclcpp::Publisher<statistics_msgs::msg::MetricsMessage>::SharedPtr publisher_; |
| 196 | + /// Timer which fires the publisher |
| 197 | + rclcpp::TimerBase::SharedPtr publisher_timer_; |
| 198 | + /// The start of the collection window, used in the published topic statistics message |
| 199 | + rclcpp::Time window_start_; |
| 200 | +}; |
| 201 | +} // namespace topic_statistics |
| 202 | +} // namespace rclcpp |
| 203 | + |
| 204 | +#endif // RCLCPP__TOPIC_STATISTICS__SUBSCRIPTION_TOPIC_STATISTICS_HPP_ |
0 commit comments