Public Member Functions | Protected Attributes | List of all members
cras::DiagnosedPublisher< Message, Enable > Class Template Reference

Wrapper for ROS publisher that automatically diagnoses the rate and delay of published messages. More...

#include <diagnosed_pub_sub.hpp>

Inheritance diagram for cras::DiagnosedPublisher< Message, Enable >:
Inheritance graph
[legend]

Public Member Functions

 DiagnosedPublisher (const ::ros::Publisher &pub, ::diagnostic_updater::Updater &updater, const ::cras::BoundParamHelperPtr &params)
 
 DiagnosedPublisher (const ::ros::Publisher &pub, ::diagnostic_updater::Updater &updater, const ::cras::BoundParamHelperPtr &params, const ::ros::Rate &defaultRate)
 
 DiagnosedPublisher (const ::ros::Publisher &pub, ::diagnostic_updater::Updater &updater, const ::cras::BoundParamHelperPtr &params, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate)
 
 DiagnosedPublisher (const ::ros::Publisher &pub, const ::cras::BoundParamHelperPtr &params)
 Add a topic diagnostic task to the publisher. More...
 
 DiagnosedPublisher (const ::ros::Publisher &pub, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam< Message > &defaultParams)
 Add a topic diagnostic task to the publisher. More...
 
 DiagnosedPublisher (const ::ros::Publisher &pub, const ::std::shared_ptr<::cras::TopicStatus< Message >> &diag)
 Add the given diagnostic task to the publisher. More...
 
 DiagnosedPublisher (const ::ros::Publisher &pub, const ::std::string &name, const ::cras::TopicStatusParam< Message > &diagParams)
 Add a topic diagnostic task to the publisher. More...
 
::ros::Rate getDesiredRate () const
 
::ros::PublishergetPublisher ()
 Get the ROS publisher. More...
 
const ::ros::PublishergetPublisher () const
 Get the ROS publisher. More...
 
virtual void publish (const Message &message)
 Publish a message. More...
 
virtual void publish (const typename Message::Ptr &message)
 Publish a message. More...
 
void setPublisher (const ::ros::Publisher &pub)
 Change the ROS publisher. More...
 
- Public Member Functions inherited from cras::DiagnosedPubSub< Message >
virtual void attach (::diagnostic_updater::Updater &updater)
 Add the diagnostic task to the given updater. More...
 
 DiagnosedPubSub (const ::cras::BoundParamHelperPtr &params)
 Configure the diagnostic task from the given ROS parameter helper. More...
 
 DiagnosedPubSub (const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam< Message > &defaultParams)
 Configure the diagnostic task from the given ROS parameter helper. More...
 
 DiagnosedPubSub (const ::std::shared_ptr<::cras::TopicStatus< Message >> &diag)
 Use the given diagnostic task to diagnose the publisher/subscriber. More...
 
 DiagnosedPubSub (const ::std::string &name, const ::cras::TopicStatusParam< Message > &diagParams)
 Create the diagnostic task from the given params. More...
 
virtual ::std::shared_ptr<::cras::TopicStatus< Message > > getDiagnosticTask () const
 Get the topic diagnostic task. More...
 
virtual ~DiagnosedPubSub ()=default
 

Protected Attributes

::ros::Publisher publisher
 The ROS publisher. More...
 
- Protected Attributes inherited from cras::DiagnosedPubSub< Message >
::std::shared_ptr<::cras::TopicStatus< Message > > diag
 The diagnostic task. More...
 

Additional Inherited Members

- Protected Member Functions inherited from cras::DiagnosedPubSub< Message >
void addDelayParams (::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr &params)
 When configuring from ROS params, load the delay configuration. More...
 
void addDelayParams (::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr &params)
 When configuring from ROS params for a headerless message type, this function does nothing. More...
 

Detailed Description

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
class cras::DiagnosedPublisher< Message, Enable >

Wrapper for ROS publisher that automatically diagnoses the rate and delay of published messages.

Template Parameters
MessageType of the published message.
EnableSFINAE only. Do not set explicitly.
Note
For the automatic diagnostics to work, you have to call the publish() method from this class, not the one from the ROS publisher.

Definition at line 136 of file diagnosed_pub_sub.hpp.

Constructor & Destructor Documentation

◆ DiagnosedPublisher() [1/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
const ::std::shared_ptr<::cras::TopicStatus< Message >> &  diag 
)

Add the given diagnostic task to the publisher.

Parameters
[in]pubThe ROS publisher.
[in]diagThe topic diagnostics task.

◆ DiagnosedPublisher() [2/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
const ::std::string &  name,
const ::cras::TopicStatusParam< Message > &  diagParams 
)

Add a topic diagnostic task to the publisher.

Parameters
[in]pubThe ROS publisher.
[in]nameName of the diagnostic task
[in]diagParamsParameters of the topic diagnostics task.

◆ DiagnosedPublisher() [3/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam< Message > &  defaultParams 
)

Add a topic diagnostic task to the publisher.

Parameters
[in]pubThe ROS publisher.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
See also
DiagnosedPubSub

◆ DiagnosedPublisher() [4/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
const ::cras::BoundParamHelperPtr params 
)

Add a topic diagnostic task to the publisher.

Parameters
[in]pubThe ROS publisher.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
See also
DiagnosedPubSub

◆ DiagnosedPublisher() [5/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
::diagnostic_updater::Updater updater,
const ::cras::BoundParamHelperPtr params 
)

◆ DiagnosedPublisher() [6/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
::diagnostic_updater::Updater updater,
const ::cras::BoundParamHelperPtr params,
const ::ros::Rate defaultRate 
)

◆ DiagnosedPublisher() [7/7]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedPublisher< Message, Enable >::DiagnosedPublisher ( const ::ros::Publisher pub,
::diagnostic_updater::Updater updater,
const ::cras::BoundParamHelperPtr params,
const ::ros::Rate defaultRate,
const ::ros::Rate defaultMinRate,
const ::ros::Rate defaultMaxRate 
)

Member Function Documentation

◆ getDesiredRate()

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::ros::Rate cras::DiagnosedPublisher< Message, Enable >::getDesiredRate ( ) const

◆ getPublisher() [1/2]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::ros::Publisher& cras::DiagnosedPublisher< Message, Enable >::getPublisher ( )

Get the ROS publisher.

Returns
The ROS publisher.

◆ getPublisher() [2/2]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
const ::ros::Publisher& cras::DiagnosedPublisher< Message, Enable >::getPublisher ( ) const

Get the ROS publisher.

Returns
The ROS publisher.

◆ publish() [1/2]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
virtual void cras::DiagnosedPublisher< Message, Enable >::publish ( const Message &  message)
virtual

Publish a message.

Parameters
[in]messageThe message to publish.

◆ publish() [2/2]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
virtual void cras::DiagnosedPublisher< Message, Enable >::publish ( const typename Message::Ptr &  message)
virtual

Publish a message.

Parameters
[in]messageThe message to publish.

◆ setPublisher()

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
void cras::DiagnosedPublisher< Message, Enable >::setPublisher ( const ::ros::Publisher pub)

Change the ROS publisher.

Parameters
[in]pubThe new ROS publisher.

Member Data Documentation

◆ publisher

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::ros::Publisher cras::DiagnosedPublisher< Message, Enable >::publisher
protected

The ROS publisher.

Definition at line 221 of file diagnosed_pub_sub.hpp.


The documentation for this class was generated from the following file:


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Mar 2 2024 03:47:35