Program Listing for File received_message_period.hpp

Return to documentation for file (include/libstatistics_collector/topic_statistics_collector/received_message_period.hpp)

// 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 LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
#define LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_

#include <chrono>
#include <mutex>
#include <string>

#include "constants.hpp"
#include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp"

#include "rcl/time.h"

namespace libstatistics_collector
{
namespace topic_statistics_collector
{

constexpr const int64_t kUninitializedTime{0};

template<typename T>
class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
{
public:
  ReceivedMessagePeriodCollector()
  {
    ResetTimeLastMessageReceived();
  }

  virtual ~ReceivedMessagePeriodCollector() = default;

  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_};

    (void) received_message;

    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<double, std::milli>(nanos);
      time_last_message_received_ = now_nanoseconds;
      collector::Collector::AcceptData(static_cast<double>(period.count()));
    }
  }

  std::string GetMetricName() const override
  {
    return topic_statistics_constants::kMsgPeriodStatName;
  }

  std::string GetMetricUnit() const override
  {
    return topic_statistics_constants::kMillisecondUnitName;
  }

protected:
  bool SetupStart() override
  {
    ResetTimeLastMessageReceived();
    return true;
  }

  bool SetupStop() override
  {
    return true;
  }

private:
  void ResetTimeLastMessageReceived()
  {
    time_last_message_received_ = kUninitializedTime;
  }

  rcl_time_point_value_t time_last_message_received_ RCPPUTILS_TSA_GUARDED_BY(mutex_) =
    kUninitializedTime;
  mutable std::mutex mutex_;
};

}  // namespace topic_statistics_collector
}  // namespace libstatistics_collector

#endif  // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_