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

Wrapper for ROS subscriber that automatically diagnoses the rate and delay of received messages. More...

#include <diagnosed_pub_sub.hpp>

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

Public Member Functions

 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam< Message > &defaultParams, ::ros::SubscribeOptions &options)
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam< Message > &defaultParams, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &cb, ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
template<typename C , typename EnableC = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultParams, const ::std::string &topic, uint32_t queue_size, const ::boost::function< void(C)> &cb, ::ros::VoidConstPtr obj={}, ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
template<typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), const ::boost::shared_ptr< T > &obj, ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
 DiagnosedSubscriber (::ros::NodeHandle nh, const ::cras::BoundParamHelperPtr &params, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultParams, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic reading diagnostic task configuration from ROS parameters. More...
 
::ros::SubscribergetSubscriber ()
 Get the created ROS subscriber. More...
 
const ::ros::SubscribergetSubscriber () const
 Get the created ROS subscriber. 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 Member Functions

::boost::function< void(const ::ros::MessageEvent< Message > &)> addTick (const ::std::function< void(const ::ros::MessageEvent< Message > &)> &fn)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
::boost::function< void(const Message &)> addTick (const ::std::function< void(const Message &)> &fn)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
::boost::function< void(const typename Message::Ptr &)> addTick (const ::std::function< void(const typename Message::Ptr &)> &fn)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function< void(M)> addTick (const ::std::function< void(M)> &fn, T)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function< void(M)> addTick (void(T::*fn)(M) const, const ::boost::shared_ptr< T > &obj)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function< void(M)> addTick (void(T::*fn)(M) const, T *obj)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function< void(M)> addTick (void(T::*fn)(M), const ::boost::shared_ptr< T > &obj)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function< void(M)> addTick (void(T::*fn)(M), T *obj)
 Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn(). More...
 
- 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...
 

Protected Attributes

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

Detailed Description

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

Wrapper for ROS subscriber that automatically diagnoses the rate and delay of received messages.

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

Definition at line 230 of file diagnosed_pub_sub.hpp.

Constructor & Destructor Documentation

◆ DiagnosedSubscriber() [1/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
void(*)(M)  cb,
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [2/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam< Message > &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &  cb,
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [3/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename C , typename EnableC = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
const ::boost::function< void(C)> &  cb,
::ros::VoidConstPtr  obj = {},
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Template Parameters
CSFINAE only. Do not set explicitly.
EnableCSFINAE only. Do not set explicitly.
Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]objTracked object for the subscriber.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [4/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M)  cb,
T *  obj,
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]objTracked object for the subscriber and on which the callback will be called.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [5/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M) const  cb,
T *  obj,
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]objTracked object for the subscriber and on which the callback will be called.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [6/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M)  cb,
const ::boost::shared_ptr< T > &  obj,
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]objTracked object for the subscriber and on which the callback will be called.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [7/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename M , class T , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
cras::DiagnosedSubscriber< Message, Enable >::DiagnosedSubscriber ( ::ros::NodeHandle  nh,
const ::cras::BoundParamHelperPtr params,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultParams,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M) const  cb,
const ::boost::shared_ptr< T > &  obj,
::ros::TransportHints  hints = {} 
)

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Template Parameters
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]topicName of the topic to subscribe.
[in]queue_sizeQueue size of the subscriber.
[in]cbThe message callback.
[in]objTracked object for the subscriber and on which the callback will be called.
[in]hintsConnection hints.

◆ DiagnosedSubscriber() [8/8]

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

Subscribe to the given topic reading diagnostic task configuration from ROS parameters.

Parameters
[in]nhNode handle used for subscribing.
[in]paramsROS parameters from which the configuration of the diagnostic task is taken.
[in]defaultParamsDefault parameters used when no ROS parameter exists.
[in]optionsSubscribe options.
Note
This constructor will "wrap" the callback specified in options to automatically trigger the diagnostic task when a message is received.

Member Function Documentation

◆ addTick() [1/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::boost::function<void(const ::ros::MessageEvent<Message>&)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( const ::std::function< void(const ::ros::MessageEvent< Message > &)> &  fn)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Parameters
[in]fnThe function to wrap.
Returns
The wrapping function.

◆ addTick() [2/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::boost::function<void(const Message&)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( const ::std::function< void(const Message &)> &  fn)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Parameters
[in]fnThe function to wrap.
Returns
The wrapping function.

◆ addTick() [3/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::boost::function<void(const typename Message::Ptr&)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( const ::std::function< void(const typename Message::Ptr &)> &  fn)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Parameters
[in]fnThe function to wrap.
Returns
The wrapping function.

◆ addTick() [4/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function<void(M)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( const ::std::function< void(M)> &  fn,
 
)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Template Parameters
TIgnored.
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]fnThe function to wrap.
Returns
The wrapping function.

◆ addTick() [5/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function<void(M)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( void(T::*)(M) const  fn,
const ::boost::shared_ptr< T > &  obj 
)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Template Parameters
TIgnored.
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]fnThe function to wrap.
[in]objTracked object for the subscriber and on which the callback will be called.
Returns
The wrapping function.

◆ addTick() [6/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function<void(M)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( void(T::*)(M) const  fn,
T *  obj 
)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Template Parameters
TIgnored.
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]fnThe function to wrap.
[in]objTracked object for the subscriber and on which the callback will be called.
Returns
The wrapping function.

◆ addTick() [7/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function<void(M)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( void(T::*)(M)  fn,
const ::boost::shared_ptr< T > &  obj 
)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Template Parameters
TIgnored.
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]fnThe function to wrap.
[in]objTracked object for the subscriber and on which the callback will be called.
Returns
The wrapping function.

◆ addTick() [8/8]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
template<typename T , typename M , typename EnableM = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::boost::function<void(M)> cras::DiagnosedSubscriber< Message, Enable >::addTick ( void(T::*)(M)  fn,
T *  obj 
)
protected

Wrap fn in a function that first calls tick() on the diagnostic task and then calls fn().

Template Parameters
TIgnored.
MSFINAE only. Do not set explicitly.
EnableMSFINAE only. Do not set explicitly.
Parameters
[in]fnThe function to wrap.
[in]objTracked object for the subscriber and on which the callback will be called.
Returns
The wrapping function.

◆ getSubscriber() [1/2]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::ros::Subscriber& cras::DiagnosedSubscriber< Message, Enable >::getSubscriber ( )

Get the created ROS subscriber.

Returns
The ROS subscriber.

◆ getSubscriber() [2/2]

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
const ::ros::Subscriber& cras::DiagnosedSubscriber< Message, Enable >::getSubscriber ( ) const

Get the created ROS subscriber.

Returns
The ROS subscriber.

Member Data Documentation

◆ subscriber

template<class Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::ros::Subscriber cras::DiagnosedSubscriber< Message, Enable >::subscriber
protected

The ROS subscriber.

Definition at line 466 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