This repository has been archived by the owner on Jun 10, 2021. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 8
/
received_message_period.hpp
131 lines (112 loc) · 3.63 KB
/
received_message_period.hpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
#define TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
#include <chrono>
#include <mutex>
#include <string>
#include "constants.hpp"
#include "topic_statistics_collector.hpp"
#include "rcl/time.h"
namespace topic_statistics_collector
{
constexpr const int64_t kUninitializedTime{0};
/**
* Class used to measure the received messsage, tparam T, period from a ROS2 subscriber. This class
* is thread safe and acquires a mutex when the member OnMessageReceived is executed.
*
* @tparam T the message type to receive from the subscriber / listener
*/
template<typename T>
class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
{
public:
/**
* Construct a ReceivedMessagePeriodCollector object.
*
*/
ReceivedMessagePeriodCollector()
{
ResetTimeLastMessageReceived();
}
virtual ~ReceivedMessagePeriodCollector() = default;
/**
* Handle a message received and measure its received period. This member is thread safe and acquires
* a lock to prevent race conditions when setting the time_last_message_received_ member.
*
* @param received_message
* @param time the message was received in nanoseconds
*/
void OnMessageReceived(const T & received_message, const rcl_time_point_value_t now_nanoseconds)
override RCPPUTILS_TSA_REQUIRES(mutex_)
{
std::unique_lock<std::mutex> ulock{mutex_};
if (time_last_message_received_ == kUninitializedTime) {
time_last_message_received_ = now_nanoseconds;
} else {
const std::chrono::nanoseconds nanos{now_nanoseconds - time_last_message_received_};
const auto period = std::chrono::duration_cast<std::chrono::milliseconds>(nanos);
time_last_message_received_ = now_nanoseconds;
collector::Collector::AcceptData(static_cast<double>(period.count()));
}
}
/**
* Return message period metric name
*
* @return a string representing message period metric name
*/
std::string GetMetricName() const override
{
return topic_statistics_constants::kMsgPeriodStatName;
}
/**
* Return message period metric unit
*
* @return a string representing message period metric unit
*/
std::string GetMetricUnit() const override
{
return topic_statistics_constants::kMillisecondUnitName;
}
protected:
/**
* Reset the time_last_message_received_ member.
* @return true
*/
bool SetupStart() override
{
ResetTimeLastMessageReceived();
return true;
}
bool SetupStop() override
{
return true;
}
private:
/**
* Resets time_last_message_received_ to the expected uninitialized_time_.
*/
void ResetTimeLastMessageReceived()
{
time_last_message_received_ = kUninitializedTime;
}
/**
* Default uninitialized time.
*/
rcl_time_point_value_t time_last_message_received_{kUninitializedTime}
RCPPUTILS_TSA_GUARDED_BY(mutex_);
mutable std::mutex mutex_;
};
} // namespace topic_statistics_collector
#endif // TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_