histogram.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/histogram.h"
00018 
00019 #include <algorithm>
00020 #include <numeric>
00021 
00022 #include "glog/logging.h"
00023 
00024 namespace cartographer_ros {
00025 namespace metrics {
00026 
00027 using BucketBoundaries = ::cartographer::metrics::Histogram::BucketBoundaries;
00028 
00029 Histogram::Histogram(const std::map<std::string, std::string>& labels,
00030                      const BucketBoundaries& bucket_boundaries)
00031     : labels_(labels),
00032       bucket_boundaries_(bucket_boundaries),
00033       bucket_counts_(bucket_boundaries.size() + 1) {
00034   absl::MutexLock lock(&mutex_);
00035   CHECK(std::is_sorted(std::begin(bucket_boundaries_),
00036                        std::end(bucket_boundaries_)));
00037 }
00038 
00039 void Histogram::Observe(double value) {
00040   auto bucket_index =
00041       std::distance(bucket_boundaries_.begin(),
00042                     std::upper_bound(bucket_boundaries_.begin(),
00043                                      bucket_boundaries_.end(), value));
00044   absl::MutexLock lock(&mutex_);
00045   sum_ += value;
00046   bucket_counts_[bucket_index] += 1;
00047 }
00048 
00049 std::map<double, double> Histogram::CountsByBucket() {
00050   absl::MutexLock lock(&mutex_);
00051   std::map<double, double> counts_by_bucket;
00052   // Add the finite buckets.
00053   for (size_t i = 0; i < bucket_boundaries_.size(); ++i) {
00054     counts_by_bucket[bucket_boundaries_.at(i)] = bucket_counts_.at(i);
00055   }
00056   // Add the "infinite" bucket.
00057   counts_by_bucket[kInfiniteBoundary] = bucket_counts_.back();
00058   return counts_by_bucket;
00059 }
00060 
00061 double Histogram::Sum() {
00062   absl::MutexLock lock(&mutex_);
00063   return sum_;
00064 }
00065 
00066 double Histogram::CumulativeCount() {
00067   absl::MutexLock lock(&mutex_);
00068   return std::accumulate(bucket_counts_.begin(), bucket_counts_.end(), 0.);
00069 }
00070 
00071 cartographer_ros_msgs::Metric Histogram::ToRosMessage() {
00072   cartographer_ros_msgs::Metric msg;
00073   msg.type = cartographer_ros_msgs::Metric::TYPE_HISTOGRAM;
00074   for (const auto& label : labels_) {
00075     cartographer_ros_msgs::MetricLabel label_msg;
00076     label_msg.key = label.first;
00077     label_msg.value = label.second;
00078     msg.labels.push_back(label_msg);
00079   }
00080   for (const auto& bucket : CountsByBucket()) {
00081     cartographer_ros_msgs::HistogramBucket bucket_msg;
00082     bucket_msg.bucket_boundary = bucket.first;
00083     bucket_msg.count = bucket.second;
00084     msg.counts_by_bucket.push_back(bucket_msg);
00085   }
00086   return msg;
00087 }
00088 
00089 }  // namespace metrics
00090 }  // namespace cartographer_ros


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