Class GenericLazyPubSub
Defined in File generic_lazy_pubsub.hpp
Inheritance Relationships
Base Type
public cras::ConditionalSubscriber(Class ConditionalSubscriber)
Class Documentation
-
class GenericLazyPubSub : public cras::ConditionalSubscriber
A pair of lazy subscriber and publisher which use the same message type (unknown at compile time).
Note
If publisher type is known at compile time, use
LazySubscriber.Note
Even though the subscriber is lazy, it has to subscribe to the input topic and receive one message from which it can derive the publisher parameters. After receiving this first message, the subscriber is disconnected in case the publisher has no subscribers.
Public Types
-
typedef const ::ros::MessageEvent<::topic_tools::ShapeShifter const> &CallbackMessageType
Signature of the subscriber’s callback.
-
typedef ::boost::function<void(::cras::GenericLazyPubSub::CallbackMessageType, ::ros::Publisher&)> CallbackType
Type of the user callback passed to this class.
Public Functions
-
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.
- Parameters:
nhIn – [in] Node handle for message subscription.
topicIn – [in] Input topic (relative to
nhIn).nhOut – [in] Node handle for message publication.
topicOut – [in] Output topic (relative to
nhOut).inQueueSize – [in] Queue size of the input subscriber.
outQueueSize – [in] Queue size of the output publisher.
callback – [in] The callback to call when a message is received.
subscribeOptions – [in] Options used when creating the subscriber.
logHelper – [in] Log helper.
-
GenericLazyPubSub(const ::ros::NodeHandle &nhIn, const ::std::string &topicIn, const ::ros::NodeHandle &nhOut, const ::std::string &topicOut, size_t queueSize, CallbackType callback, ::ros::SubscribeOptions subscribeOptions = {}, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())
Create the pair of lazy subscriber and publisher (with equal input and output queue size).
- Parameters:
nhIn – [in] Node handle for message subscription.
topicIn – [in] Input topic (relative to
nhIn).nhOut – [in] Node handle for message publication.
topicOut – [in] Output topic (relative to
nhOut).queueSize – [in] Queue size of the subscriber and publisher.
callback – [in] The callback to call when a message is received.
subscribeOptions – [in] Options used when creating the subscriber.
logHelper – [in] Log helper.
-
GenericLazyPubSub(const ::ros::NodeHandle &nhIn, const ::std::string &topicIn, const ::ros::NodeHandle &nhOut, const ::std::string &topicOut, CallbackType callback, ::ros::SubscribeOptions subscribeOptions = {}, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())
Create the pair of lazy subscriber and publisher (with input and output queue size of 10).
- Parameters:
nhIn – [in] Node handle for message subscription.
topicIn – [in] Input topic (relative to
nhIn).nhOut – [in] Node handle for message publication.
topicOut – [in] Output topic (relative to
nhOut).callback – [in] The callback to call when a message is received.
subscribeOptions – [in] Options used when creating the subscriber.
logHelper – [in] Log helper.
-
GenericLazyPubSub(const ::ros::NodeHandle &nh, const ::std::string &topicIn, 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 (with the same node handle used for input and output).
- Parameters:
nh – [in] Node handle for message subscription and publication.
topicIn – [in] Input topic (relative to
nh).topicOut – [in] Output topic (relative to
nh).inQueueSize – [in] Queue size of the input subscriber.
outQueueSize – [in] Queue size of the output publisher.
callback – [in] The callback to call when a message is received.
subscribeOptions – [in] Options used when creating the subscriber.
logHelper – [in] Log helper.
-
GenericLazyPubSub(const ::ros::NodeHandle &nh, const ::std::string &topicIn, const ::std::string &topicOut, size_t queueSize, CallbackType callback, ::ros::SubscribeOptions subscribeOptions = {}, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())
Create the pair of lazy subscriber and publisher (with the same node handle and queue size used for input and output).
- Parameters:
nh – [in] Node handle for message subscription and publication.
topicIn – [in] Input topic (relative to
nh).topicOut – [in] Output topic (relative to
nh).queueSize – [in] Queue size of the subscriber and publisher.
callback – [in] The callback to call when a message is received.
subscribeOptions – [in] Options used when creating the subscriber.
logHelper – [in] Log helper.
-
GenericLazyPubSub(const ::ros::NodeHandle &nh, const ::std::string &topicIn, const ::std::string &topicOut, CallbackType callback, ::ros::SubscribeOptions subscribeOptions = {}, const ::cras::LogHelperPtr &logHelper = ::std::make_shared<::cras::NodeLogHelper>())
Create the pair of lazy subscriber and publisher (with the same node handle used for input and output and both using queue size of 10).
- Parameters:
nh – [in] Node handle for message subscription and publication.
topicIn – [in] Input topic (relative to
nh).topicOut – [in] Output topic (relative to
nh).callback – [in] The callback to call when a message is received.
subscribeOptions – [in] Options used when creating the subscriber.
logHelper – [in] Log helper.
Protected Functions
-
void subscribe(::ros::Subscriber &sub)
Perform the subscription to the input topic.
- Parameters:
sub – [out] The subscriber reference to fill with the created subscriber.
-
virtual bool shouldBeSubscribed() const override
Returns true when the subscriber should be connected - i.e. either at the start, or when pub has clients.
- Returns:
Whether the subscriber should be connected.
-
void connectCb(const ::ros::SingleSubscriberPublisher&)
Callback that is called whenever someone (un)subscribes from the publisher.
-
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.
- Parameters:
event – [in] The message event.
-
::ros::AdvertiseOptions createAdvertiseOptions(const ::ros::MessageEvent<::topic_tools::ShapeShifter const> &event)
Create ros::AdvertiseOptions from a message event.
- Parameters:
event – [in] The event to examine.
- Returns:
The advertise options.
Protected Attributes
-
::std::string topicIn
Input topic (relative to
nh).
-
::std::string topicOut
Output topic (relative to
nh).
-
size_t inQueueSize
Queue size of the input subscriber.
-
size_t outQueueSize
Queue size of the output publisher.
-
::ros::Publisher pub
The output publisher. It will be invalid until first message is received.
-
::ros::Subscriber sub
The input subscriber.
-
::ros::NodeHandle nhIn
Node handle for topic subscription.
-
::ros::NodeHandle nhOut
Node handle for topic publication.
-
::cras::GenericLazyPubSub::CallbackType callback
The user callback to be called when a message is received.
-
::std::mutex pubCreateMutex
Mutex protecting
pub.
-
::cras::optional<::ros::AdvertiseOptions> advertiseOptions
The options used when the publisher was created.
nulloptbefore the publisher is created.
-
const ::ros::SubscribeOptions subscribeOptions
Options used when subscribing to the input topic.
-
typedef const ::ros::MessageEvent<::topic_tools::ShapeShifter const> &CallbackMessageType