lazy_subscriber.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
12 #include <functional>
13 #include <memory>
14 #include <mutex>
15 #include <string>
16 
17 #include <boost/functional.hpp>
18 
19 #include <ros/node_handle.h>
20 #include <ros/publisher.h>
22 #include <ros/subscriber.h>
23 
26 
27 namespace cras
28 {
29 
34 {
35 public:
38  typedef ::std::function<void(::ros::Subscriber& sub)> ConnectFn;
39 
42  typedef ::std::function<void(::ros::Subscriber& sub)> DisconnectFn;
43 
54  ConditionalSubscriber(ConnectFn connectFn, DisconnectFn disconnectFn,
55  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
56 
65  explicit ConditionalSubscriber(ConnectFn connectFn,
66  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
67 
71  virtual ~ConditionalSubscriber();
72 
77  bool isLazy() const;
78 
84  void setLazy(bool lazy);
85 
90  bool isSubscribed() const;
91 
92 protected:
99  virtual bool shouldBeSubscribed() const = 0;
100 
105  void updateSubscription();
106 
112 
117  void connectNoLock();
118 
123  void disconnectNoLock();
124 
127 
129  bool lazy {true};
130 
132  bool subscribed {false};
133 
135  ConnectFn connectFn;
136 
138  DisconnectFn disconnectFn;
139 
141  mutable ::std::mutex connectMutex;
142 };
143 
148 template<typename PublisherMsgType>
150 {
151 public:
162  LazySubscriberBase(::ros::NodeHandle publisherNh, const ::std::string& publisherTopic,
163  typename ::cras::ConditionalSubscriber::ConnectFn connectFn,
164  typename ::cras::ConditionalSubscriber::DisconnectFn disconnectFn,
165  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
166 
175  LazySubscriberBase(::ros::NodeHandle publisherNh, const ::std::string& publisherTopic,
176  typename ::cras::ConditionalSubscriber::ConnectFn connectFn,
177  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
178 
179 protected:
183  void connectCb(const ::ros::SingleSubscriberPublisher&);
184 
185  bool shouldBeSubscribed() const override;
186 
190 };
191 
196 template<typename PublisherMsgType, typename CallbackType = const PublisherMsgType&>
197 class LazySubscriber : public ::cras::LazySubscriberBase<PublisherMsgType>
198 {
199 public:
212  LazySubscriber(::ros::NodeHandle publisherNh, const ::std::string& publisherTopic,
213  ::ros::NodeHandle subscriberNh, const ::std::string& subscriberTopic, size_t subscriberQueueSize,
214  ::boost::function<void(CallbackType)> subscriberCallback, ::ros::SubscribeOptions subscribeOptions,
215  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
216 
227  LazySubscriber(::ros::NodeHandle publisherNh, const ::std::string& publisherTopic,
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>());
231 };
232 
233 }
234 
235 #include "impl/lazy_subscriber.hpp"
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.


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:33:13