Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics. More...
#include <nodelet_lazy.h>
Public Member Functions | |
NodeletLazy () | |
Protected Member Functions | |
template<class T > | |
ros::Publisher | advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false) |
Update the list of Publishers created by this method. It automatically reads latch boolean parameter from nh and publish topic with appropriate latch parameter. | |
virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) |
callback function which is called when new subscriber come | |
virtual void | onInit () |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method. | |
virtual void | onInitPostProcess () |
Post processing of initialization of nodelet. You need to call this method in order to use always_subscribe feature. | |
virtual void | subscribe ()=0 |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method. | |
virtual void | unsubscribe ()=0 |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method. | |
virtual void | warnNeverSubscribedCallback (const ros::WallTimerEvent &event) |
callback function which is called when walltimer duration run out. | |
Protected Attributes | |
boost::mutex | connection_mutex_ |
mutex to call subscribe() and unsubscribe() in critical section. | |
ConnectionStatus | connection_status_ |
Status of connection. | |
bool | ever_subscribed_ |
A flag to check if the node has been ever subscribed or not. | |
bool | lazy_ |
A flag to disable watching mechanism and always subscribe input topics. It can be specified via `~lazy` parameter. | |
boost::shared_ptr < ros::NodeHandle > | nh_ |
Shared pointer to nodehandle. | |
boost::shared_ptr < ros::NodeHandle > | pnh_ |
Shared pointer to private nodehandle. | |
std::vector< ros::Publisher > | publishers_ |
List of watching publishers. | |
ros::WallTimer | timer_ever_subscribed_ |
WallTimer instance for warning about no connection. | |
bool | verbose_connection_ |
true if `~verbose_connection` or `verbose_connection` parameter is true. |
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
It's important not to subscribe topic if no output is required.
In order to watch advertised topics, need to use advertise template method. And create subscribers in subscribe() and shutdown them in unsubscribed().
Definition at line 70 of file nodelet_lazy.h.
nodelet_topic_tools::NodeletLazy::NodeletLazy | ( | ) | [inline] |
Definition at line 73 of file nodelet_lazy.h.
ros::Publisher nodelet_topic_tools::NodeletLazy::advertise | ( | ros::NodeHandle & | nh, |
std::string | topic, | ||
int | queue_size, | ||
bool | latch = false |
||
) | [inline, protected] |
Update the list of Publishers created by this method. It automatically reads latch boolean parameter from nh and publish topic with appropriate latch parameter.
nh | NodeHandle. |
topic | topic name to advertise. |
queue_size | queue size for publisher. |
latch | set true if latch topic publication. |
Definition at line 219 of file nodelet_lazy.h.
virtual void nodelet_topic_tools::NodeletLazy::connectionCallback | ( | const ros::SingleSubscriberPublisher & | pub | ) | [inline, protected, virtual] |
callback function which is called when new subscriber come
Definition at line 138 of file nodelet_lazy.h.
virtual void nodelet_topic_tools::NodeletLazy::onInit | ( | ) | [inline, protected, virtual] |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Implements nodelet::Nodelet.
Definition at line 80 of file nodelet_lazy.h.
virtual void nodelet_topic_tools::NodeletLazy::onInitPostProcess | ( | ) | [inline, protected, virtual] |
Post processing of initialization of nodelet. You need to call this method in order to use always_subscribe feature.
Definition at line 125 of file nodelet_lazy.h.
virtual void nodelet_topic_tools::NodeletLazy::subscribe | ( | ) | [protected, pure virtual] |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
virtual void nodelet_topic_tools::NodeletLazy::unsubscribe | ( | ) | [protected, pure virtual] |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.
virtual void nodelet_topic_tools::NodeletLazy::warnNeverSubscribedCallback | ( | const ros::WallTimerEvent & | event | ) | [inline, protected, virtual] |
callback function which is called when walltimer duration run out.
Definition at line 184 of file nodelet_lazy.h.
boost::mutex nodelet_topic_tools::NodeletLazy::connection_mutex_ [protected] |
mutex to call subscribe() and unsubscribe() in critical section.
Definition at line 240 of file nodelet_lazy.h.
Status of connection.
Definition at line 277 of file nodelet_lazy.h.
bool nodelet_topic_tools::NodeletLazy::ever_subscribed_ [protected] |
A flag to check if the node has been ever subscribed or not.
Definition at line 266 of file nodelet_lazy.h.
bool nodelet_topic_tools::NodeletLazy::lazy_ [protected] |
A flag to disable watching mechanism and always subscribe input topics. It can be specified via `~lazy` parameter.
Definition at line 272 of file nodelet_lazy.h.
boost::shared_ptr<ros::NodeHandle> nodelet_topic_tools::NodeletLazy::nh_ [protected] |
Shared pointer to nodehandle.
Reimplemented from nodelet::Nodelet.
Definition at line 245 of file nodelet_lazy.h.
boost::shared_ptr<ros::NodeHandle> nodelet_topic_tools::NodeletLazy::pnh_ [protected] |
Shared pointer to private nodehandle.
Definition at line 250 of file nodelet_lazy.h.
std::vector<ros::Publisher> nodelet_topic_tools::NodeletLazy::publishers_ [protected] |
List of watching publishers.
Definition at line 255 of file nodelet_lazy.h.
WallTimer instance for warning about no connection.
Definition at line 260 of file nodelet_lazy.h.
bool nodelet_topic_tools::NodeletLazy::verbose_connection_ [protected] |
true if `~verbose_connection` or `verbose_connection` parameter is true.
Definition at line 282 of file nodelet_lazy.h.