Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cras::ConditionalSubscriber Class Referenceabstract

A lazy subscriber that subscribes only when a condition is met. More...

#include <lazy_subscriber.hpp>

Inheritance diagram for cras::ConditionalSubscriber:
Inheritance graph
[legend]

Public Types

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

Public Member Functions

 ConditionalSubscriber (ConnectFn connectFn, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
 Create the conditional subscriber. More...
 
 ConditionalSubscriber (ConnectFn connectFn, DisconnectFn disconnectFn, 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 connectNoLock ()
 Connect the subscriber to its input. More...
 
void disconnectNoLock ()
 Disconnect the subscriber from its input. More...
 
virtual bool shouldBeSubscribed () const =0
 Tell whether the subscriber should be subscribed or not. 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

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
 

Detailed Description

A lazy subscriber that subscribes only when a condition is met.

Definition at line 33 of file lazy_subscriber.hpp.

Member Typedef Documentation

◆ ConnectFn

typedef ::std::function<void(::ros::Subscriber& sub)> cras::ConditionalSubscriber::ConnectFn

Type of the function that connects the subscriber.

Parameters
[out]subReference to the subscriber object to be created.

Definition at line 38 of file lazy_subscriber.hpp.

◆ DisconnectFn

Type of the function that disconnects the subscriber.

Parameters
[in,out]Referenceto the subscriber object to be disconnected.

Definition at line 42 of file lazy_subscriber.hpp.

Constructor & Destructor Documentation

◆ ConditionalSubscriber() [1/2]

cras::ConditionalSubscriber::ConditionalSubscriber ( ConnectFn  connectFn,
DisconnectFn  disconnectFn,
const ::cras::LogHelperPtr logHelper = ::std::make_shared<::cras::NodeLogHelper >() 
)

Create the conditional subscriber.

Parameters
[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.
Note
The base class itself does not regularly check the connect/disconnect condition. Subclasses are responsible for calling updateSubscription() when it is possible that the subscription condition changed.

◆ ConditionalSubscriber() [2/2]

cras::ConditionalSubscriber::ConditionalSubscriber ( ConnectFn  connectFn,
const ::cras::LogHelperPtr logHelper = ::std::make_shared<::cras::NodeLogHelper >() 
)
explicit

Create the conditional subscriber.

Parameters
[in]connectFnThe function that connects the subscriber. It should store the subscriber in the passed sub object. Disconnection is done by simply calling sub.shutdown().
[in]logHelperLogging helper.
Note
The base class itself does not regularly check the connect/disconnect condition. Subclasses are responsible for calling updateSubscription() when it is possible that the subscription condition changed.

◆ ~ConditionalSubscriber()

cras::ConditionalSubscriber::~ConditionalSubscriber ( )
virtual

Destroy this object and unsubscribe the subscriber if it was subscribed.

Definition at line 32 of file lazy_subscriber.cpp.

Member Function Documentation

◆ connectNoLock()

void cras::ConditionalSubscriber::connectNoLock ( )
protected

Connect the subscriber to its input.

Note
You have to lock this->connectMutex prior to calling this method.

Definition at line 86 of file lazy_subscriber.cpp.

◆ disconnectNoLock()

void cras::ConditionalSubscriber::disconnectNoLock ( )
protected

Disconnect the subscriber from its input.

Note
You have to lock this->connectMutex prior to calling this method.

Definition at line 93 of file lazy_subscriber.cpp.

◆ isLazy()

bool cras::ConditionalSubscriber::isLazy ( ) const

Tell whether this subscriber has the lazy behavior enabled.

Returns
Whether lazy behavior is enabled.

Definition at line 39 of file lazy_subscriber.cpp.

◆ isSubscribed()

bool cras::ConditionalSubscriber::isSubscribed ( ) const

Whether the subscriber is currently subscribed to its topic or not.

Returns
Whether the subscriber is currently subscribed to its topic or not.

Definition at line 61 of file lazy_subscriber.cpp.

◆ setLazy()

void cras::ConditionalSubscriber::setLazy ( bool  lazy)

Set whether the subscriber behaves in the lazy way.

Parameters
[in]lazyIf set to false, the subscriber is switched to always subscribed mode.
Note
Calling this function checks the subscription condition and subscribes/unsubscribes as necessary.

Definition at line 44 of file lazy_subscriber.cpp.

◆ shouldBeSubscribed()

virtual bool cras::ConditionalSubscriber::shouldBeSubscribed ( ) const
protectedpure virtual

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.

Implemented in cras::LazySubscriberBase< PublisherMsgType >, and cras::GenericLazyPubSub.

◆ updateSubscription()

void cras::ConditionalSubscriber::updateSubscription ( )
protected

The callback called when the condition might have changed.

Note
This function locks connectMutex.

Definition at line 67 of file lazy_subscriber.cpp.

◆ updateSubscriptionNoLock()

void cras::ConditionalSubscriber::updateSubscriptionNoLock ( )
protected

The callback called when the condition might have changed.

Note
You have to lock this->connectMutex prior to calling this method.

Definition at line 73 of file lazy_subscriber.cpp.

Member Data Documentation

◆ connectFn

ConnectFn cras::ConditionalSubscriber::connectFn
protected

The function used to establish connection.

Definition at line 135 of file lazy_subscriber.hpp.

◆ connectMutex

mutable ::std::mutex cras::ConditionalSubscriber::connectMutex
protected

Mutex protecting sub and subscribed.

Definition at line 141 of file lazy_subscriber.hpp.

◆ disconnectFn

DisconnectFn cras::ConditionalSubscriber::disconnectFn
protected

The function used to close connection.

Definition at line 138 of file lazy_subscriber.hpp.

◆ lazy

bool cras::ConditionalSubscriber::lazy {true}
protected

Whether the lazy behavior is enabled (if false, the subscriber is always subscribed).

Definition at line 129 of file lazy_subscriber.hpp.

◆ sub

::ros::Subscriber cras::ConditionalSubscriber::sub
protected

The underlying subscriber (valid only when subscribed is true).

Definition at line 126 of file lazy_subscriber.hpp.

◆ subscribed

bool cras::ConditionalSubscriber::subscribed {false}
protected

Whether the subscriber is currently subscribed to its topic or not.

Definition at line 132 of file lazy_subscriber.hpp.


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


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:28