Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nodelet_topic_tools::NodeletLazy Class Referenceabstract

Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics. More...

#include <nodelet_lazy.h>

Inheritance diagram for nodelet_topic_tools::NodeletLazy:
Inheritance graph
[legend]

Public Member Functions

 NodeletLazy ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

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. More...
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come More...
 
virtual void onInit ()
 Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method. More...
 
virtual void onInitPostProcess ()
 Post processing of initialization of nodelet. You need to call this method in order to use always_subscribe feature. More...
 
virtual void subscribe ()=0
 This method is called when publisher is subscribed by other nodes. Set up subscribers in this method. More...
 
virtual void unsubscribe ()=0
 This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method. More...
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 callback function which is called when walltimer duration run out. More...
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

boost::mutex connection_mutex_
 mutex to call subscribe() and unsubscribe() in critical section. More...
 
ConnectionStatus connection_status_
 Status of connection. More...
 
bool ever_subscribed_
 A flag to check if the node has been ever subscribed or not. More...
 
bool lazy_
 A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~lazy parameter. More...
 
boost::shared_ptr< ros::NodeHandlenh_
 Shared pointer to nodehandle. More...
 
boost::shared_ptr< ros::NodeHandlepnh_
 Shared pointer to private nodehandle. More...
 
std::vector< ros::Publisherpublishers_
 List of watching publishers. More...
 
ros::WallTimer timer_ever_subscribed_
 WallTimer instance for warning about no connection. More...
 
bool verbose_connection_
 true if ~verbose_connection or verbose_connection parameter is true. More...
 

Detailed Description

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 102 of file nodelet_lazy.h.

Constructor & Destructor Documentation

◆ NodeletLazy()

nodelet_topic_tools::NodeletLazy::NodeletLazy ( )
inline

Definition at line 105 of file nodelet_lazy.h.

Member Function Documentation

◆ advertise()

template<class T >
ros::Publisher nodelet_topic_tools::NodeletLazy::advertise ( ros::NodeHandle nh,
std::string  topic,
int  queue_size,
bool  latch = false 
)
inlineprotected

Update the list of Publishers created by this method. It automatically reads latch boolean parameter from nh and publish topic with appropriate latch parameter.

Parameters
nhNodeHandle.
topictopic name to advertise.
queue_sizequeue size for publisher.
latchset true if latch topic publication.
Returns
Publisher for the advertised topic.

Definition at line 251 of file nodelet_lazy.h.

◆ connectionCallback()

virtual void nodelet_topic_tools::NodeletLazy::connectionCallback ( const ros::SingleSubscriberPublisher pub)
inlineprotectedvirtual

callback function which is called when new subscriber come

Definition at line 170 of file nodelet_lazy.h.

◆ onInit()

virtual void nodelet_topic_tools::NodeletLazy::onInit ( )
inlineprotectedvirtual

Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.

Implements nodelet::Nodelet.

Definition at line 112 of file nodelet_lazy.h.

◆ onInitPostProcess()

virtual void nodelet_topic_tools::NodeletLazy::onInitPostProcess ( )
inlineprotectedvirtual

Post processing of initialization of nodelet. You need to call this method in order to use always_subscribe feature.

Definition at line 157 of file nodelet_lazy.h.

◆ subscribe()

virtual void nodelet_topic_tools::NodeletLazy::subscribe ( )
protectedpure virtual

This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.

◆ unsubscribe()

virtual void nodelet_topic_tools::NodeletLazy::unsubscribe ( )
protectedpure virtual

This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.

◆ warnNeverSubscribedCallback()

virtual void nodelet_topic_tools::NodeletLazy::warnNeverSubscribedCallback ( const ros::WallTimerEvent event)
inlineprotectedvirtual

callback function which is called when walltimer duration run out.

Definition at line 216 of file nodelet_lazy.h.

Member Data Documentation

◆ connection_mutex_

boost::mutex nodelet_topic_tools::NodeletLazy::connection_mutex_
protected

mutex to call subscribe() and unsubscribe() in critical section.

Definition at line 272 of file nodelet_lazy.h.

◆ connection_status_

ConnectionStatus nodelet_topic_tools::NodeletLazy::connection_status_
protected

Status of connection.

Definition at line 309 of file nodelet_lazy.h.

◆ ever_subscribed_

bool nodelet_topic_tools::NodeletLazy::ever_subscribed_
protected

A flag to check if the node has been ever subscribed or not.

Definition at line 298 of file nodelet_lazy.h.

◆ lazy_

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 304 of file nodelet_lazy.h.

◆ nh_

boost::shared_ptr<ros::NodeHandle> nodelet_topic_tools::NodeletLazy::nh_
protected

Shared pointer to nodehandle.

Definition at line 277 of file nodelet_lazy.h.

◆ pnh_

boost::shared_ptr<ros::NodeHandle> nodelet_topic_tools::NodeletLazy::pnh_
protected

Shared pointer to private nodehandle.

Definition at line 282 of file nodelet_lazy.h.

◆ publishers_

std::vector<ros::Publisher> nodelet_topic_tools::NodeletLazy::publishers_
protected

List of watching publishers.

Definition at line 287 of file nodelet_lazy.h.

◆ timer_ever_subscribed_

ros::WallTimer nodelet_topic_tools::NodeletLazy::timer_ever_subscribed_
protected

WallTimer instance for warning about no connection.

Definition at line 292 of file nodelet_lazy.h.

◆ verbose_connection_

bool nodelet_topic_tools::NodeletLazy::verbose_connection_
protected

true if ~verbose_connection or verbose_connection parameter is true.

Definition at line 314 of file nodelet_lazy.h.


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


nodelet_topic_tools
Author(s): Radu Bogdan Rusu, Tully Foote, Michael Carroll
autogenerated on Fri Nov 15 2024 03:38:12