Public Member Functions | Protected Member Functions | Private Attributes | List of all members
cras::NodeletWithDiagnostics< NodeletType > Struct Template Reference

Nodelet mixin that provides helper functions for running a diagnostics updater. More...

#include <nodelet_with_diagnostics.hpp>

Inheritance diagram for cras::NodeletWithDiagnostics< NodeletType >:
Inheritance graph
[legend]

Public Member Functions

 NodeletWithDiagnostics ()
 
virtual ~NodeletWithDiagnostics ()
 

Protected Member Functions

template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &diagNamespace, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ::ros::NodeHandle diagNh, ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (::ros::NodeHandle publisherNh, ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (const ::std::string &topic, size_t queueSize, bool latch=false)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher< Message > > advertiseDiagnosed (ros::AdvertiseOptions &options)
 Advertise a topic and setup up an automatic topic diagnostic task for it. More...
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(const ::std::string &diagNamespace,), CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,), CRAS_SINGLE_ARG(subscriberNh, diagNh,), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,), CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, ""),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
 CRAS_NODELET_DIAG_GENERATE_OVERLOADS (CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG(this->getNodeHandle(),), CRAS_SINGLE_ARG(), CRAS_SINGLE_ARG("",))
 
template<typename T >
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace, const ::ros::Rate &defaultRate, const ::ros::Rate &defaultMinRate, const ::ros::Rate &defaultMaxRate)
 Create a diagnosed publisher for a message type without header. More...
 
template<typename T >
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace, const ::ros::Rate &defaultRate)
 Create a diagnosed publisher for a message type with header. More...
 
template<typename T >
::std::unique_ptr<::cras::DiagnosedPublisher< T > > createDiagnosedPublisher (::ros::NodeHandle nh, const ::std::string &topic, size_t queueSize, const ::std::string &paramNamespace)
 Create a diagnosed publisher for a message type with header. More...
 
::ros::NodeHandle getDefaultDiagNh (const ::ros::NodeHandle &pubSubNh, const ::std::string &diagNamespace)
 Get the default node handle for reading diagnostic task configuration. More...
 
::cras::BoundParamHelperPtr getDiagParams (const ::ros::NodeHandle &nh, const ::std::string &diagNamespace, const ::std::string &topic)
 Get the parameters configuring a diagnosed publisher or subscriber. More...
 
::cras::DiagnosticUpdatergetDiagUpdater (bool forceNew=false) const
 Get a diagnostic updater to be used with this nodelet. More...
 
void startDiagTimer () const
 Start periodic updates of the diagnostics updater. More...
 
void startDiagTimer (const ::ros::NodeHandle &nh) const
 Start periodic updates of the diagnostics updater. More...
 
void stopDiagTimer () const
 Stop the automatic updates of the diagnostic updater. More...
 
template<typename M , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(*cb)(M), ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, 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, automatically updating the diagnostic task every time a message is received. More...
 
template<typename C , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< C > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &defaultDiagParams, const ::std::string &diagNamespace, 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, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M), T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, uint32_t queue_size, void(T::*cb)(M) const, T *obj, ::ros::TransportHints hints={})
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, 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, automatically updating the diagnostic task every time a message is received. More...
 
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage< M > > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace, 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, automatically updating the diagnostic task every time a message is received. More...
 
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber< Message > > subscribeDiagnosed (::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh, const ::cras::SimpleTopicStatusParam< Message > &defaultDiagParams, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)
 Subscribe to the given topic, automatically updating the diagnostic task every time a message is received. More...
 

Private Attributes

::std::unique_ptr<::cras::impl::NodeletWithDiagnosticsPrivate > data
 PIMPL. More...
 

Detailed Description

template<typename NodeletType>
struct cras::NodeletWithDiagnostics< NodeletType >

Nodelet mixin that provides helper functions for running a diagnostics updater.

Template Parameters
NodeletTypeType of the base nodelet.

Methods advertiseDiagnosed() and subscribeDiagnosed() offer a versatile API based on the API of NodeHandle. Additional required arguments like node handles or diagnostic task configuration are prepended to the list of usual arguments of advertise()/subscribe(). All of these additional arguments are optional (which is achieved by providing a lot of overrides of the functions).

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

The parameter namespace from which the parameters are read is determined as follows:

