Class ConditionalSubscriber
Defined in File lazy_subscriber.hpp
Inheritance Relationships
Base Type
public cras::HasLogger
Derived Types
public cras::GenericLazyPubSub(Class GenericLazyPubSub)public cras::LazySubscriberBase< PublisherMsgType >(Template Class LazySubscriberBase)
Class Documentation
-
class ConditionalSubscriber : public cras::HasLogger
A lazy subscriber that subscribes only when a condition is met.
Subclassed by cras::GenericLazyPubSub, cras::LazySubscriberBase< PublisherMsgType >
Public Types
-
typedef ::std::function<void(::ros::Subscriber &sub)> ConnectFn
Type of the function that connects the subscriber.
- Param sub:
[out] Reference to the subscriber object to be created.
-
typedef ::std::function<void(::ros::Subscriber &sub)> DisconnectFn
Type of the function that disconnects the subscriber.
- Param Reference:
[inout] to the subscriber object to be disconnected.
Public Functions
-
ConditionalSubscriber(ConnectFn connectFn, DisconnectFn disconnectFn, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())
Create the conditional subscriber.
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.- Parameters:
connectFn – [in] The function that connects the subscriber. It should store the subscriber in the passed
subobject.disconnectFn – [in] The function that disconnects the subscriber. The
subobject passed to the function is the one created previously byconnectFn. The passed subscriber should be invalidated.logHelper – [in] Logging helper.
-
explicit ConditionalSubscriber(ConnectFn connectFn, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())
Create the conditional subscriber.
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.- Parameters:
connectFn – [in] The function that connects the subscriber. It should store the subscriber in the passed
subobject. Disconnection is done by simply callingsub.shutdown().logHelper – [in] Logging helper.
-
virtual ~ConditionalSubscriber()
Destroy this object and unsubscribe the subscriber if it was subscribed.
-
bool isLazy() const
Tell whether this subscriber has the lazy behavior enabled.
- Returns:
Whether lazy behavior is enabled.
-
void setLazy(bool lazy)
Set whether the subscriber behaves in the lazy way.
Note
Calling this function checks the subscription condition and subscribes/unsubscribes as necessary.
- Parameters:
lazy – [in] If set to false, the subscriber is switched to always subscribed mode.
-
bool 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.
Protected Functions
-
virtual bool shouldBeSubscribed() const = 0
Tell whether the subscriber should be subscribed or not.
Note
This function does not need to take into account the
lazyflag.Note
This function cannot lock
connectMutex.- Returns:
Whether the subscriber should be subscribed or not.
-
void updateSubscription()
The callback called when the condition might have changed.
Note
This function locks
connectMutex.
-
void updateSubscriptionNoLock()
The callback called when the condition might have changed.
Note
You have to lock this->connectMutex prior to calling this method.
-
void connectNoLock()
Connect the subscriber to its input.
Note
You have to lock this->connectMutex prior to calling this method.
-
void disconnectNoLock()
Disconnect the subscriber from its input.
Note
You have to lock this->connectMutex prior to calling this method.
Protected Attributes
-
::ros::Subscriber sub
The underlying subscriber (valid only when
subscribedis true).
-
bool lazy = {true}
Whether the lazy behavior is enabled (if false, the subscriber is always subscribed).
-
bool subscribed = {false}
Whether the subscriber is currently subscribed to its topic or not.
-
DisconnectFn disconnectFn
The function used to close connection.
-
mutable ::std::mutex connectMutex
Mutex protecting
subandsubscribed.
-
typedef ::std::function<void(::ros::Subscriber &sub)> ConnectFn