libstatistics_collector  master
Lightweight aggregation utilities to collect statistics and measure message metrics.
All Classes Functions Variables Pages
received_message_age.hpp
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_AGE_HPP_
16 #define LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_AGE_HPP_
17 
18 #include <chrono>
19 #include <string>
20 #include <sstream>
21 #include <type_traits>
22 #include <utility>
23 
24 #include "constants.hpp"
25 
26 #include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp"
27 
28 #include "rcl/time.h"
29 #include "rcutils/logging_macros.h"
30 
31 namespace libstatistics_collector
32 {
33 namespace topic_statistics_collector
34 {
35 
40 template<typename M, typename = void>
41 struct HasHeader : public std::false_type {};
42 
47 template<typename M>
48 struct HasHeader<M, decltype((void) M::header)>: std::true_type {};
49 
54 template<typename M, typename Enable = void>
55 struct TimeStamp
56 {
61  static std::pair<bool, int64_t> value(const M &)
62  {
63  return std::make_pair(false, 0);
64  }
65 };
66 
71 template<typename M>
72 struct TimeStamp<M, typename std::enable_if<HasHeader<M>::value>::type>
73 {
77  static std::pair<bool, int64_t> value(const M & m)
78  {
79  const auto stamp = m.header.stamp;
80  const auto nanos = RCL_S_TO_NS(static_cast<int64_t>(stamp.sec)) + stamp.nanosec;
81  return std::make_pair(true, nanos);
82  }
83 };
84 
90 template<typename T>
92 {
93 public:
94  ReceivedMessageAgeCollector() = default;
95 
96  virtual ~ReceivedMessageAgeCollector() = default;
97 
105  const T & received_message,
106  const rcl_time_point_value_t now_nanoseconds) override
107  {
108  const auto timestamp_from_header = TimeStamp<T>::value(received_message);
109 
110  if (timestamp_from_header.first) {
111  // only compare if non-zero
112  if (timestamp_from_header.second && now_nanoseconds) {
113  const std::chrono::nanoseconds age_nanos{now_nanoseconds - timestamp_from_header.second};
114  const auto age_millis = std::chrono::duration<double, std::milli>(age_nanos);
115 
116  collector::Collector::AcceptData(static_cast<double>(age_millis.count()));
117  } // else no valid time to compute age
118  }
119  }
120 
126  std::string GetMetricName() const override
127  {
128  return topic_statistics_constants::kMsgAgeStatName;
129  }
130 
136  std::string GetMetricUnit() const override
137  {
138  return topic_statistics_constants::kMillisecondUnitName;
139  }
140 
141 protected:
142  bool SetupStart() override
143  {
144  return true;
145  }
146 
147  bool SetupStop() override
148  {
149  return true;
150  }
151 };
152 
153 } // namespace topic_statistics_collector
154 } // namespace libstatistics_collector
155 
156 #endif // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_AGE_HPP_
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector::GetMetricUnit
std::string GetMetricUnit() const override
Definition: received_message_age.hpp:136
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector::OnMessageReceived
void OnMessageReceived(const T &received_message, const rcl_time_point_value_t now_nanoseconds) override
Definition: received_message_age.hpp:104
libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector
Definition: topic_statistics_collector.hpp:37
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector::SetupStart
bool SetupStart() override
Definition: received_message_age.hpp:142
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector::GetMetricName
std::string GetMetricName() const override
Definition: received_message_age.hpp:126
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector
Definition: received_message_age.hpp:91
libstatistics_collector::topic_statistics_collector::HasHeader
Definition: received_message_age.hpp:41
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector::SetupStop
bool SetupStop() override
Definition: received_message_age.hpp:147
libstatistics_collector::topic_statistics_collector::TimeStamp< M, typename std::enable_if< HasHeader< M >::value >::type >::value
static std::pair< bool, int64_t > value(const M &m)
Definition: received_message_age.hpp:77
libstatistics_collector::collector::Collector::AcceptData
virtual void AcceptData(const double measurement)
libstatistics_collector::topic_statistics_collector::TimeStamp::value
static std::pair< bool, int64_t > value(const M &)
Definition: received_message_age.hpp:61
libstatistics_collector::topic_statistics_collector::TimeStamp
Definition: received_message_age.hpp:55