libstatistics_collector  master
Lightweight aggregation utilities to collect statistics and measure message metrics.
received_message_period.hpp
Go to the documentation of this file.
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 LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
16 #define LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
17 
18 #include <chrono>
19 #include <mutex>
20 #include <string>
21 
22 #include "constants.hpp"
24 
25 #include "rcl/time.h"
26 
28 {
29 namespace topic_statistics_collector
30 {
31 
32 constexpr const int64_t kUninitializedTime{0};
33 
40 template<typename T>
42 {
43 public:
49  {
50  ResetTimeLastMessageReceived();
51  }
52 
53  virtual ~ReceivedMessagePeriodCollector() = default;
54 
62  void OnMessageReceived(const T & received_message, const rcl_time_point_value_t now_nanoseconds)
63  override RCPPUTILS_TSA_REQUIRES(mutex_)
64  {
65  std::unique_lock<std::mutex> ulock{mutex_};
66 
67  (void) received_message;
68 
69  if (time_last_message_received_ == kUninitializedTime) {
70  time_last_message_received_ = now_nanoseconds;
71  } else {
72  const std::chrono::nanoseconds nanos{now_nanoseconds - time_last_message_received_};
73  const auto period = std::chrono::duration_cast<std::chrono::milliseconds>(nanos);
74  time_last_message_received_ = now_nanoseconds;
75  collector::Collector::AcceptData(static_cast<double>(period.count()));
76  }
77  }
78 
84  std::string GetMetricName() const override
85  {
87  }
88 
94  std::string GetMetricUnit() const override
95  {
97  }
98 
99 protected:
104  bool SetupStart() override
105  {
106  ResetTimeLastMessageReceived();
107  return true;
108  }
109 
110  bool SetupStop() override
111  {
112  return true;
113  }
114 
115 private:
119  void ResetTimeLastMessageReceived()
120  {
121  time_last_message_received_ = kUninitializedTime;
122  }
123 
127  rcl_time_point_value_t time_last_message_received_ RCPPUTILS_TSA_GUARDED_BY(mutex_) =
129  mutable std::mutex mutex_;
130 };
131 
132 } // namespace topic_statistics_collector
133 } // namespace libstatistics_collector
134 
135 #endif // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::GetMetricUnit
std::string GetMetricUnit() const override
Definition: received_message_period.hpp:94
libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector
Definition: topic_statistics_collector.hpp:37
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::GetMetricName
std::string GetMetricName() const override
Definition: received_message_period.hpp:84
libstatistics_collector::topic_statistics_collector::kUninitializedTime
constexpr const int64_t kUninitializedTime
Definition: received_message_period.hpp:32
libstatistics_collector
Definition: collector.hpp:29
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::SetupStop
bool SetupStop() override
Definition: received_message_period.hpp:110
topic_statistics_collector.hpp
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::SetupStart
bool SetupStart() override
Definition: received_message_period.hpp:104
libstatistics_collector::topic_statistics_collector::topic_statistics_constants::kMillisecondUnitName
constexpr const char kMillisecondUnitName[]
Definition: constants.hpp:29
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::~ReceivedMessagePeriodCollector
virtual ~ReceivedMessagePeriodCollector()=default
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::OnMessageReceived
void OnMessageReceived(const T &received_message, const rcl_time_point_value_t now_nanoseconds) override RCPPUTILS_TSA_REQUIRES(mutex_)
Definition: received_message_period.hpp:62
libstatistics_collector::topic_statistics_collector::topic_statistics_constants::kMsgPeriodStatName
constexpr const char kMsgPeriodStatName[]
Definition: constants.hpp:28
constants.hpp
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector::ReceivedMessagePeriodCollector
ReceivedMessagePeriodCollector()
Definition: received_message_period.hpp:48
libstatistics_collector::collector::Collector::AcceptData
virtual void AcceptData(const double measurement)
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector
Definition: received_message_period.hpp:41