libstatistics_collector  master
Lightweight aggregation utilities to collect statistics and measure message metrics.
collector.hpp
Go to the documentation of this file.
1 // Copyright 2019 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__COLLECTOR__COLLECTOR_HPP_
16 #define LIBSTATISTICS_COLLECTOR__COLLECTOR__COLLECTOR_HPP_
17 
18 #include <mutex>
19 #include <string>
20 
24 
26 
27 #include "rcpputils/thread_safety_annotations.hpp"
28 
30 {
31 namespace collector
32 {
33 
38 {
39 public:
41  Collector() = default;
42 
44  virtual ~Collector() = default;
45 
53  virtual void AcceptData(const double measurement);
54 
62 
67  virtual void ClearCurrentMeasurements();
68 
75  bool IsStarted() const;
76 
83  virtual std::string GetStatusString() const;
84 
85  // TODO(dabonnie): uptime (once start has been called)
86 
95  virtual bool Start();
96 
107  virtual bool Stop();
108 
109 private:
115  virtual bool SetupStart() RCPPUTILS_TSA_REQUIRES(mutex_) = 0;
116 
122  virtual bool SetupStop() RCPPUTILS_TSA_REQUIRES(mutex_) = 0;
123 
124  mutable std::mutex mutex_;
125 
127 
128  bool started_ RCPPUTILS_TSA_GUARDED_BY(mutex_) = false;
129 };
130 
131 } // namespace collector
132 } // namespace libstatistics_collector
133 
134 #endif // LIBSTATISTICS_COLLECTOR__COLLECTOR__COLLECTOR_HPP_
libstatistics_collector::collector::Collector::Stop
virtual bool Stop()
libstatistics_collector::collector::Collector::~Collector
virtual ~Collector()=default
libstatistics_collector::collector::Collector::Collector
Collector()=default
types.hpp
libstatistics_collector
Definition: collector.hpp:29
libstatistics_collector::collector::Collector::IsStarted
bool IsStarted() const
libstatistics_collector::collector::MetricDetailsInterface
Definition: metric_details_interface.hpp:31
libstatistics_collector::collector::Collector::GetStatusString
virtual std::string GetStatusString() const
metric_details_interface.hpp
moving_average.hpp
libstatistics_collector::collector::Collector::ClearCurrentMeasurements
virtual void ClearCurrentMeasurements()
visibility_control.hpp
libstatistics_collector::collector::Collector::Start
virtual bool Start()
libstatistics_collector::collector::Collector::GetStatisticsResults
virtual moving_average_statistics::StatisticData GetStatisticsResults() const
libstatistics_collector::moving_average_statistics::MovingAverageStatistics
Definition: moving_average.hpp:49
libstatistics_collector::collector::Collector::AcceptData
virtual void AcceptData(const double measurement)
LIBSTATISTICS_COLLECTOR_PUBLIC
#define LIBSTATISTICS_COLLECTOR_PUBLIC
Definition: visibility_control.hpp:40
libstatistics_collector::collector::Collector
Definition: collector.hpp:37
libstatistics_collector::moving_average_statistics::StatisticData
Definition: types.hpp:32