Go to the documentation of this file.
17 #include <boost/functional.hpp>
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>());
void updateSubscription()
The callback called when the condition might have changed.
void setLazy(bool lazy)
Set whether the subscriber behaves in the lazy way.
DisconnectFn disconnectFn
The function used to close connection.
::std::function< void(::ros::Subscriber &sub)> ConnectFn
Type of the function that connects the subscriber.
::ros::Publisher pub
The publisher whose number of subscribers decides whether to connect or not. It is not used to publis...
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).
bool isSubscribed() const
Whether the subscriber is currently subscribed to its topic or not.
bool isLazy() const
Tell whether this subscriber has the lazy behavior enabled.
virtual ~ConditionalSubscriber()
Destroy this object and unsubscribe the subscriber if it was subscribed.
void updateSubscriptionNoLock()
The callback called when the condition might have changed.
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.
::std::function< void(::ros::Subscriber &sub)> DisconnectFn
Type of the function that disconnects the subscriber.
Lazy subscriber that subscribes only when a paired publisher has subscribers.
bool subscribed
Whether the subscriber is currently subscribed to its topic or not.
void connectCb(const ::ros::SingleSubscriberPublisher &)
The callback called when a new subscriber appears or disappears.
void connectNoLock()
Connect the subscriber to its input.
Lazy subscriber that subscribes only when a paired publisher has subscribers (implementation details,...
Base for lazy subscribers that subscribes only when a paired publisher has subscribers.
virtual bool shouldBeSubscribed() const =0
Tell whether the subscriber should be subscribed or not.
mutable ::std::mutex connectMutex
Mutex protecting sub and subscribed.
A lazy subscriber that subscribes only when a condition is met.
bool shouldBeSubscribed() const override
Tell whether the subscriber should be subscribed or not.
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.
void disconnectNoLock()
Disconnect the subscriber from its input.
ConnectFn connectFn
The function used to establish connection.
bool lazy
Whether the lazy behavior is enabled (if false, the subscriber is always subscribed).
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sun Jan 5 2025 03:50:49