Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cras::LazySubscriberBase< PublisherMsgType > Class Template Reference

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

#include <lazy_subscriber.hpp>

Inheritance diagram for cras::LazySubscriberBase< PublisherMsgType >:
Inheritance graph
[legend]

Public Member 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. More...
 
 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. More...
 
- Public Member Functions inherited from cras::ConditionalSubscriber
 ConditionalSubscriber (ConnectFn connectFn, DisconnectFn disconnectFn, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
 Create the conditional subscriber. More...
 
 ConditionalSubscriber (ConnectFn connectFn, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
 Create the conditional subscriber. More...
 
bool isLazy () const
 Tell whether this subscriber has the lazy behavior enabled. More...
 
bool isSubscribed () const
 Whether the subscriber is currently subscribed to its topic or not. More...
 
void setLazy (bool lazy)
 Set whether the subscriber behaves in the lazy way. More...
 
virtual ~ConditionalSubscriber ()
 Destroy this object and unsubscribe the subscriber if it was subscribed. More...
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Protected Member Functions

void connectCb (const ::ros::SingleSubscriberPublisher &)
 The callback called when a new subscriber appears or disappears. More...
 
bool shouldBeSubscribed () const override
 Tell whether the subscriber should be subscribed or not. More...
 
- Protected Member Functions inherited from cras::ConditionalSubscriber
void connectNoLock ()
 Connect the subscriber to its input. More...
 
void disconnectNoLock ()
 Disconnect the subscriber from its input. More...
 
void updateSubscription ()
 The callback called when the condition might have changed. More...
 
void updateSubscriptionNoLock ()
 The callback called when the condition might have changed. More...
 

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. More...
 
- Protected Attributes inherited from cras::ConditionalSubscriber
ConnectFn connectFn
 The function used to establish connection. More...
 
mutable ::std::mutex connectMutex
 Mutex protecting sub and subscribed. More...
 
DisconnectFn disconnectFn
 The function used to close connection. More...
 
bool lazy {true}
 Whether the lazy behavior is enabled (if false, the subscriber is always subscribed). More...
 
::ros::Subscriber sub
 The underlying subscriber (valid only when subscribed is true). More...
 
bool subscribed {false}
 Whether the subscriber is currently subscribed to its topic or not. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Additional Inherited Members

- Public Types inherited from cras::ConditionalSubscriber
typedef ::std::function< void(::ros::Subscriber &sub)> ConnectFn
 Type of the function that connects the subscriber. More...
 
typedef ::std::function< void(::ros::Subscriber &sub)> DisconnectFn
 Type of the function that disconnects the subscriber. More...
 

Detailed Description

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

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

Template Parameters
PublisherMsgTypeType of the publisher messages.

Definition at line 149 of file lazy_subscriber.hpp.

Constructor & Destructor Documentation

◆ LazySubscriberBase() [1/2]

template<typename PublisherMsgType >
cras::LazySubscriberBase< PublisherMsgType >::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
[in]publisherNhNode handle used for publisher topic.
[in]publisherTopicThe topic whose number of subscribers decides whether to connect or not.
[in]connectFnThe function that connects the subscriber. It should store the subscriber in the passed sub object.
[in]disconnectFnThe 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.
[in]logHelperLogging helper.

Definition at line 32 of file impl/lazy_subscriber.hpp.

◆ LazySubscriberBase() [2/2]

template<typename PublisherMsgType >
cras::LazySubscriberBase< PublisherMsgType >::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
[in]publisherNhNode handle used for publisher topic.
[in]publisherTopicThe topic whose number of subscribers decides whether to connect or not.
[in]connectFnThe 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().
[in]logHelperLogging helper.

Definition at line 50 of file impl/lazy_subscriber.hpp.

Member Function Documentation

◆ connectCb()

template<typename PublisherMsgType>
void cras::LazySubscriberBase< PublisherMsgType >::connectCb ( const ::ros::SingleSubscriberPublisher )
protected

The callback called when a new subscriber appears or disappears.

◆ shouldBeSubscribed()

template<typename PublisherMsgType>
bool cras::LazySubscriberBase< PublisherMsgType >::shouldBeSubscribed ( ) const
overrideprotectedvirtual

Tell whether the subscriber should be subscribed or not.

Returns
Whether the subscriber should be subscribed or not.
Note
This function does not need to take into account the lazy flag.
This function cannot lock connectMutex.

Implements cras::ConditionalSubscriber.

Member Data Documentation

◆ pub

template<typename PublisherMsgType>
::ros::Publisher cras::LazySubscriberBase< PublisherMsgType >::pub
protected

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

Definition at line 189 of file lazy_subscriber.hpp.


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


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:33:13