Template Class DiagnosedSubscriber

Inheritance Relationships

Base Type

Class Documentation

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

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

Template Parameters:
  • Message – Type of the subscribed message.

  • Enable – SFINAE only. Do not set explicitly.

Public Functions

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.

Template Parameters:
  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • hints[in] Connection hints.

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:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • hints[in] Connection hints.

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.

Template Parameters:
  • C – SFINAE only. Do not set explicitly.

  • EnableC – SFINAE only. Do not set explicitly.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • obj[in] Tracked object for the subscriber.

  • hints[in] Connection hints.

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.

Template Parameters:
  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

  • hints[in] Connection hints.

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.

Template Parameters:
  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

  • hints[in] Connection hints.

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.

Template Parameters:
  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

  • hints[in] Connection hints.

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.

Template Parameters:
  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • topic[in] Name of the topic to subscribe.

  • queue_size[in] Queue size of the subscriber.

  • cb[in] The message callback.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

  • hints[in] Connection hints.

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.

Note

This constructor will “wrap” the callback specified in options to automatically trigger the diagnostic task when a message is received.

Parameters:
  • nh[in] Node handle used for subscribing.

  • params[in] ROS parameters from which the configuration of the diagnostic task is taken.

  • defaultParams[in] Default parameters used when no ROS parameter exists.

  • options[in] Subscribe options.

const ::ros::Subscriber &getSubscriber() const

Get the created ROS subscriber.

Returns:

The ROS subscriber.

::ros::Subscriber &getSubscriber()

Get the created ROS subscriber.

Returns:

The ROS subscriber.

template<typename T, typename M, typename EnableM>
::boost::function<void(M)> addTick(const ::std::function<void(M)> &fn, T)
template<typename T, typename M, typename EnableM>
::boost::function<void(M)> addTick(void (T::* fn)(M), T *obj)
template<typename T, typename M, typename EnableM>
::boost::function<void(M)> addTick(void (T::* fn)(M), const ::boost::shared_ptr<T> &obj)
template<typename T, typename M, typename EnableM>
::boost::function<void(M)> addTick(void (T::* fn)(M) const, T *obj)
template<typename T, typename M, typename EnableM>
::boost::function<void(M)> addTick(void (T::* fn)(M) const, const ::boost::shared_ptr<T> &obj)

Protected Functions

::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().

Parameters:

fn[in] The function to wrap.

Returns:

The wrapping function.

::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().

Parameters:

fn[in] The function to wrap.

Returns:

The wrapping function.

::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().

Parameters:

fn[in] The function to wrap.

Returns:

The wrapping function.

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().

Template Parameters:
  • T – Ignored.

  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:

fn[in] The function to wrap.

Returns:

The wrapping function.

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().

Template Parameters:
  • T – Ignored.

  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • fn[in] The function to wrap.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

Returns:

The wrapping function.

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().

Template Parameters:
  • T – Ignored.

  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • fn[in] The function to wrap.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

Returns:

The wrapping function.

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().

Template Parameters:
  • T – Ignored.

  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • fn[in] The function to wrap.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

Returns:

The wrapping function.

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().

Template Parameters:
  • T – Ignored.

  • M – SFINAE only. Do not set explicitly.

  • EnableM – SFINAE only. Do not set explicitly.

Parameters:
  • fn[in] The function to wrap.

  • obj[in] Tracked object for the subscriber and on which the callback will be called.

Returns:

The wrapping function.

Protected Attributes

::ros::Subscriber subscriber

The ROS subscriber.