Template Class TopicStatus

Inheritance Relationships

Base Type

  • public diagnostic_updater::CompositeDiagnosticTask

Class Documentation

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
class TopicStatus : public diagnostic_updater::CompositeDiagnosticTask

Diagnostic task for topic frequency and timestamp delay (combining FrequencyStatus and TimeStampStatus tasks).

Template Parameters:

Message – Type of the message. If it contains a header field, the task will automatically check both frequency and timestamp delay. Header-less messages will only have their frequency checked.

Public Functions

template<typename M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader<M>::value, bool> = true>
inline TopicStatus(const ::std::string &name, const ::cras::TopicStatusParam<Message> &params)

Create the diagnostic task for a header-less message (checking frequency only).

Template Parameters:

M – SFINAE only. Do not set explicitly.

Parameters:
  • name[in] Name of the diagnostic task.

  • params[in] Parameters of the task.

template<typename M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader<M>::value, bool> = true>
inline explicit TopicStatus(const ::std::string &name, const double minRate = 0.0, const double maxRate = ::std::numeric_limits<double>::infinity(), const double rateTolerance = 0.1, const int rateWindowSize = 5)

Create the diagnostic task for a header-less message (checking frequency only).

Template Parameters:

M – SFINAE only. Do not set explicitly.

Parameters:
  • name[in] Name of the diagnostic task.

  • minRate[in] Minimum allowed frequency.

  • maxRate[in] Maximum allowed frequency.

  • rateTolerance[in] Tolerance of the rate.

  • rateWindowSize[in] Number of updates during which the frequency is computed.

template<typename M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value, bool> = true>
inline TopicStatus(const ::std::string &name, const ::cras::TopicStatusParam<Message> &params)

Create the diagnostic task for a message with header (checking frequency and timestamp delay).

Template Parameters:

M – SFINAE only. Do not set explicitly.

Parameters:
  • name[in] Name of the diagnostic task.

  • params[in] Parameters of the task.

template<typename M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value, bool> = true>
inline explicit TopicStatus(const ::std::string &name, const double minRate = 0.0, const double maxRate = ::std::numeric_limits<double>::infinity(), const double rateTolerance = 0.1, const int rateWindowSize = 5, const double minDelay = -1.0, const double maxDelay = 5.0)

Create the diagnostic task for a message with header (checking frequency and timestamp delay).

Template Parameters:

M – SFINAE only. Do not set explicitly.

Parameters:
  • name[in] Name of the diagnostic task.

  • minRate[in] Minimum allowed frequency.

  • maxRate[in] Maximum allowed frequency.

  • rateTolerance[in] Tolerance of the rate.

  • rateWindowSize[in] Number of updates during which the frequency is computed.

  • minDelay[in] Min acceptable delay (in s). It can be negative if timestamps in future are expected.

  • maxDelay[in] Max acceptable delay (in s). It can be negative if timestamps in future are expected.

inline TopicStatus(const ::std::string &name, const ::cras::SimpleTopicStatusParam<Message> &params)

Create the diagnostic task checking frequency of messages and timestamp delay (if the message has header).

Parameters:
  • name[in] Name of the diagnostic task.

  • params[in] Parameters of the task.

inline ~TopicStatus() override
inline virtual void tick(const ::ros::Time &stamp)

Record that a message has arrived now with the given timestamp.

Parameters:

stamp[in] Timestamp in the message header.

inline virtual void tick(const Message &message)

Record that a message has arrived.

Parameters:

message[in] The message that arrived.

inline virtual void tick(const typename Message::Ptr &message)

Record that a message has arrived.

Parameters:

message[in] The message that arrived.

inline virtual void tick(const typename Message::ConstPtr &message)

Record that a message has arrived.

Parameters:

message[in] The message that arrived.

inline virtual void tick(const ::ros::MessageEvent<Message> &event)

Record that a message has arrived.

Parameters:

event[in] The message event describing the message that arrived.

inline ::ros::Rate getExpectedRate() const

Get the expected/average rate. If min and max are the same, their value will be returned. If min rate is non-positive, the max rate is returned. Otherwise, if max rate is infinite, the min rate will be returned. If min is positive and max is finite, their arithmetic mean is returned.

Returns:

The expected rate (in Hz).

inline ::ros::Rate getMinRate() const

Minimum allowed frequency.

Returns:

The frequency (in Hz).

inline ::ros::Rate getMaxRate() const

Maximum allowed frequency.

Returns:

The frequency (in Hz).

inline double getRateTolerance() const

Tolerance of frequency.

Returns:

The tolerance (0.0 means exact match of the frequency bounds).

inline int getRateWindowSize() const

Number of updates during which the frequency is computed.

Returns:

The window size.

template<typename M = Message, typename = ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value>>
inline ::ros::Duration getMinDelay() const

Min acceptable delay (in s). It can be negative if timestamps in future are expected.

Template Parameters:

M – SFINAE only. Do not set explicitly.

Returns:

The minimum delay.

template<typename M = Message, typename = ::std::enable_if_t<::ros::message_traits::HasHeader<M>::value>>
inline ::ros::Duration getMaxDelay() const

Max acceptable delay (in s). It can be negative if timestamps in future are expected.

Template Parameters:

M – SFINAE only. Do not set explicitly.

Returns:

The maximum delay.

Protected Attributes

::std::unique_ptr<::diagnostic_updater::FrequencyStatus> freqTask

The frequency-checking diagnostic task. This will always be non-null.

::std::unique_ptr<::diagnostic_updater::SlowTimeStampStatus> stampTask

The delay-checking diagnostic task. It will be non-null only for messages with header.

::cras::TopicStatusParam<Message> origParams

The parameters via which this task has been configured.