Whenever the topic name is used in the topic diagnostic configuration namespace, the name of the topic is not affected by topic remappings passed to the nodelet (but its parent namespaces are affected).

Here are a few examples:

    // nodelet name is "nodelet"
    ros::NodeHandle nh = this->getNodeHandle();
    ros::NodeHandle pnh = this->getPrivateNodeHandle();
    ros::NodeHandle tnh(nh, "test");
    ros::NodeHandle rnh(nh, "", {{"/topic", "/topic2"}});  // remap /topic->/topic2
    this->advertiseDiagnosed(nh, "topic", 10);  // param namespace is /nodelet/topic
    this->advertiseDiagnosed(nh, "/topic", 10);  // param namespace is /topic
    this->advertiseDiagnosed(nh, "test", "topic", 10);  // param namespace is /test
    this->advertiseDiagnosed(nh, "~test", "topic", 10);  // param namespace is /nodelet/test
    this->advertiseDiagnosed(nh, pnh, "topic", 10);  // param namespace is /nodelet/topic
    this->advertiseDiagnosed(nh, pnh, "test", "topic", 10);  // param namespace is /nodelet/test
    this->advertiseDiagnosed(nh, pnh, "~test", "topic", 10);  // param namespace is /nodelet/test
    this->advertiseDiagnosed(pnh, "topic", 10);  // param namespace is /nodelet/topic
    this->advertiseDiagnosed(pnh, "/topic", 10);  // param namespace is /topic
    this->advertiseDiagnosed(pnh, "test", "topic", 10);  // param namespace is /nodelet/test
    this->advertiseDiagnosed(pnh, "~test", "topic", 10);  // param namespace is /nodelet/test
    this->advertiseDiagnosed(pnh, tnh, "topic", 10);  // param namespace is /test/topic
    this->advertiseDiagnosed(pnh, tnh, "test", "topic", 10);  // param namespace is /test/test
    this->advertiseDiagnosed(pnh, tnh, "~test", "topic", 10);  // param namespace is /test/test
    this->advertiseDiagnosed(tnh, "topic", 10);  // param namespace is /test/topic
    this->advertiseDiagnosed(tnh, "/topic", 10);  // param namespace is /topic
    this->advertiseDiagnosed(tnh, "test", "topic", 10);  // param namespace is /test/test
    this->advertiseDiagnosed(tnh, "~test", "topic", 10);  // param namespace is /test/test
    this->advertiseDiagnosed(rnh, "topic", 10);  // subscribes /topic2, param namespace is /nodelet/topic
    this->advertiseDiagnosed(rnh, "/topic", 10);  // subscribes /topic2, param namespace is /topic
  

Definition at line 104 of file nodelet_with_diagnostics.hpp.

Constructor & Destructor Documentation

◆ NodeletWithDiagnostics()

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::NodeletWithDiagnostics ( )

◆ ~NodeletWithDiagnostics()

template<typename NodeletType>
virtual cras::NodeletWithDiagnostics< NodeletType >::~NodeletWithDiagnostics ( )
virtual

Member Function Documentation

