17 #include <boost/bind.hpp> 18 #include <boost/bind/placeholders.hpp> 19 #include <boost/functional.hpp> 31 template<typename PublisherMsgType>
32 ::cras::LazySubscriberBase<PublisherMsgType>::LazySubscriberBase(
34 typename ::cras::ConditionalSubscriber::ConnectFn connectFn,
35 typename ::cras::ConditionalSubscriber::DisconnectFn disconnectFn,
36 const ::cras::LogHelperPtr& logHelper) :
41 opts.template init<PublisherMsgType>(publisherTopic, 1, cb, cb);
45 ::std::lock_guard<::std::mutex> lock(this->connectMutex);
49 template<typename PublisherMsgType>
50 ::cras::LazySubscriberBase<PublisherMsgType>::LazySubscriberBase(
52 typename ::cras::ConditionalSubscriber::ConnectFn connectFn, const ::cras::LogHelperPtr& logHelper) :
54 [](::
ros::Subscriber& sub) { sub.shutdown(); }, logHelper)
58 template<
typename PublisherMsgType>
59 void ::cras::LazySubscriberBase<PublisherMsgType>::connectCb(const ::ros::SingleSubscriberPublisher&)
64 this->updateSubscription();
67 template<
typename PublisherMsgType>
68 bool ::cras::LazySubscriberBase<PublisherMsgType>::shouldBeSubscribed()
const 70 return this->pub && this->pub.getNumSubscribers() > 0;
73 template<typename PublisherMsgType, typename CallbackType>
74 ::cras::LazySubscriber<PublisherMsgType, CallbackType>::LazySubscriber(
76 ::
ros::NodeHandle subscriberNh, const ::std::string& subscriberTopic,
const size_t subscriberQueueSize,
78 const ::cras::LogHelperPtr& logHelper) :
80 [=](::
ros::Subscriber& sub) mutable
82 subscribeOptions.template initByFullCallbackType<CallbackType>(
83 subscriberTopic, subscriberQueueSize, ::std::move(subscriberCallback));
90 template<typename PublisherMsgType, typename CallbackType>
91 ::cras::LazySubscriber<PublisherMsgType, CallbackType>::LazySubscriber(
93 ::
ros::NodeHandle subscriberNh, const ::std::string& subscriberTopic,
const size_t subscriberQueueSize,
94 ::boost::function<
void(CallbackType)> subscriberCallback, const ::cras::LogHelperPtr& logHelper) :
95 LazySubscriber<PublisherMsgType, CallbackType>(::
std::move(publisherNh), publisherTopic, ::
std::move(subscriberNh),
96 subscriberTopic, subscriberQueueSize, subscriberCallback, {}, logHelper)
::ros::Subscriber sub
The underlying subscriber (valid only when subscribed is true).
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Base for lazy subscribers that subscribes only when a paired publisher has subscribers.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Lazy subscriber that subscribes only when a paired publisher has subscribers.
Lazy subscriber that subscribes only when a paired publisher has subscribers.
A lazy subscriber that subscribes only when a condition is met.