Template Class ReceivedMessageAgeCollector< rmw_message_info_t, std::enable_if_t< std::is_same< rmw_message_info_t, rmw_message_info_t >::value > >
Defined in File received_message_age.hpp
Inheritance Relationships
Base Type
public libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector<>
(Template Class TopicStatisticsCollector)
Class Documentation
-
template<>
class ReceivedMessageAgeCollector<rmw_message_info_t, std::enable_if_t<std::is_same<rmw_message_info_t, rmw_message_info_t>::value>> : public libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector<> Class used to measure the received message age from a ROS2 subscriber.
Public Functions
-
ReceivedMessageAgeCollector() = default
-
~ReceivedMessageAgeCollector() override = default
-
inline void OnMessageReceived(const rmw_message_info_t &message_info, const rcl_time_point_value_t now_nanoseconds) override
Handle a new incoming message. Calculate message age if timestamps in message info are valid.
- Parameters:
message_info – the message information of the received message.
now_nanoseconds – time the message was received in nanoseconds
-
inline virtual std::string GetMetricName() const override
Return message age metric name
- Returns:
a string representing message age metric name
-
inline virtual std::string GetMetricUnit() const override
Return message age metric unit
- Returns:
a string representing message age metric unit
Protected Functions
-
inline virtual bool SetupStart() override
Override in order to perform necessary starting steps.
- Returns:
true if setup was successful, false otherwise.
-
inline virtual bool SetupStop() override
Override in order to perform necessary teardown.
- Returns:
true if teardown was successful, false otherwise.
-
ReceivedMessageAgeCollector() = default