◆ advertiseDiagnosed() [1/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [2/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
::ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in,out]optionsTopic advertise options.
Returns
The publisher object.

◆ advertiseDiagnosed() [3/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in]topicThe topic to subscribe to.
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [4/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
::ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in,out]optionsTopic advertise options.
Returns
The publisher object.

◆ advertiseDiagnosed() [5/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in]topicThe topic to subscribe to (relative to public node handle of the nodelet).
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [6/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
::ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in,out]optionsTopic advertise options (topic is relative to public node handle of the nodelet).
Returns
The publisher object.

◆ advertiseDiagnosed() [7/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
::ros::NodeHandle  diagNh,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle used for the publisher of messages.
[in]diagNhNode handle used for configuration of the diagnostics.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in]topicThe topic to subscribe to (relative to public node handle of the nodelet).
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [8/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
::ros::NodeHandle  diagNh,
const ::std::string &  diagNamespace,
::ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle used for the publisher of messages.
[in]diagNhNode handle used for configuration of the diagnostics.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in,out]optionsTopic advertise options (topic is relative to public node handle of the nodelet).
Returns
The publisher object.

◆ advertiseDiagnosed() [9/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in]topicThe topic to subscribe to.
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [10/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
const ::std::string &  diagNamespace,
::ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in,out]optionsTopic advertise options.
Returns
The publisher object.

◆ advertiseDiagnosed() [11/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( const ::std::string &  diagNamespace,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in]topicThe topic to subscribe to (relative to public node handle of the nodelet).
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [12/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( const ::std::string &  diagNamespace,
::ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched (using the private node handle of the nodelet).
[in,out]optionsTopic advertise options (topic is relative to public node handle of the nodelet).
Returns
The publisher object.

◆ advertiseDiagnosed() [13/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
::ros::NodeHandle  diagNh,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]diagNhNode handle to use for reading parameters of the diagnostic task (namespace is same as topic).
[in]topicThe topic to subscribe to.
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.

◆ advertiseDiagnosed() [14/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
::ros::NodeHandle  diagNh,
ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]diagNhNode handle to use for reading parameters of the diagnostic task (namespace is same as topic).
[in,out]optionsTopic advertise options.
Returns
The publisher object.

◆ advertiseDiagnosed() [15/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in]topicThe topic to subscribe to.
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.
Note
Diagnostic task config is read from ~topic namespace (with topic not remapped).

◆ advertiseDiagnosed() [16/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ::ros::NodeHandle  publisherNh,
ros::AdvertiseOptions options 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]publisherNhNode handle to use for setting up the publisher.
[in,out]optionsTopic advertise options.
Returns
The publisher object.
Note
Diagnostic task config is read from ~topic namespace (with topic not remapped).

◆ advertiseDiagnosed() [17/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( const ::std::string &  topic,
size_t  queueSize,
bool  latch = false 
)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in]topicThe topic to subscribe to (relative to public node handle of the nodelet).
[in]queueSizeSize of the subscription queue.
[in]latchWhether the topic should be latched.
Returns
The publisher object.
Note
Diagnostic task config is read from ~topic namespace (with topic not remapped).

◆ advertiseDiagnosed() [18/18]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedPublisher<Message> > cras::NodeletWithDiagnostics< NodeletType >::advertiseDiagnosed ( ros::AdvertiseOptions options)
protected

Advertise a topic and setup up an automatic topic diagnostic task for it.

Template Parameters
MessageThe published message type.
EnableSFINAE only. Do not explicitly set.
Parameters
[in,out]optionsTopic advertise options.
Returns
The publisher object.
Note
Diagnostic task config is read from ~topic namespace (with topic not remapped).

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [1/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,)  ,
CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),)  ,
CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,)  ,
CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [2/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG()  ,
CRAS_SINGLE_ARG(this->getNodeHandle(),)  ,
CRAS_SINGLE_ARG(const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &defaultDiagParams, const ::std::string &diagNamespace,)  ,
CRAS_SINGLE_ARG(defaultDiagParams, diagNamespace,)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [3/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,)  ,
CRAS_SINGLE_ARG(subscriberNh, diagNh,)  ,
CRAS_SINGLE_ARG(const ::std::string &diagNamespace,)  ,
CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [4/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,)  ,
CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, diagNamespace),)  ,
CRAS_SINGLE_ARG(const ::std::string &diagNamespace,)  ,
CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [5/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG()  ,
CRAS_SINGLE_ARG(this->getNodeHandle(),)  ,
CRAS_SINGLE_ARG(const ::std::string &diagNamespace,)  ,
CRAS_SINGLE_ARG(::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >>(), diagNamespace,)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [6/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh, ::ros::NodeHandle diagNh,)  ,
CRAS_SINGLE_ARG(subscriberNh, diagNh,)  ,
CRAS_SINGLE_ARG()  ,
CRAS_SINGLE_ARG("",)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [7/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG(::ros::NodeHandle subscriberNh,)  ,
CRAS_SINGLE_ARG(subscriberNh, this->getDefaultDiagNh(subscriberNh, ""),)  ,
CRAS_SINGLE_ARG()  ,
CRAS_SINGLE_ARG("",)   
)
protected

◆ CRAS_NODELET_DIAG_GENERATE_OVERLOADS() [8/8]

template<typename NodeletType>
cras::NodeletWithDiagnostics< NodeletType >::CRAS_NODELET_DIAG_GENERATE_OVERLOADS ( CRAS_SINGLE_ARG()  ,
CRAS_SINGLE_ARG(this->getNodeHandle(),)  ,
CRAS_SINGLE_ARG()  ,
CRAS_SINGLE_ARG("",)   
)
protected

◆ createDiagnosedPublisher() [1/3]

template<typename NodeletType>
template<typename T >
::std::unique_ptr<::cras::DiagnosedPublisher<T> > cras::NodeletWithDiagnostics< NodeletType >::createDiagnosedPublisher ( ::ros::NodeHandle  nh,
const ::std::string &  topic,
size_t  queueSize,
const ::std::string &  paramNamespace,
const ::ros::Rate defaultRate,
const ::ros::Rate defaultMinRate,
const ::ros::Rate defaultMaxRate 
)
protected

Create a diagnosed publisher for a message type without header.

Template Parameters
TType of the published data.
Parameters
[in]nhNode handle for which the publisher should be created.
[in]topicTopic to publish to.
[in]queueSizeQueue size.
[in]paramNamespaceNamespace in private parameters of this nodelet where configuration of the diagnostics is stored. Params are: rate/desired, rate/max, rate/min, rate/tolerance, rate/window_size.
[in]defaultRateDefault expected rate.
[in]defaultMinRateDefault minimum rate.
[in]defaultMaxRateDefault maximum rate.
Returns
The publisher with diagnostics.

◆ createDiagnosedPublisher() [2/3]

template<typename NodeletType>
template<typename T >
::std::unique_ptr<::cras::DiagnosedPublisher<T> > cras::NodeletWithDiagnostics< NodeletType >::createDiagnosedPublisher ( ::ros::NodeHandle  nh,
const ::std::string &  topic,
size_t  queueSize,
const ::std::string &  paramNamespace,
const ::ros::Rate defaultRate 
)
protected

Create a diagnosed publisher for a message type with header.

Template Parameters
TType of the published data.
Parameters
[in]nhNode handle for which the publisher should be created.
[in]topicTopic to publish to.
[in]queueSizeQueue size.
[in]paramNamespaceNamespace in private parameters of this nodelet where configuration of the diagnostics is stored. Params are: rate/desired, rate/max, rate/min, rate/tolerance, rate/window_size, delay/min, delay/max.
[in]defaultRateDefault expected rate.
Returns
The publisher with diagnostics.

◆ createDiagnosedPublisher() [3/3]

template<typename NodeletType>
template<typename T >
::std::unique_ptr<::cras::DiagnosedPublisher<T> > cras::NodeletWithDiagnostics< NodeletType >::createDiagnosedPublisher ( ::ros::NodeHandle  nh,
const ::std::string &  topic,
size_t  queueSize,
const ::std::string &  paramNamespace 
)
protected

Create a diagnosed publisher for a message type with header.

Template Parameters
TType of the published data.
Parameters
[in]nhNode handle for which the publisher should be created.
[in]topicTopic to publish to.
[in]queueSizeQueue size.
[in]paramNamespaceNamespace in private parameters of this nodelet where configuration of the diagnostics is stored. Params are: rate/desired, rate/max, rate/min, rate/tolerance, rate/window_size, delay/min, delay/max.
Returns
The publisher with diagnostics.

◆ getDefaultDiagNh()

template<typename NodeletType>
::ros::NodeHandle cras::NodeletWithDiagnostics< NodeletType >::getDefaultDiagNh ( const ::ros::NodeHandle pubSubNh,
const ::std::string &  diagNamespace 
)
protected

Get the default node handle for reading diagnostic task configuration.

Parameters
[in]pubSubNhThe node handle used for creating the publisher/subscriber.
[in]diagNamespaceThe explicit namespace.
Returns
The node handle.

◆ getDiagParams()

template<typename NodeletType>
::cras::BoundParamHelperPtr cras::NodeletWithDiagnostics< NodeletType >::getDiagParams ( const ::ros::NodeHandle nh,
const ::std::string &  diagNamespace,
const ::std::string &  topic 
)
protected

Get the parameters configuring a diagnosed publisher or subscriber.

Parameters
[in]nhNode handle of the publisher or subscriber.
[in]diagNamespaceParameter sub-namespace inside the node handle's namespace.
[in]topicName of the diagnosed topic.
Returns
Param helper with the parameters.

◆ getDiagUpdater()

template<typename NodeletType>
::cras::DiagnosticUpdater& cras::NodeletWithDiagnostics< NodeletType >::getDiagUpdater ( bool  forceNew = false) const
protected

Get a diagnostic updater to be used with this nodelet.

Parameters
[in]forceNewIf true, force creating a new updater, otherwise reuse the previously created one if it exists.
Returns
The updater.

◆ startDiagTimer() [1/2]

template<typename NodeletType>
void cras::NodeletWithDiagnostics< NodeletType >::startDiagTimer ( ) const
protected

Start periodic updates of the diagnostics updater.

◆ startDiagTimer() [2/2]

template<typename NodeletType>
void cras::NodeletWithDiagnostics< NodeletType >::startDiagTimer ( const ::ros::NodeHandle nh) const
protected

Start periodic updates of the diagnostics updater.

Parameters
[in]nhThe node handle on which the timer should be started.

◆ stopDiagTimer()

template<typename NodeletType>
void cras::NodeletWithDiagnostics< NodeletType >::stopDiagTimer ( ) const
protected

Stop the automatic updates of the diagnostic updater.

◆ subscribeDiagnosed() [1/8]

template<typename NodeletType>
template<typename M , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M> > > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
void(*)(M)  cb,
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MSignature of the callback.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [2/8]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<Message> > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
const ::boost::function< void(const ::boost::shared_ptr< Message > &)> &  cb,
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MessageType of the message to subscribe to.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [3/8]

template<typename NodeletType>
template<typename C , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C> > > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< C >> &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
const ::boost::function< void(C)> &  cb,
::ros::VoidConstPtr  obj = {},
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
CSignature of the callback.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]objTracked object.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [4/8]

