generic_lazy_pubsub.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 
13 #include <memory>
14 #include <mutex>
15 #include <string>
16 
17 #include <boost/functional.hpp>
18 
19 #include <ros/advertise_options.h>
20 #include <ros/message_event.h>
21 #include <ros/node_handle.h>
22 #include <ros/publisher.h>
24 #include <ros/subscribe_options.h>
25 #include <ros/subscriber.h>
26 #include <topic_tools/shape_shifter.h>
27 
31 
33 
34 namespace cras
35 {
36 
45 {
46 public:
48  typedef const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& CallbackMessageType;
49 
52 
65  GenericLazyPubSub(const ::ros::NodeHandle& nhIn, const ::std::string& topicIn,
66  const ::ros::NodeHandle& nhOut, const ::std::string& topicOut, size_t inQueueSize, size_t outQueueSize,
68  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
69 
81  GenericLazyPubSub(const ::ros::NodeHandle& nhIn, const ::std::string& topicIn,
82  const ::ros::NodeHandle& nhOut, const ::std::string& topicOut, size_t queueSize, CallbackType callback,
84  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
85 
96  GenericLazyPubSub(const ::ros::NodeHandle& nhIn, const ::std::string& topicIn,
97  const ::ros::NodeHandle& nhOut, const ::std::string& topicOut, CallbackType callback,
99  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
100 
112  GenericLazyPubSub(const ::ros::NodeHandle& nh, const ::std::string& topicIn, const ::std::string& topicOut,
115  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
116 
128  GenericLazyPubSub(const ::ros::NodeHandle& nh, const ::std::string& topicIn, const ::std::string& topicOut,
130  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
131 
142  GenericLazyPubSub(const ::ros::NodeHandle& nh, const ::std::string& topicIn, const ::std::string& topicOut,
144  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
145 
146 protected:
151  void subscribe(::ros::Subscriber& sub);
152 
157  bool shouldBeSubscribed() const override;
158 
162  void connectCb(const ::ros::SingleSubscriberPublisher&);
163 
168  void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
169 
175  virtual ::ros::AdvertiseOptions createAdvertiseOptions(
176  const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
177 
179  ::std::string topicIn;
180 
182  ::std::string topicOut;
183 
185  size_t inQueueSize;
186 
188  size_t outQueueSize;
189 
192 
195 
198 
201 
204 
206  ::std::mutex pubCreateMutex;
207 
209  ::cras::optional<::ros::AdvertiseOptions> advertiseOptions;
210 
212  const ::ros::SubscribeOptions subscribeOptions;
213 };
214 
215 }
optional.hpp
cras::GenericLazyPubSub
A pair of lazy subscriber and publisher which use the same message type (unknown at compile time).
Definition: generic_lazy_pubsub.hpp:44
node_handle.h
cras::GenericLazyPubSub::advertiseOptions
::cras::optional<::ros::AdvertiseOptions > advertiseOptions
The options used when the publisher was created. nullopt before the publisher is created.
Definition: generic_lazy_pubsub.hpp:209
ros::Publisher
cras::GenericLazyPubSub::subscribe
void subscribe(::ros::Subscriber &sub)
Perform the subscription to the input topic.
Definition: generic_lazy_pubsub.cpp:48
cras::GenericLazyPubSub::shouldBeSubscribed
bool shouldBeSubscribed() const override
Returns true when the subscriber should be connected - i.e. either at the start, or when pub has clie...
Definition: generic_lazy_pubsub.cpp:56
cras
cras::GenericLazyPubSub::CallbackMessageType
const typedef ::ros::MessageEvent<::topic_tools::ShapeShifter const > & CallbackMessageType
Signature of the subscriber's callback.
Definition: generic_lazy_pubsub.hpp:48
cras::GenericLazyPubSub::nhIn
::ros::NodeHandle nhIn
Node handle for topic subscription.
Definition: generic_lazy_pubsub.hpp:197
cras::GenericLazyPubSub::callback
::cras::GenericLazyPubSub::CallbackType callback
The user callback to be called when a message is received.
Definition: generic_lazy_pubsub.hpp:203
cras::GenericLazyPubSub::CallbackType
::boost::function< void(::cras::GenericLazyPubSub::CallbackMessageType, ::ros::Publisher &)> CallbackType
Type of the user callback passed to this class.
Definition: generic_lazy_pubsub.hpp:51
cras::GenericLazyPubSub::cb
void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback for the received messages from subscriber. It also handles publisher creation if none exists...
Definition: generic_lazy_pubsub.cpp:70
lazy_subscriber.hpp
Lazy subscriber that subscribes only when a paired publisher has subscribers.
cras::GenericLazyPubSub::GenericLazyPubSub
GenericLazyPubSub(const ::ros::NodeHandle &nhIn, const ::std::string &topicIn, const ::ros::NodeHandle &nhOut, const ::std::string &topicOut, size_t inQueueSize, size_t outQueueSize, CallbackType callback, ::ros::SubscribeOptions subscribeOptions={}, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
Create the pair of lazy subscriber and publisher.
publisher.h
cras::GenericLazyPubSub::sub
::ros::Subscriber sub
The input subscriber.
Definition: generic_lazy_pubsub.hpp:194
cras::GenericLazyPubSub::nhOut
::ros::NodeHandle nhOut
Node handle for topic publication.
Definition: generic_lazy_pubsub.hpp:200
cras::GenericLazyPubSub::subscribeOptions
const ::ros::SubscribeOptions subscribeOptions
Options used when subscribing to the input topic.
Definition: generic_lazy_pubsub.hpp:212
log_utils.h
cras::GenericLazyPubSub::outQueueSize
size_t outQueueSize
Queue size of the output publisher.
Definition: generic_lazy_pubsub.hpp:188
subscriber.h
cras::GenericLazyPubSub::pub
::ros::Publisher pub
The output publisher. It will be invalid until first message is received.
Definition: generic_lazy_pubsub.hpp:191
cras::GenericLazyPubSub::pubCreateMutex
::std::mutex pubCreateMutex
Mutex protecting pub.
Definition: generic_lazy_pubsub.hpp:206
cras::GenericLazyPubSub::inQueueSize
size_t inQueueSize
Queue size of the input subscriber.
Definition: generic_lazy_pubsub.hpp:185
ros::NodeHandle
ros::Publisher
single_subscriber_publisher.h
advertise_options.h
ros::SubscribeOptions
cras::GenericLazyPubSub::topicIn
::std::string topicIn
Input topic (relative to nh).
Definition: generic_lazy_pubsub.hpp:179
node.h
cras::ConditionalSubscriber
A lazy subscriber that subscribes only when a condition is met.
Definition: lazy_subscriber.hpp:33
cras::GenericLazyPubSub::createAdvertiseOptions
virtual ::ros::AdvertiseOptions createAdvertiseOptions(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Create ros::AdvertiseOptions from a message event.
Definition: generic_lazy_pubsub.cpp:98
ros::Subscriber
cras::GenericLazyPubSub::connectCb
void connectCb(const ::ros::SingleSubscriberPublisher &)
Callback that is called whenever someone (un)subscribes from the publisher.
Definition: generic_lazy_pubsub.cpp:63
message_event.h
subscribe_options.h
ros::Subscriber
cras::GenericLazyPubSub::topicOut
::std::string topicOut
Output topic (relative to nh).
Definition: generic_lazy_pubsub.hpp:182


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sun Jan 14 2024 03:48:28