A pair of lazy subscriber and publisher which use the same message type (unknown at compile time). More...
#include <generic_lazy_pubsub.hpp>
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::AdvertiseOptions > | advertiseOptions |
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 |
A pair of lazy subscriber and publisher which use the same message type (unknown at compile time).
LazySubscriber
. Definition at line 44 of file generic_lazy_pubsub.hpp.
typedef ::boost::function<void(::cras::GenericLazyPubSub::CallbackMessageType, ::ros::Publisher&)> cras::GenericLazyPubSub::CallbackType |
Type of the user callback passed to this class.
Definition at line 51 of file generic_lazy_pubsub.hpp.
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.
[in] | nhIn | Node handle for message subscription. |
[in] | topicIn | Input topic (relative to nhIn ). |
[in] | nhOut | Node handle for message publication. |
[in] | topicOut | Output topic (relative to nhOut ). |
[in] | inQueueSize | Queue size of the input subscriber. |
[in] | outQueueSize | Queue size of the output publisher. |
[in] | callback | The callback to call when a message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. |
[in] | logHelper | Log helper. |
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).
[in] | nhIn | Node handle for message subscription. |
[in] | topicIn | Input topic (relative to nhIn ). |
[in] | nhOut | Node handle for message publication. |
[in] | topicOut | Output topic (relative to nhOut ). |
[in] | queueSize | Queue size of the subscriber and publisher. |
[in] | callback | The callback to call when a message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. |
[in] | logHelper | Log helper. |
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).
[in] | nhIn | Node handle for message subscription. |
[in] | topicIn | Input topic (relative to nhIn ). |
[in] | nhOut | Node handle for message publication. |
[in] | topicOut | Output topic (relative to nhOut ). |
[in] | callback | The callback to call when a message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. |
[in] | logHelper | Log helper. |
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).
[in] | nh | Node handle for message subscription and publication. |
[in] | topicIn | Input topic (relative to nh ). |
[in] | topicOut | Output topic (relative to nh ). |
[in] | inQueueSize | Queue size of the input subscriber. |
[in] | outQueueSize | Queue size of the output publisher. |
[in] | callback | The callback to call when a message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. |
[in] | logHelper | Log helper. |
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).
[in] | nh | Node handle for message subscription and publication. |
[in] | topicIn | Input topic (relative to nh ). |
[in] | topicOut | Output topic (relative to nh ). |
[in] | queueSize | Queue size of the subscriber and publisher. |
[in] | callback | The callback to call when a message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. |
[in] | logHelper | Log helper. |
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).
[in] | nh | Node handle for message subscription and publication. |
[in] | topicIn | Input topic (relative to nh ). |
[in] | topicOut | Output topic (relative to nh ). |
[in] | callback | The callback to call when a message is received. |
[in] | subscribeOptions | Options used when creating the subscriber. |
[in] | logHelper | Log helper. |
|
protected |
Callback for the received messages from subscriber. It also handles publisher creation if none exists.
[in] | event | The message event. |
Definition at line 70 of file generic_lazy_pubsub.cpp.
|
protected |
Callback that is called whenever someone (un)subscribes from the publisher.
Definition at line 63 of file generic_lazy_pubsub.cpp.
|
protected |
Create ros::AdvertiseOptions from a message event.
[in] | event | The event to examine. |
Definition at line 98 of file generic_lazy_pubsub.cpp.
|
overrideprotectedvirtual |
Returns true when the subscriber should be connected - i.e. either at the start, or when pub has clients.
Implements cras::ConditionalSubscriber.
Definition at line 56 of file generic_lazy_pubsub.cpp.
|
protected |
Perform the subscription to the input topic.
[out] | sub | The subscriber reference to fill with the created subscriber. |
Definition at line 48 of file generic_lazy_pubsub.cpp.
|
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.
|
protected |
The user callback to be called when a message is received.
Definition at line 203 of file generic_lazy_pubsub.hpp.
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.
|
protected |
Queue size of the input subscriber.
Definition at line 185 of file generic_lazy_pubsub.hpp.
|
protected |
Node handle for topic subscription.
Definition at line 197 of file generic_lazy_pubsub.hpp.
|
protected |
Node handle for topic publication.
Definition at line 200 of file generic_lazy_pubsub.hpp.
|
protected |
Queue size of the output publisher.
Definition at line 188 of file generic_lazy_pubsub.hpp.
|
protected |
The output publisher. It will be invalid until first message is received.
Definition at line 191 of file generic_lazy_pubsub.hpp.
|
protected |
Mutex protecting pub
.
Definition at line 206 of file generic_lazy_pubsub.hpp.
|
protected |
The input subscriber.
Definition at line 194 of file generic_lazy_pubsub.hpp.
|
protected |
Options used when subscribing to the input topic.
Definition at line 212 of file generic_lazy_pubsub.hpp.
|
protected |
Input topic (relative to nh
).
Definition at line 179 of file generic_lazy_pubsub.hpp.
|
protected |
Output topic (relative to nh
).
Definition at line 182 of file generic_lazy_pubsub.hpp.