family.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_ros/metrics/internal/family.h"
00018 
00019 #include "absl/memory/memory.h"
00020 #include "cartographer_ros/metrics/internal/counter.h"
00021 #include "cartographer_ros/metrics/internal/gauge.h"
00022 #include "cartographer_ros/metrics/internal/histogram.h"
00023 
00024 namespace cartographer_ros {
00025 namespace metrics {
00026 
00027 using BucketBoundaries = ::cartographer::metrics::Histogram::BucketBoundaries;
00028 
00029 Counter* CounterFamily::Add(const std::map<std::string, std::string>& labels) {
00030   auto wrapper = absl::make_unique<Counter>(labels);
00031   auto* ptr = wrapper.get();
00032   wrappers_.emplace_back(std::move(wrapper));
00033   return ptr;
00034 }
00035 
00036 cartographer_ros_msgs::MetricFamily CounterFamily::ToRosMessage() {
00037   cartographer_ros_msgs::MetricFamily family_msg;
00038   family_msg.name = name_;
00039   family_msg.description = description_;
00040   for (const auto& wrapper : wrappers_) {
00041     family_msg.metrics.push_back(wrapper->ToRosMessage());
00042   }
00043   return family_msg;
00044 }
00045 
00046 Gauge* GaugeFamily::Add(const std::map<std::string, std::string>& labels) {
00047   auto wrapper = absl::make_unique<Gauge>(labels);
00048   auto* ptr = wrapper.get();
00049   wrappers_.emplace_back(std::move(wrapper));
00050   return ptr;
00051 }
00052 
00053 cartographer_ros_msgs::MetricFamily GaugeFamily::ToRosMessage() {
00054   cartographer_ros_msgs::MetricFamily family_msg;
00055   family_msg.name = name_;
00056   family_msg.description = description_;
00057   for (const auto& wrapper : wrappers_) {
00058     family_msg.metrics.push_back(wrapper->ToRosMessage());
00059   }
00060   return family_msg;
00061 }
00062 
00063 Histogram* HistogramFamily::Add(
00064     const std::map<std::string, std::string>& labels) {
00065   auto wrapper = absl::make_unique<Histogram>(labels, boundaries_);
00066   auto* ptr = wrapper.get();
00067   wrappers_.emplace_back(std::move(wrapper));
00068   return ptr;
00069 }
00070 
00071 cartographer_ros_msgs::MetricFamily HistogramFamily::ToRosMessage() {
00072   cartographer_ros_msgs::MetricFamily family_msg;
00073   family_msg.name = name_;
00074   family_msg.description = description_;
00075   for (const auto& wrapper : wrappers_) {
00076     family_msg.metrics.push_back(wrapper->ToRosMessage());
00077   }
00078   return family_msg;
00079 }
00080 
00081 }  // namespace metrics
00082 }  // namespace cartographer_ros


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28