Lazy subscriber that subscribes only when a paired publisher has subscribers. More...
#include <lazy_subscriber.hpp>
Public Member Functions | |
LazySubscriber (::ros::NodeHandle publisherNh, const ::std::string &publisherTopic, ::ros::NodeHandle subscriberNh, const ::std::string &subscriberTopic, size_t subscriberQueueSize, ::boost::function< void(CallbackType)> subscriberCallback, ::ros::SubscribeOptions subscribeOptions, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >()) | |
Create the lazy subscriber that subscribes to subscriberTopic when publisherTopic has subscribers. More... | |
LazySubscriber (::ros::NodeHandle publisherNh, const ::std::string &publisherTopic, ::ros::NodeHandle subscriberNh, const ::std::string &subscriberTopic, size_t subscriberQueueSize, ::boost::function< void(CallbackType)> subscriberCallback, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >()) | |
Create the lazy subscriber that subscribes to subscriberTopic when publisherTopic has subscribers. More... | |
Public Member Functions inherited from 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. 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... | |
Public Member Functions inherited from cras::ConditionalSubscriber | |
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) |
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... | |
Protected Member Functions inherited from cras::LazySubscriberBase< PublisherMsgType > | |
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 inherited from cras::LazySubscriberBase< PublisherMsgType > | |
::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 |
Lazy subscriber that subscribes only when a paired publisher has subscribers.
PublisherMsgType | Type of the publisher messages. |
Definition at line 197 of file lazy_subscriber.hpp.
cras::LazySubscriber< PublisherMsgType, CallbackType >::LazySubscriber | ( | ::ros::NodeHandle | publisherNh, |
const ::std::string & | publisherTopic, | ||
::ros::NodeHandle | subscriberNh, | ||
const ::std::string & | subscriberTopic, | ||
size_t | subscriberQueueSize, | ||
::boost::function< void(CallbackType)> | subscriberCallback, | ||
::ros::SubscribeOptions | subscribeOptions, | ||
const ::cras::LogHelperPtr & | logHelper = ::std::make_shared<::cras::NodeLogHelper>() |
||
) |
Create the lazy subscriber that subscribes to subscriberTopic
when publisherTopic
has subscribers.
[in] | publisherNh | Node handle used for publisher topic. |
[in] | publisherTopic | The topic whose number of subscribers decides whether to connect or not. |
[in] | subscriberNh | Node handle used for subscriber topic. |
[in] | subscriberTopic | The topic to subscribe. |
[in] | subscriberQueueSize | Queue size for the subscriber. |
[in] | subscriberCallback | The callback called by the subscriber when a new message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. Only allow_concurrent_callbacks and transport_hints fields from this object are used. |
[in] | logHelper | Logging helper. |
Definition at line 74 of file impl/lazy_subscriber.hpp.
cras::LazySubscriber< PublisherMsgType, CallbackType >::LazySubscriber | ( | ::ros::NodeHandle | publisherNh, |
const ::std::string & | publisherTopic, | ||
::ros::NodeHandle | subscriberNh, | ||
const ::std::string & | subscriberTopic, | ||
size_t | subscriberQueueSize, | ||
::boost::function< void(CallbackType)> | subscriberCallback, | ||
const ::cras::LogHelperPtr & | logHelper = ::std::make_shared<::cras::NodeLogHelper>() |
||
) |
Create the lazy subscriber that subscribes to subscriberTopic
when publisherTopic
has subscribers.
[in] | publisherNh | Node handle used for publisher topic. |
[in] | publisherTopic | The topic whose number of subscribers decides whether to connect or not. |
[in] | subscriberNh | Node handle used for subscriber topic. |
[in] | subscriberTopic | The topic to subscribe. |
[in] | subscriberQueueSize | Queue size for the subscriber. |
[in] | subscriberCallback | The callback called by the subscriber when a new message is received. |
[in] | logHelper | Logging helper. |
Definition at line 91 of file impl/lazy_subscriber.hpp.