Public Member Functions | Protected Member Functions | Protected Attributes
jsk_topic_tools::ConnectionBasedNodelet Class Reference

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

#include <connection_based_nodelet.h>

Inheritance diagram for jsk_topic_tools::ConnectionBasedNodelet:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 ConnectionBasedNodelet ()

Protected Member Functions

template<class T >
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size)
 Advertise a topic and watch the publisher. Publishers which are created by this method. It automatically reads latch boolean parameter from nh and publish topic with appropriate latch parameter.
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
image_transport::CameraPublisher advertiseCamera (ros::NodeHandle &nh, const std::string &topic, int queue_size)
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, image_transport::ImageTransport &it, const std::string &topic, int queue_size)
image_transport::Publisher advertiseImage (ros::NodeHandle &nh, const std::string &topic, int queue_size)
 Advertise an image topic and watch the publisher. Publishers which are created by this method. It automatically reads latch boolean parameter from nh and it and publish topic with appropriate latch parameter.
virtual void cameraConnectionBaseCallback ()
 callback function which is called when new subscriber come for camera image publisher or camera info publisher. This function is called from cameraConnectionCallback or cameraInfoConnectionCallback.
virtual void cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come for camera image publisher
virtual void cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come for camera info publisher
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come
virtual void imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub)
 callback function which is called when new subscriber come for image publisher
virtual bool isSubscribed ()
 Returns true when this nodelet subscribes topics, false otherwise.
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.
virtual void warnOnInitPostProcessCalledCallback (const ros::WallTimerEvent &event)
 callback function which is called when walltimer duration run out.

Protected Attributes

bool always_subscribe_
 A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~always_subscribe parameter.
std::vector
< image_transport::CameraPublisher
camera_publishers_
 List of watching camera publishers.
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.
std::vector
< image_transport::Publisher
image_publishers_
 List of watching image publishers.
boost::shared_ptr
< ros::NodeHandle
nh_
 Shared pointer to nodehandle.
bool on_init_post_process_called_
 Never warning on not calling onInitPostProcess if true.
boost::shared_ptr
< ros::NodeHandle
pnh_
 Shared pointer to private nodehandle.
std::vector< ros::Publisherpublishers_
 List of watching publishers.
bool subscribed_
 A flag to check if any publisher is already subscribed or not.
ros::WallTimer timer_warn_never_subscribed_
 WallTimer instance for warning about no connection.
ros::WallTimer timer_warn_on_init_post_process_called_
 WallTimer instance for warning about no connection.
bool verbose_connection_
 true if `~verbose_connection` or `verbose_connection` parameter is true.

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 68 of file connection_based_nodelet.h.


Constructor & Destructor Documentation

Definition at line 71 of file connection_based_nodelet.h.


Member Function Documentation

template<class T >
ros::Publisher jsk_topic_tools::ConnectionBasedNodelet::advertise ( ros::NodeHandle nh,
std::string  topic,
int  queue_size 
) [inline, protected]

Advertise a topic and watch the publisher. Publishers which are 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 166 of file connection_based_nodelet.h.

image_transport::CameraPublisher jsk_topic_tools::ConnectionBasedNodelet::advertiseCamera ( ros::NodeHandle nh,
image_transport::ImageTransport it,
const std::string &  topic,
int  queue_size 
) [inline, protected]

Definition at line 234 of file connection_based_nodelet.h.

image_transport::CameraPublisher jsk_topic_tools::ConnectionBasedNodelet::advertiseCamera ( ros::NodeHandle nh,
const std::string &  topic,
int  queue_size 
) [inline, protected]

Definition at line 244 of file connection_based_nodelet.h.

image_transport::Publisher jsk_topic_tools::ConnectionBasedNodelet::advertiseImage ( ros::NodeHandle nh,
image_transport::ImageTransport it,
const std::string &  topic,
int  queue_size 
) [inline, protected]

Definition at line 187 of file connection_based_nodelet.h.

