Public Member Functions | |
TestLazySubscriber (ros::NodeHandle publisherNh, const std::string &publisherTopic, typename cras::ConditionalSubscriber::ConnectFn connectFn, typename cras::ConditionalSubscriber::DisconnectFn disconnectFn=[](ros::Subscriber &sub) { sub.shutdown();}, const cras::LogHelperPtr &logHelper=std::make_shared< cras::NodeLogHelper >()) | |
![]() | |
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... | |
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... | |
![]() | |
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... | |
![]() | |
::cras::LogHelperConstPtr | getCrasLogger () const |
HasLogger (const ::cras::LogHelperPtr &log) | |
void | setCrasLogger (const ::cras::LogHelperPtr &log) |
Additional Inherited Members | |
![]() | |
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... | |
![]() | |
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... | |
![]() | |
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... | |
![]() | |
::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... | |
![]() | |
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... | |
![]() | |
::cras::LogHelperPtr | log |
Definition at line 58 of file test_lazy_subscriber.cpp.
|
inline |
Definition at line 61 of file test_lazy_subscriber.cpp.