Template Class DiagnosedPublisher

Inheritance Relationships

Base Type

Class Documentation

template<typename MessageT, typename AllocatorT = std::allocator<void>>
class DiagnosedPublisher : public diagnostic_updater::TopicDiagnostic

A TopicDiagnostic combined with a ros::Publisher.

For a standard ros::Publisher, this class allows the ros::Publisher and the TopicDiagnostic to be combined for added convenience.

Public Types

using PublisherT = rclcpp::Publisher<MessageT, AllocatorT>

Constructs a DiagnosedPublisher.

Param pub:

The publisher on which statistics are being collected.

Param diag:

The diagnostic_updater that the CompositeDiagnosticTask should add itself to.

Param freq:

The parameters for the FrequencyStatus class that will be computing statistics.

Param stamp:

The parameters for the TimeStampStatus class that will be computing statistics.

Public Functions

inline DiagnosedPublisher(const typename PublisherT::SharedPtr &pub, diagnostic_updater::Updater &diag, const diagnostic_updater::FrequencyStatusParam &freq, const diagnostic_updater::TimeStampStatusParam &stamp)
inline virtual ~DiagnosedPublisher()
inline virtual void publish(typename PublisherT::MessageUniquePtr message)

Collects statistics and publishes the message.

The timestamp to be used by the TimeStampStatus class will be extracted from message.header.stamp.

inline virtual void publish(const MessageT &message)

Collects statistics and publishes the message.

The timestamp to be used by the TimeStampStatus class will be extracted from message.header.stamp.

inline PublisherT::SharedPtr getPublisher() const

Returns the publisher.

inline void setPublisher(typename PublisherT::SharedPtr pub)

Changes the publisher.