image_transport::Publisher jsk_topic_tools::ConnectionBasedNodelet::advertiseImage ( ros::NodeHandle nh,
const std::string &  topic,
int  queue_size 
) [inline, protected]

Advertise an image topic and watch the publisher. Publishers which are created by this method. It automatically reads latch boolean parameter from nh and it 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 209 of file connection_based_nodelet.h.

callback function which is called when new subscriber come for camera image publisher or camera info publisher. This function is called from cameraConnectionCallback or cameraInfoConnectionCallback.

Definition at line 189 of file connection_based_nodelet.cpp.

callback function which is called when new subscriber come for camera image publisher

Definition at line 177 of file connection_based_nodelet.cpp.

callback function which is called when new subscriber come for camera info publisher

Definition at line 183 of file connection_based_nodelet.cpp.

callback function which is called when new subscriber come

Definition at line 110 of file connection_based_nodelet.cpp.

callback function which is called when new subscriber come for image publisher

Definition at line 143 of file connection_based_nodelet.cpp.

bool jsk_topic_tools::ConnectionBasedNodelet::isSubscribed ( ) [inline, protected, virtual]

Returns true when this nodelet subscribes topics, false otherwise.

Definition at line 90 of file connection_based_nodelet.cpp.

void jsk_topic_tools::ConnectionBasedNodelet::onInit ( ) [protected, virtual]

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

Implements nodelet::Nodelet.

Reimplemented in jsk_topic_tools::DiagnosticNodelet, jsk_topic_tools::VitalCheckerNodelet, and jsk_topic_tools::StringRelay.

Definition at line 41 of file connection_based_nodelet.cpp.

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

Definition at line 80 of file connection_based_nodelet.cpp.

virtual void jsk_topic_tools::ConnectionBasedNodelet::subscribe ( ) [protected, pure virtual]

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

Implemented in jsk_topic_tools::VitalCheckerNodelet, and jsk_topic_tools::StringRelay.

virtual void jsk_topic_tools::ConnectionBasedNodelet::unsubscribe ( ) [protected, pure virtual]

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

Implemented in jsk_topic_tools::VitalCheckerNodelet, and jsk_topic_tools::StringRelay.

callback function which is called when walltimer duration run out.

Definition at line 103 of file connection_based_nodelet.cpp.

callback function which is called when walltimer duration run out.

Definition at line 96 of file connection_based_nodelet.cpp.


Member Data Documentation

A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~always_subscribe parameter.

Definition at line 326 of file connection_based_nodelet.h.

List of watching camera publishers.

Definition at line 293 of file connection_based_nodelet.h.

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

Definition at line 278 of file connection_based_nodelet.h.

Status of connection.

Definition at line 331 of file connection_based_nodelet.h.

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

Definition at line 320 of file connection_based_nodelet.h.

List of watching image publishers.

Definition at line 288 of file connection_based_nodelet.h.

Shared pointer to nodehandle.

Reimplemented from nodelet::Nodelet.

Definition at line 298 of file connection_based_nodelet.h.

Never warning on not calling onInitPostProcess if true.

Definition at line 341 of file connection_based_nodelet.h.

Shared pointer to private nodehandle.

Definition at line 303 of file connection_based_nodelet.h.

List of watching publishers.

Definition at line 283 of file connection_based_nodelet.h.

A flag to check if any publisher is already subscribed or not.

Definition at line 314 of file connection_based_nodelet.h.

WallTimer instance for warning about no connection.

Definition at line 308 of file connection_based_nodelet.h.

WallTimer instance for warning about no connection.

Definition at line 346 of file connection_based_nodelet.h.

true if `~verbose_connection` or `verbose_connection` parameter is true.

Definition at line 336 of file connection_based_nodelet.h.


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


jsk_topic_tools
Author(s): Kei Okada , Yusuke Furuta
autogenerated on Fri Sep 8 2017 03:38:56