template<typename NodeletType>
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M> > > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M)  cb,
T *  obj,
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MSignature of the callback.
TType of the object on which the callback will be called.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]objThe object to call the callback on.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [5/8]

template<typename NodeletType>
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M> > > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M) const  cb,
T *  obj,
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MSignature of the callback.
TType of the object on which the callback will be called.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]objThe object to call the callback on.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [6/8]

template<typename NodeletType>
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M> > > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M)  cb,
const ::boost::shared_ptr< T > &  obj,
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MSignature of the callback.
TType of the object on which the callback will be called.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]objThe object to call the callback on.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [7/8]

template<typename NodeletType>
template<typename M , class T , typename Enable = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M> > > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam<::cras::BaseMessage< M >> &  defaultDiagParams,
const ::std::string &  diagNamespace,
const ::std::string &  topic,
uint32_t  queue_size,
void(T::*)(M) const  cb,
const ::boost::shared_ptr< T > &  obj,
::ros::TransportHints  hints = {} 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MSignature of the callback.
TType of the object on which the callback will be called.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in]topicThe topic to subscribe to.
[in]queue_sizeSize of the subscription queue.
[in]cbThe callback to call when a message is received.
[in]objThe object to call the callback on.
[in]hintsConnection hints.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

◆ subscribeDiagnosed() [8/8]

