Class NodeHandleWithDiagnostics

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class NodeHandleWithDiagnostics : public cras::NodeParamHelper

Utils for adding diagnostics to a topic via node handle.

The publisher and subscriber diagnostic tasks can be configured from ROS parameters. The following parameters are read:

  • rate/desired (double, Hz, no default): If set, this value will be used as the default of min/max rates.

  • rate/min (double, Hz, default 0.0 or desired): Minimum acceptable rate.

  • rate/max (double, Hz, default +inf or desired): Maximum acceptable rate.

  • rate/tolerance (double, default 0.1): Tolerance of the min/max rate (0.0 means that the min/max rate limits are strict).

  • rate/window_size (uint, default 5): Over how many diagnostics updates should the rate be computed.

  • delay/min (double, s, default -1.0): Minimum acceptable delay (only computed for messages with a header).

  • delay/max (double, s, default 5.0): Maximum acceptable delay (only computed for messages with a header).

The parameter namespace from which they are configured is determined as follows:

  • If no explicit namespace is specified, the topic name is used.

    • Name remapping is done only “until” the topic name level. I.e. node name or parent namespaces are affected by remappings, but the topic name is not. If the topic name is absolute, it is taken as is without any remappings.

    • Explicit namespaces are remapped as normal ROS parameters.

  • If the namespace starts with ~ or is not specified (topic name is used), the private node namespace (node name) is prepended.

    • If this node handle already represents a private node handle, no additional namespace is prepended.

Here are a few examples:

Subclassed by cras::NodeHandle

Public Functions

explicit NodeHandleWithDiagnostics(const ::std::string &ns = "", const ::ros::M_string &remappings = {})

Create the node handle using the passed ROS node handle parameters.

Parameters:
  • ns[in] Namespace of the handle.

  • remappings[in] Remappings.

NodeHandleWithDiagnostics(const ::ros::NodeHandle &parent, const ::std::string &ns)

Create the node handle using the passed ROS node handle parameters.

Parameters:
  • parent[in] Parent node handle.

  • ns[in] Namespace of the handle.

NodeHandleWithDiagnostics(const ::ros::NodeHandle &parent, const ::std::string &ns, const ::ros::M_string &remappings)

Create the node handle using the passed ROS node handle parameters.

Parameters:
  • parent[in] Parent node handle.

  • ns[in] Namespace of the handle.

  • remappings[in] Remappings.

template<class Message>
inline ::std::unique_ptr<::cras::DiagnosedPublisher<Message>> advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<Message> &defaultDiagParams, const ::std::string &diagNamespace, const ::std::string &topic, const size_t queueSize, const bool latch = false)

Advertise publication of a message, automatically adding diagnostics to it.

Template Parameters:

Message – Type of the message to be published.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to advertise and diagnose.

  • queueSize[in] Size of the publishing queue.

  • latch[in] Whether to latch the publication.

Returns:

A publisher object whose publish() method has to be used to correctly automate the diagnostic task updating.

template<class Message>
inline ::std::unique_ptr<::cras::DiagnosedPublisher<Message>> advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::cras::SimpleTopicStatusParam<Message> &defaultDiagParams, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)

Advertise publication of a message, automatically adding diagnostics to it.

Template Parameters:

Message – Type of the message to be published.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • options[inout] Advertise options that configure the publisher.

Returns:

A publisher object whose publish() method has to be used to correctly automate the diagnostic task updating.

template<class Message>
inline ::std::unique_ptr<::cras::DiagnosedPublisher<Message>> advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, const ::std::string &topic, const size_t queueSize, const bool latch = false)

Advertise publication of a message, automatically adding diagnostics to it.

Template Parameters:

Message – Type of the message to be published.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to advertise and diagnose.

  • queueSize[in] Size of the publishing queue.

  • latch[in] Whether to latch the publication.

Returns:

A publisher object whose publish() method has to be used to correctly automate the diagnostic task updating.

template<class Message>
inline ::std::unique_ptr<::cras::DiagnosedPublisher<Message>> advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, ::ros::AdvertiseOptions &options)

