Go to the documentation of this file.
17 #include <boost/functional.hpp>
26 #include <topic_tools/shape_shifter.h>
68 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
84 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
99 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
115 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
130 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
144 const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
162 void connectCb(const ::ros::SingleSubscriberPublisher&);
168 void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
176 const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
A pair of lazy subscriber and publisher which use the same message type (unknown at compile time).
::cras::optional<::ros::AdvertiseOptions > advertiseOptions
The options used when the publisher was created. nullopt before the publisher is created.
void subscribe(::ros::Subscriber &sub)
Perform the subscription to the input topic.
bool shouldBeSubscribed() const override
Returns true when the subscriber should be connected - i.e. either at the start, or when pub has clie...
const typedef ::ros::MessageEvent<::topic_tools::ShapeShifter const > & CallbackMessageType
Signature of the subscriber's callback.
::ros::NodeHandle nhIn
Node handle for topic subscription.
::cras::GenericLazyPubSub::CallbackType callback
The user callback to be called when a message is received.
::boost::function< void(::cras::GenericLazyPubSub::CallbackMessageType, ::ros::Publisher &)> CallbackType
Type of the user callback passed to this class.
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...
Lazy subscriber that subscribes only when a paired publisher has subscribers.
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.
::ros::Subscriber sub
The input subscriber.
::ros::NodeHandle nhOut
Node handle for topic publication.
const ::ros::SubscribeOptions subscribeOptions
Options used when subscribing to the input topic.
size_t outQueueSize
Queue size of the output publisher.
::ros::Publisher pub
The output publisher. It will be invalid until first message is received.
::std::mutex pubCreateMutex
Mutex protecting pub.
size_t inQueueSize
Queue size of the input subscriber.
::std::string topicIn
Input topic (relative to nh).
A lazy subscriber that subscribes only when a condition is met.
virtual ::ros::AdvertiseOptions createAdvertiseOptions(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Create ros::AdvertiseOptions from a message event.
void connectCb(const ::ros::SingleSubscriberPublisher &)
Callback that is called whenever someone (un)subscribes from the publisher.
::std::string topicOut
Output topic (relative to nh).
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sun Jan 5 2025 03:50:49