Public Member Functions | Protected Member Functions | Protected Attributes
opencv_apps::Nodelet Class Reference

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

#include <nodelet.h>

Inheritance diagram for opencv_apps::Nodelet:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 Nodelet ()

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, const std::string &topic, int queue_size)
 Advertise an image topic camera info 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.
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 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

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.
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_
 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 65 of file nodelet.h.


Constructor & Destructor Documentation

Reimplemented from nodelet::Nodelet.

Definition at line 68 of file nodelet.h.


Member Function Documentation

template<class T >
ros::Publisher opencv_apps::Nodelet::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 152 of file nodelet.h.

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

Advertise an image topic camera info 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 221 of file nodelet.h.

image_transport::Publisher opencv_apps::Nodelet::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 185 of file 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 152 of file nodelet.cpp.

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

Definition at line 140 of file nodelet.cpp.

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

Definition at line 146 of file nodelet.cpp.

callback function which is called when new subscriber come

Definition at line 73 of file nodelet.cpp.

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

Definition at line 106 of file nodelet.cpp.

void opencv_apps::Nodelet::onInit ( ) [protected, virtual]
void opencv_apps::Nodelet::onInitPostProcess ( ) [protected, virtual]

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

Definition at line 59 of file nodelet.cpp.

virtual void opencv_apps::Nodelet::subscribe ( ) [protected, pure virtual]
virtual void opencv_apps::Nodelet::unsubscribe ( ) [protected, pure virtual]
void opencv_apps::Nodelet::warnNeverSubscribedCallback ( const ros::WallTimerEvent event) [protected, virtual]

callback function which is called when walltimer duration run out.

Definition at line 66 of file 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 302 of file nodelet.h.

List of watching camera publishers.

Definition at line 269 of file nodelet.h.

boost::mutex opencv_apps::Nodelet::connection_mutex_ [protected]

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

Definition at line 254 of file nodelet.h.

Status of connection.

Definition at line 307 of file nodelet.h.

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

Definition at line 296 of file nodelet.h.

List of watching image publishers.

Definition at line 264 of file nodelet.h.

boost::shared_ptr<ros::NodeHandle> opencv_apps::Nodelet::nh_ [protected]

Shared pointer to nodehandle.

Reimplemented from nodelet::Nodelet.

Definition at line 274 of file nodelet.h.

boost::shared_ptr<ros::NodeHandle> opencv_apps::Nodelet::pnh_ [protected]

Shared pointer to private nodehandle.

Definition at line 279 of file nodelet.h.

List of watching publishers.

Definition at line 259 of file nodelet.h.

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

Definition at line 290 of file nodelet.h.

WallTimer instance for warning about no connection.

Definition at line 284 of file nodelet.h.

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

Definition at line 312 of file nodelet.h.


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


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:59