.. _program_listing_file_include_libstatistics_collector_topic_statistics_collector_received_message_age.hpp: Program Listing for File received_message_age.hpp ================================================= |exhale_lsh| :ref:`Return to documentation for file ` (``include/libstatistics_collector/topic_statistics_collector/received_message_age.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // 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_AGE_HPP_ #define LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_AGE_HPP_ #include #include #include #include #include #include "constants.hpp" #include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp" #include "builtin_interfaces/msg/time.hpp" #include "rcl/time.h" #include "rcutils/logging_macros.h" namespace libstatistics_collector { namespace topic_statistics_collector { template struct HasHeader : public std::false_type {}; template struct HasHeader::value>::type>: public std::true_type {}; template struct TimeStamp { static std::pair value(const M &) { return std::make_pair(false, 0); } }; template struct TimeStamp::value>::type> { static std::pair value(const M & m) { const auto stamp = m.header.stamp; const auto nanos = RCL_S_TO_NS(static_cast(stamp.sec)) + stamp.nanosec; return std::make_pair(true, nanos); } }; template class ReceivedMessageAgeCollector : public TopicStatisticsCollector { public: ReceivedMessageAgeCollector() = default; virtual ~ReceivedMessageAgeCollector() = default; void OnMessageReceived( const T & received_message, const rcl_time_point_value_t now_nanoseconds) override { const auto timestamp_from_header = TimeStamp::value(received_message); if (timestamp_from_header.first) { // only compare if non-zero if (timestamp_from_header.second && now_nanoseconds) { const std::chrono::nanoseconds age_nanos{now_nanoseconds - timestamp_from_header.second}; const auto age_millis = std::chrono::duration(age_nanos); collector::Collector::AcceptData(static_cast(age_millis.count())); } // else no valid time to compute age } } std::string GetMetricName() const override { return topic_statistics_constants::kMsgAgeStatName; } std::string GetMetricUnit() const override { return topic_statistics_constants::kMillisecondUnitName; } protected: bool SetupStart() override { return true; } bool SetupStop() override { return true; } }; } // namespace topic_statistics_collector } // namespace libstatistics_collector #endif // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_AGE_HPP_