Advertise publication of a message, automatically adding diagnostics to it.

Template Parameters:

Message – Type of the message to be published.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • options[inout] Advertise options that configure the publisher.

Returns:

A publisher object whose publish() method has to be used to correctly automate the diagnostic task updating.

template<class Message>
inline ::std::unique_ptr<::cras::DiagnosedPublisher<Message>> advertiseDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &topic, const size_t queueSize, const bool latch = false)

Advertise publication of a message, automatically adding diagnostics to it.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:

Message – Type of the message to be published.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to advertise and diagnose.

  • queueSize[in] Size of the publishing queue.

  • latch[in] Whether to latch the publication.

Returns:

A publisher object whose publish() method has to be used to correctly automate the diagnostic task updating.

template<class Message>
inline ::std::unique_ptr<::cras::DiagnosedPublisher<Message>> advertiseDiagnosed(::diagnostic_updater::Updater &updater, ::ros::AdvertiseOptions &options)

Advertise publication of a message, automatically adding diagnostics to it.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:

Message – Type of the message to be published.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • options[inout] Advertise options that configure the publisher.

Returns:

A publisher object whose publish() method has to be used to correctly automate the diagnostic task updating.

template<typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

M – Signature of the callback.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

Message – Type of the message to subscribe to.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

C – Signature of the callback.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] Tracked object.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

Message – Type of the message to subscribe to.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • defaultDiagParams[in] Default parameters of the diagnostic task.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • options[inout] Subscription options.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

M – Signature of the callback.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

Message – Type of the message to subscribe to.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

C – Signature of the callback.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] Tracked object.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, const ::std::string &diagNamespace, ::ros::SubscribeOptions &options)

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

Template Parameters:

Message – Type of the message to subscribe to.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • diagNamespace[in] Parameter namespace in which the parameters for the diagnostic task will be searched.

  • options[inout] Subscription options.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:

M – Signature of the callback.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:

Message – Type of the message to subscribe to.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename C, typename = ::std::enable_if_t<::cras::IsMessageParam<C>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<C>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Template Parameters:

C – Signature of the callback.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] Tracked object.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename M, class T, typename = ::std::enable_if_t<::cras::IsMessageParam<M>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<::cras::BaseMessage<M>>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, 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.

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:
  • M – Signature of the callback.

  • T – Type of the object on which the callback will be called.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • topic[in] The topic to subscribe to.

  • queue_size[in] Size of the subscription queue.

  • cb[in] The callback to call when a message is received.

  • obj[in] The object to call the callback on.

  • hints[in] Connection hints.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

template<typename Message, typename = ::std::enable_if_t<::ros::message_traits::IsMessage<Message>::value>>
inline ::std::unique_ptr<::cras::DiagnosedSubscriber<Message>> subscribeDiagnosed(::diagnostic_updater::Updater &updater, ::ros::SubscribeOptions &options)

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

Note

The diagnostic task will search its parameters in parameter namespace ~/topic.

Template Parameters:

Message – Type of the message to subscribe to.

Parameters:
  • updater[in] The diagnostic updater to add the diagnostic task to.

  • options[inout] Subscription options.

Returns:

The subscriber object. Keep it alive whole time the subscription should be active!

Protected Functions

::std::string prefixDiagNamespace(const ::std::string &ns) const

Optionally add a private node namespace to the given topic if this nodehandle is in the root node namespace.

Parameters:

ns[in] The namespace to prefix.

Returns:

The prefix namespace.

::cras::BoundParamHelperPtr getDiagParams(const ::std::string &diagNs, const ::std::string &topic) const

Get the param helper from which parameters for the diagnostic task can be extracted.

Parameters:
  • diagNs[in] Namespace of the diagnostic task. Pass empty string if you want to search a parameter namespace based on the topic name.

  • topic[in] Name of the diagnosed topic which will be used as a default parameter namespace.

Returns:

The param helper.

Protected Attributes

::ros::NodeHandle parentNh = {}

The parent node handle of this one.