Template Class LazySubscriberBase

Inheritance Relationships

Base Type

Derived Type

Class Documentation

template<typename PublisherMsgType>
class LazySubscriberBase : public cras::ConditionalSubscriber

Base for lazy subscribers that subscribes only when a paired publisher has subscribers.

Template Parameters:

PublisherMsgType – Type of the publisher messages.

Subclassed by cras::LazySubscriber< PublisherMsgType, CallbackType >

Public Functions

LazySubscriberBase(::ros::NodeHandle publisherNh, const ::std::string &publisherTopic, typename ::cras::ConditionalSubscriber::ConnectFn connectFn, typename ::cras::ConditionalSubscriber::DisconnectFn disconnectFn, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())

Create the lazy subscriber that subscribes only when publisherTopic has subscribers.

Parameters:
  • publisherNh[in] Node handle used for publisher topic.

  • publisherTopic[in] The topic whose number of subscribers decides whether to connect or not.

  • connectFn[in] The function that connects the subscriber. It should store the subscriber in the passed sub object.

  • disconnectFn[in] The function that disconnects the subscriber. The sub object passed to the function is the one created previously by connectFn. The passed subscriber should be invalidated.

  • logHelper[in] Logging helper.

LazySubscriberBase(::ros::NodeHandle publisherNh, const ::std::string &publisherTopic, typename ::cras::ConditionalSubscriber::ConnectFn connectFn, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())

Create the lazy subscriber that subscribes only when publisherTopic has subscribers.

Parameters:
  • publisherNh[in] Node handle used for publisher topic.

  • publisherTopic[in] The topic whose number of subscribers decides whether to connect or not.

  • connectFn[in] The function that connects the subscriber. It should store the subscriber in the passed sub object. Disconnection of the subscriber is done by simply calling sub.shutdown().

  • logHelper[in] Logging helper.

Protected Functions

void connectCb(const ::ros::SingleSubscriberPublisher&)

The callback called when a new subscriber appears or disappears.

virtual bool shouldBeSubscribed() const override

Tell whether the subscriber should be subscribed or not.

Note

This function does not need to take into account the lazy flag.

Note

This function cannot lock connectMutex.

Returns:

Whether the subscriber should be subscribed or not.

Protected Attributes

::ros::Publisher pub

The publisher whose number of subscribers decides whether to connect or not. It is not used to publish any actual messages.