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

Base for ROS publisher and subscriber with automatic message rate and delay diagnostics. More...

#include <diagnosed_pub_sub.hpp>

Public Member Functions

virtual void attach (::diagnostic_updater::Updater &updater)
 Add the diagnostic task to the given updater. 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...
 
 DiagnosedPubSub (const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam< Message > &defaultParams)
 Configure the diagnostic task from the given ROS parameter helper. More...
 
 DiagnosedPubSub (const ::cras::BoundParamHelperPtr &params)
 Configure the diagnostic task from the given ROS parameter helper. More...
 
virtual ::std::shared_ptr<::cras::TopicStatus< Message > > getDiagnosticTask () const
 Get the topic diagnostic task. More...
 
virtual ~DiagnosedPubSub ()=default
 

Protected Member Functions

template<class M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader< M >::value, bool > EnableM = true>
void addDelayParams (::cras::SimpleTopicStatusParam< Message > &topicStatusParam, const ::cras::BoundParamHelperPtr &params)
 When configuring from ROS params, load the delay configuration. More...
 
template<class M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader< M >::value, bool > EnableM = true>
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...
 

Protected Attributes

::std::shared_ptr<::cras::TopicStatus< Message > > diag {nullptr}
 The diagnostic task. More...
 

Detailed Description

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

Base for ROS publisher and subscriber with automatic message rate and delay diagnostics.

This class offers an option to configure the diagnostic task from a set of ROS parameters. The following parameters are read:

Template Parameters
MessageType of the published/subscribed message.
EnableSFINAE only. Do not explicitly set.

Definition at line 57 of file diagnosed_pub_sub.hpp.

Constructor & Destructor Documentation

◆ DiagnosedPubSub() [1/4]

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

Use the given diagnostic task to diagnose the publisher/subscriber.

Parameters
[in]diag

◆ DiagnosedPubSub() [2/4]

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

Create the diagnostic task from the given params.

Parameters
[in]nameName of the task.
[in]diagParamsParameters of the task.

◆ DiagnosedPubSub() [3/4]

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

Configure the diagnostic task from the given ROS parameter helper.

Parameters
[in]paramsThe ROS parameters to load configuration from.
[in]defaultParamsDefaults used in case a ROS parameter doesn' exist.

◆ DiagnosedPubSub() [4/4]

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

Configure the diagnostic task from the given ROS parameter helper.

Parameters
[in]paramsThe ROS parameters to load configuration from.

◆ ~DiagnosedPubSub()

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
virtual cras::DiagnosedPubSub< Message, Enable >::~DiagnosedPubSub ( )
virtualdefault

Member Function Documentation

◆ addDelayParams() [1/2]

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<class M = Message, ::std::enable_if_t<::ros::message_traits::HasHeader< M >::value, bool > EnableM = true>
void cras::DiagnosedPubSub< Message, Enable >::addDelayParams ( ::cras::SimpleTopicStatusParam< Message > &  topicStatusParam,
const ::cras::BoundParamHelperPtr params 
)
protected

When configuring from ROS params, load the delay configuration.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]topicStatusParamSome pre-loaded param struct.
[in]paramsParameters to load from?

◆ addDelayParams() [2/2]

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<class M = Message, ::std::enable_if_t<!::ros::message_traits::HasHeader< M >::value, bool > EnableM = true>
void cras::DiagnosedPubSub< Message, Enable >::addDelayParams ( ::cras::SimpleTopicStatusParam< Message > &  topicStatusParam,
const ::cras::BoundParamHelperPtr params 
)
protected

When configuring from ROS params for a headerless message type, this function does nothing.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]topicStatusParamSome pre-loaded param struct.
[in]paramsParameters to load from?

◆ attach()

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
virtual void cras::DiagnosedPubSub< Message, Enable >::attach ( ::diagnostic_updater::Updater updater)
virtual

Add the diagnostic task to the given updater.

Parameters
[in]updaterThe updater to add to.

◆ getDiagnosticTask()

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
virtual ::std::shared_ptr<::cras::TopicStatus<Message> > cras::DiagnosedPubSub< Message, Enable >::getDiagnosticTask ( ) const

Get the topic diagnostic task.

Returns
The task.

Member Data Documentation

◆ diag

template<class Message, typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::shared_ptr<::cras::TopicStatus<Message> > cras::DiagnosedPubSub< Message, Enable >::diag {nullptr}
protected

The diagnostic task.

Definition at line 125 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 Jun 17 2023 02:32:53