family_factory.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/cloud/metrics/prometheus/family_factory.h"
00018 
00019 #include "absl/container/flat_hash_map.h"
00020 #include "absl/memory/memory.h"
00021 #include "prometheus/counter.h"
00022 #include "prometheus/family.h"
00023 #include "prometheus/gauge.h"
00024 #include "prometheus/histogram.h"
00025 
00026 namespace cartographer {
00027 namespace cloud {
00028 namespace metrics {
00029 namespace prometheus {
00030 namespace {
00031 
00032 using BucketBoundaries = ::cartographer::metrics::Histogram::BucketBoundaries;
00033 
00034 // Creates or looks up already existing objects from a wrapper map.
00035 template <typename WrapperMap,
00036           typename ObjectPtr = typename WrapperMap::key_type,
00037           typename Wrapper = typename WrapperMap::mapped_type::element_type>
00038 Wrapper* GetOrCreateWrapper(ObjectPtr object_ptr, WrapperMap* wrapper_map,
00039                             std::mutex* wrapper_mutex) {
00040   std::lock_guard<std::mutex> lock(*wrapper_mutex);
00041   auto wrappers_itr = wrapper_map->find(object_ptr);
00042   if (wrappers_itr == wrapper_map->end()) {
00043     auto wrapper = absl::make_unique<Wrapper>(object_ptr);
00044     auto* ptr = wrapper.get();
00045     (*wrapper_map)[object_ptr] = std::unique_ptr<Wrapper>(std::move(wrapper));
00046     return ptr;
00047   }
00048   return wrappers_itr->second.get();
00049 }
00050 
00051 class Counter : public ::cartographer::metrics::Counter {
00052  public:
00053   explicit Counter(::prometheus::Counter* prometheus)
00054       : prometheus_(prometheus) {}
00055 
00056   void Increment() override { prometheus_->Increment(); }
00057   void Increment(double by_value) override { prometheus_->Increment(by_value); }
00058 
00059  private:
00060   ::prometheus::Counter* prometheus_;
00061 };
00062 
00063 class CounterFamily
00064     : public ::cartographer::metrics::Family<::cartographer::metrics::Counter> {
00065  public:
00066   explicit CounterFamily(
00067       ::prometheus::Family<::prometheus::Counter>* prometheus)
00068       : prometheus_(prometheus) {}
00069 
00070   Counter* Add(const std::map<std::string, std::string>& labels) override {
00071     ::prometheus::Counter* counter = &prometheus_->Add(labels);
00072     return GetOrCreateWrapper<>(counter, &wrappers_, &wrappers_mutex_);
00073   }
00074 
00075  private:
00076   ::prometheus::Family<::prometheus::Counter>* prometheus_;
00077   std::mutex wrappers_mutex_;
00078   absl::flat_hash_map<::prometheus::Counter*, std::unique_ptr<Counter>>
00079       wrappers_;
00080 };
00081 
00082 class Gauge : public ::cartographer::metrics::Gauge {
00083  public:
00084   explicit Gauge(::prometheus::Gauge* prometheus) : prometheus_(prometheus) {}
00085 
00086   void Decrement() override { prometheus_->Decrement(); }
00087   void Decrement(double by_value) override { prometheus_->Decrement(by_value); }
00088   void Increment() override { prometheus_->Increment(); }
00089   void Increment(double by_value) override { prometheus_->Increment(by_value); }
00090   void Set(double value) override { prometheus_->Set(value); }
00091 
00092  private:
00093   ::prometheus::Gauge* prometheus_;
00094 };
00095 
00096 class GaugeFamily
00097     : public ::cartographer::metrics::Family<::cartographer::metrics::Gauge> {
00098  public:
00099   explicit GaugeFamily(::prometheus::Family<::prometheus::Gauge>* prometheus)
00100       : prometheus_(prometheus) {}
00101 
00102   Gauge* Add(const std::map<std::string, std::string>& labels) override {
00103     ::prometheus::Gauge* gauge = &prometheus_->Add(labels);
00104     return GetOrCreateWrapper<>(gauge, &wrappers_, &wrappers_mutex_);
00105   }
00106 
00107  private:
00108   ::prometheus::Family<::prometheus::Gauge>* prometheus_;
00109   std::mutex wrappers_mutex_;
00110   absl::flat_hash_map<::prometheus::Gauge*, std::unique_ptr<Gauge>> wrappers_;
00111 };
00112 
00113 class Histogram : public ::cartographer::metrics::Histogram {
00114  public:
00115   explicit Histogram(::prometheus::Histogram* prometheus)
00116       : prometheus_(prometheus) {}
00117 
00118   void Observe(double value) override { prometheus_->Observe(value); }
00119 
00120  private:
00121   ::prometheus::Histogram* prometheus_;
00122 };
00123 
00124 class HistogramFamily : public ::cartographer::metrics::Family<
00125                             ::cartographer::metrics::Histogram> {
00126  public:
00127   HistogramFamily(::prometheus::Family<::prometheus::Histogram>* prometheus,
00128                   const BucketBoundaries& boundaries)
00129       : prometheus_(prometheus), boundaries_(boundaries) {}
00130 
00131   Histogram* Add(const std::map<std::string, std::string>& labels) override {
00132     ::prometheus::Histogram* histogram = &prometheus_->Add(labels, boundaries_);
00133     return GetOrCreateWrapper<>(histogram, &wrappers_, &wrappers_mutex_);
00134   }
00135 
00136  private:
00137   ::prometheus::Family<::prometheus::Histogram>* prometheus_;
00138   std::mutex wrappers_mutex_;
00139   absl::flat_hash_map<::prometheus::Histogram*, std::unique_ptr<Histogram>>
00140       wrappers_;
00141   const BucketBoundaries boundaries_;
00142 };
00143 
00144 }  // namespace
00145 
00146 FamilyFactory::FamilyFactory()
00147     : registry_(std::make_shared<::prometheus::Registry>()) {}
00148 
00149 ::cartographer::metrics::Family<::cartographer::metrics::Counter>*
00150 FamilyFactory::NewCounterFamily(const std::string& name,
00151                                 const std::string& description) {
00152   auto& family = ::prometheus::BuildCounter()
00153                      .Name(name)
00154                      .Help(description)
00155                      .Register(*registry_);
00156   auto wrapper = absl::make_unique<CounterFamily>(&family);
00157   auto* ptr = wrapper.get();
00158   counters_.emplace_back(std::move(wrapper));
00159   return ptr;
00160 }
00161 
00162 ::cartographer::metrics::Family<::cartographer::metrics::Gauge>*
00163 FamilyFactory::NewGaugeFamily(const std::string& name,
00164                               const std::string& description) {
00165   auto& family = ::prometheus::BuildGauge()
00166                      .Name(name)
00167                      .Help(description)
00168                      .Register(*registry_);
00169   auto wrapper = absl::make_unique<GaugeFamily>(&family);
00170   auto* ptr = wrapper.get();
00171   gauges_.emplace_back(std::move(wrapper));
00172   return ptr;
00173 }
00174 
00175 ::cartographer::metrics::Family<::cartographer::metrics::Histogram>*
00176 FamilyFactory::NewHistogramFamily(const std::string& name,
00177                                   const std::string& description,
00178                                   const BucketBoundaries& boundaries) {
00179   auto& family = ::prometheus::BuildHistogram()
00180                      .Name(name)
00181                      .Help(description)
00182                      .Register(*registry_);
00183   auto wrapper = absl::make_unique<HistogramFamily>(&family, boundaries);
00184   auto* ptr = wrapper.get();
00185   histograms_.emplace_back(std::move(wrapper));
00186   return ptr;
00187 }
00188 
00189 std::weak_ptr<::prometheus::Collectable> FamilyFactory::GetCollectable() const {
00190   return registry_;
00191 }
00192 
00193 }  // namespace prometheus
00194 }  // namespace metrics
00195 }  // namespace cloud
00196 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35