Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
cras::GenericLazyPubSub Class Reference

A pair of lazy subscriber and publisher which use the same message type (unknown at compile time). More...

#include <generic_lazy_pubsub.hpp>

Inheritance diagram for cras::GenericLazyPubSub:
Inheritance graph
[legend]

Public Types

typedef ::boost::function< void(::cras::GenericLazyPubSub::CallbackMessageType, ::ros::Publisher &)> CallbackType
 Type of the user callback passed to this class. More...
 
- Public Types inherited from cras::ConditionalSubscriber
typedef ::std::function< void(::ros::Subscriber &sub)> ConnectFn
 Type of the function that connects the subscriber. More...
 
typedef ::std::function< void(::ros::Subscriber &sub)> DisconnectFn
 Type of the function that disconnects the subscriber. More...
 

Public Member Functions

 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). More...
 
 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). More...
 
 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). More...
 
 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). More...
 
 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. More...
 
 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). More...
 
- Public Member Functions inherited from cras::ConditionalSubscriber
 ConditionalSubscriber (ConnectFn connectFn, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
 Create the conditional subscriber. More...
 
 ConditionalSubscriber (ConnectFn connectFn, DisconnectFn disconnectFn, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
 Create the conditional subscriber. More...
 
bool isLazy () const
 Tell whether this subscriber has the lazy behavior enabled. More...
 
bool isSubscribed () const
 Whether the subscriber is currently subscribed to its topic or not. More...
 
void setLazy (bool lazy)
 Set whether the subscriber behaves in the lazy way. More...
 
virtual ~ConditionalSubscriber ()
 Destroy this object and unsubscribe the subscriber if it was subscribed. More...
 
- Public Member Functions inherited from cras::HasLogger
::cras::LogHelperConstPtr getCrasLogger () const
 
 HasLogger (const ::cras::LogHelperPtr &log)
 
void setCrasLogger (const ::cras::LogHelperPtr &log)
 

Public Attributes

const typedef ::ros::MessageEvent<::topic_tools::ShapeShifter const > & CallbackMessageType
 Signature of the subscriber's callback. More...
 

Protected Member Functions

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. More...
 
void connectCb (const ::ros::SingleSubscriberPublisher &)
 Callback that is called whenever someone (un)subscribes from the publisher. More...
 
virtual ::ros::AdvertiseOptions createAdvertiseOptions (const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
 Create ros::AdvertiseOptions from a message event. More...
 
bool shouldBeSubscribed () const override
 Returns true when the subscriber should be connected - i.e. either at the start, or when pub has clients. More...
 
void subscribe (::ros::Subscriber &sub)
 Perform the subscription to the input topic. More...
 
- Protected Member Functions inherited from cras::ConditionalSubscriber
void connectNoLock ()
 Connect the subscriber to its input. More...
 
void disconnectNoLock ()
 Disconnect the subscriber from its input. More...
 
void updateSubscription ()
 The callback called when the condition might have changed. More...
 
void updateSubscriptionNoLock ()
 The callback called when the condition might have changed. More...
 

Protected Attributes

::cras::optional<::ros::AdvertiseOptionsadvertiseOptions
 The options used when the publisher was created. nullopt before the publisher is created. More...
 
::cras::GenericLazyPubSub::CallbackType callback
 The user callback to be called when a message is received. More...
 
size_t inQueueSize
 Queue size of the input subscriber. More...
 
::ros::NodeHandle nhIn
 Node handle for topic subscription. More...
 
::ros::NodeHandle nhOut
 Node handle for topic publication. More...
 
size_t outQueueSize
 Queue size of the output publisher. More...
 
::ros::Publisher pub
 The output publisher. It will be invalid until first message is received. More...
 
::std::mutex pubCreateMutex
 Mutex protecting pub. More...
 
::ros::Subscriber sub
 The input subscriber. More...
 
const ::ros::SubscribeOptions subscribeOptions
 Options used when subscribing to the input topic. More...
 
::std::string topicIn
 Input topic (relative to nh). More...
 
::std::string topicOut
 Output topic (relative to nh). More...
 
- Protected Attributes inherited from cras::ConditionalSubscriber
ConnectFn connectFn
 The function used to establish connection. More...
 
mutable ::std::mutex connectMutex
 Mutex protecting sub and subscribed. More...
 
DisconnectFn disconnectFn
 The function used to close connection. More...
 
bool lazy {true}
 Whether the lazy behavior is enabled (if false, the subscriber is always subscribed). More...
 
::ros::Subscriber sub
 The underlying subscriber (valid only when subscribed is true). More...
 
bool subscribed {false}
 Whether the subscriber is currently subscribed to its topic or not. More...
 
- Protected Attributes inherited from cras::HasLogger
::cras::LogHelperPtr log
 

Detailed Description

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.
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.

Definition at line 44 of file generic_lazy_pubsub.hpp.

Member Typedef Documentation

◆ CallbackType

Type of the user callback passed to this class.

Definition at line 51 of file generic_lazy_pubsub.hpp.

Constructor & Destructor Documentation

◆ GenericLazyPubSub() [1/6]

cras::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.

Parameters
[in]nhInNode handle for message subscription.
[in]topicInInput topic (relative to nhIn).
[in]nhOutNode handle for message publication.
[in]topicOutOutput topic (relative to nhOut).
[in]inQueueSizeQueue size of the input subscriber.
[in]outQueueSizeQueue size of the output publisher.
[in]callbackThe callback to call when a message is received.
[in]subscribeOptionsOptions used when creating the subscriber.
[in]logHelperLog helper.

◆ GenericLazyPubSub() [2/6]

cras::GenericLazyPubSub::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
[in]nhInNode handle for message subscription.
[in]topicInInput topic (relative to nhIn).
[in]nhOutNode handle for message publication.
[in]topicOutOutput topic (relative to nhOut).
[in]queueSizeQueue size of the subscriber and publisher.
[in]callbackThe callback to call when a message is received.
[in]subscribeOptionsOptions used when creating the subscriber.
[in]logHelperLog helper.

◆ GenericLazyPubSub() [3/6]

cras::GenericLazyPubSub::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
[in]nhInNode handle for message subscription.
[in]topicInInput topic (relative to nhIn).
[in]nhOutNode handle for message publication.
[in]topicOutOutput topic (relative to nhOut).
[in]callbackThe callback to call when a message is received.
[in]subscribeOptionsOptions used when creating the subscriber.
[in]logHelperLog helper.

◆ GenericLazyPubSub() [4/6]

cras::GenericLazyPubSub::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
[in]nhNode handle for message subscription and publication.
[in]topicInInput topic (relative to nh).
[in]topicOutOutput topic (relative to nh).
[in]inQueueSizeQueue size of the input subscriber.
[in]outQueueSizeQueue size of the output publisher.
[in]callbackThe callback to call when a message is received.
[in]subscribeOptionsOptions used when creating the subscriber.
[in]logHelperLog helper.

◆ GenericLazyPubSub() [5/6]

cras::GenericLazyPubSub::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
[in]nhNode handle for message subscription and publication.
[in]topicInInput topic (relative to nh).
[in]topicOutOutput topic (relative to nh).
[in]queueSizeQueue size of the subscriber and publisher.
[in]callbackThe callback to call when a message is received.
[in]subscribeOptionsOptions used when creating the subscriber.
[in]logHelperLog helper.

◆ GenericLazyPubSub() [6/6]

cras::GenericLazyPubSub::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
[in]nhNode handle for message subscription and publication.
[in]topicInInput topic (relative to nh).
[in]topicOutOutput topic (relative to nh).
[in]callbackThe callback to call when a message is received.
[in]subscribeOptionsOptions used when creating the subscriber.
[in]logHelperLog helper.

Member Function Documentation

◆ cb()

void cras::GenericLazyPubSub::cb ( const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &  event)
protected

Callback for the received messages from subscriber. It also handles publisher creation if none exists.

Parameters
[in]eventThe message event.

Definition at line 70 of file generic_lazy_pubsub.cpp.

◆ connectCb()

void cras::GenericLazyPubSub::connectCb ( const ::ros::SingleSubscriberPublisher )
protected

Callback that is called whenever someone (un)subscribes from the publisher.

Definition at line 63 of file generic_lazy_pubsub.cpp.

◆ createAdvertiseOptions()

ros::AdvertiseOptions cras::GenericLazyPubSub::createAdvertiseOptions ( const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &  event)
protected

Create ros::AdvertiseOptions from a message event.

Parameters
[in]eventThe event to examine.
Returns
The advertise options.

Definition at line 98 of file generic_lazy_pubsub.cpp.

◆ shouldBeSubscribed()

bool cras::GenericLazyPubSub::shouldBeSubscribed ( ) const
overrideprotectedvirtual

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.

Implements cras::ConditionalSubscriber.

Definition at line 56 of file generic_lazy_pubsub.cpp.

◆ subscribe()

void cras::GenericLazyPubSub::subscribe ( ::ros::Subscriber sub)
protected

Perform the subscription to the input topic.

Parameters
[out]subThe subscriber reference to fill with the created subscriber.

Definition at line 48 of file generic_lazy_pubsub.cpp.

Member Data Documentation

◆ advertiseOptions

::cras::optional<::ros::AdvertiseOptions> cras::GenericLazyPubSub::advertiseOptions
protected

The options used when the publisher was created. nullopt before the publisher is created.

Definition at line 209 of file generic_lazy_pubsub.hpp.

◆ callback

::cras::GenericLazyPubSub::CallbackType cras::GenericLazyPubSub::callback
protected

The user callback to be called when a message is received.

Definition at line 203 of file generic_lazy_pubsub.hpp.

◆ CallbackMessageType

const typedef ::ros::MessageEvent<::topic_tools::ShapeShifter const>& cras::GenericLazyPubSub::CallbackMessageType

Signature of the subscriber's callback.

Definition at line 48 of file generic_lazy_pubsub.hpp.

◆ inQueueSize

size_t cras::GenericLazyPubSub::inQueueSize
protected

Queue size of the input subscriber.

Definition at line 185 of file generic_lazy_pubsub.hpp.

◆ nhIn

::ros::NodeHandle cras::GenericLazyPubSub::nhIn
protected

Node handle for topic subscription.

Definition at line 197 of file generic_lazy_pubsub.hpp.

◆ nhOut

::ros::NodeHandle cras::GenericLazyPubSub::nhOut
protected

Node handle for topic publication.

Definition at line 200 of file generic_lazy_pubsub.hpp.

◆ outQueueSize

size_t cras::GenericLazyPubSub::outQueueSize
protected

Queue size of the output publisher.

Definition at line 188 of file generic_lazy_pubsub.hpp.

◆ pub

::ros::Publisher cras::GenericLazyPubSub::pub
protected

The output publisher. It will be invalid until first message is received.

Definition at line 191 of file generic_lazy_pubsub.hpp.

◆ pubCreateMutex

::std::mutex cras::GenericLazyPubSub::pubCreateMutex
protected

Mutex protecting pub.

Definition at line 206 of file generic_lazy_pubsub.hpp.

◆ sub

::ros::Subscriber cras::GenericLazyPubSub::sub
protected

The input subscriber.

Definition at line 194 of file generic_lazy_pubsub.hpp.

◆ subscribeOptions

const ::ros::SubscribeOptions cras::GenericLazyPubSub::subscribeOptions
protected

Options used when subscribing to the input topic.

Definition at line 212 of file generic_lazy_pubsub.hpp.

◆ topicIn

::std::string cras::GenericLazyPubSub::topicIn
protected

Input topic (relative to nh).

Definition at line 179 of file generic_lazy_pubsub.hpp.

◆ topicOut

::std::string cras::GenericLazyPubSub::topicOut
protected

Output topic (relative to nh).

Definition at line 182 of file generic_lazy_pubsub.hpp.


The documentation for this class was generated from the following files:


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18