template<typename NodeletType>
template<typename Message , typename Enable = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
::std::unique_ptr<::cras::DiagnosedSubscriber<Message> > cras::NodeletWithDiagnostics< NodeletType >::subscribeDiagnosed ( ::ros::NodeHandle  subscriberNh,
::ros::NodeHandle  diagNh,
const ::cras::SimpleTopicStatusParam< Message > &  defaultDiagParams,
const ::std::string &  diagNamespace,
::ros::SubscribeOptions options 
)
protected

Subscribe to the given topic, automatically updating the diagnostic task every time a message is received.

Template Parameters
MessageType of the message to subscribe to.
Parameters
[in]subscriberNhNode handle to use for setting up the subscriber.
[in]diagNhNode handle to use for reading parameters of the diagnostic task.
[in]defaultDiagParamsDefault parameters of the diagnostic task.
[in]diagNamespaceParameter namespace in which the parameters for the diagnostic task will be searched.
[in,out]optionsSubscription options.
Returns
The subscriber object. Keep it alive whole time the subscription should be active!

Member Data Documentation

◆ data

template<typename NodeletType>
::std::unique_ptr<::cras::impl::NodeletWithDiagnosticsPrivate> cras::NodeletWithDiagnostics< NodeletType >::data
private

PIMPL.

Definition at line 774 of file nodelet_with_diagnostics.hpp.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53