17 #include <boost/functional.hpp> 38 typedef ::std::function<void(::ros::Subscriber& sub)>
ConnectFn;
42 typedef ::std::function<void(::ros::Subscriber& sub)>
DisconnectFn;
55 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
66 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
148 template<
typename PublisherMsgType>
163 typename ::cras::ConditionalSubscriber::ConnectFn connectFn,
164 typename ::cras::ConditionalSubscriber::DisconnectFn disconnectFn,
165 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
176 typename ::cras::ConditionalSubscriber::ConnectFn connectFn,
177 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
183 void connectCb(const ::ros::SingleSubscriberPublisher&);
196 template<
typename PublisherMsgType,
typename CallbackType = const PublisherMsgType&>
213 ::
ros::NodeHandle subscriberNh, const ::std::string& subscriberTopic,
size_t subscriberQueueSize,
215 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
228 ::
ros::NodeHandle subscriberNh, const ::std::string& subscriberTopic,
size_t subscriberQueueSize,
229 ::boost::function<
void(CallbackType)> subscriberCallback,
230 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
ConditionalSubscriber(ConnectFn connectFn, DisconnectFn disconnectFn, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
Create the conditional subscriber.
::ros::Subscriber sub
The underlying subscriber (valid only when subscribed is true).
virtual bool shouldBeSubscribed() const =0
Tell whether the subscriber should be subscribed or not.
bool subscribed
Whether the subscriber is currently subscribed to its topic or not.
void connectNoLock()
Connect the subscriber to its input.
::std::function< void(::ros::Subscriber &sub)> DisconnectFn
Type of the function that disconnects the subscriber.
Base for lazy subscribers that subscribes only when a paired publisher has subscribers.
::std::function< void(::ros::Subscriber &sub)> ConnectFn
Type of the function that connects the subscriber.
mutable ::std::mutex connectMutex
Mutex protecting sub and subscribed.
void updateSubscriptionNoLock()
The callback called when the condition might have changed.
::ros::Publisher pub
The publisher whose number of subscribers decides whether to connect or not. It is not used to publis...
Lazy subscriber that subscribes only when a paired publisher has subscribers (implementation details...
bool lazy
Whether the lazy behavior is enabled (if false, the subscriber is always subscribed).
bool isSubscribed() const
Whether the subscriber is currently subscribed to its topic or not.
Lazy subscriber that subscribes only when a paired publisher has subscribers.
void disconnectNoLock()
Disconnect the subscriber from its input.
virtual ~ConditionalSubscriber()
Destroy this object and unsubscribe the subscriber if it was subscribed.
void setLazy(bool lazy)
Set whether the subscriber behaves in the lazy way.
bool isLazy() const
Tell whether this subscriber has the lazy behavior enabled.
DisconnectFn disconnectFn
The function used to close connection.
A lazy subscriber that subscribes only when a condition is met.
ConnectFn connectFn
The function used to establish connection.
void updateSubscription()
The callback called when the condition might have changed.