Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics. More...
#include <nodelet.h>
Public Member Functions | |
Nodelet () | |
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) |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
virtual void | cameraConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
callback function which is called when new subscriber come for camera image publisher More... | |
virtual void | cameraInfoConnectionCallback (const ros::SingleSubscriberPublisher &pub) |
callback function which is called when new subscriber come for camera info publisher More... | |
virtual void | connectionCallback (const ros::SingleSubscriberPublisher &pub) |
callback function which is called when new subscriber come More... | |
virtual void | imageConnectionCallback (const image_transport::SingleSubscriberPublisher &pub) |
callback function which is called when new subscriber come for image publisher 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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
Protected Attributes | |
bool | always_subscribe_ |
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~always_subscribe parameter. More... | |
std::vector< image_transport::CameraPublisher > | camera_publishers_ |
List of watching camera publishers. More... | |
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... | |
std::vector< image_transport::Publisher > | image_publishers_ |
List of watching image publishers. More... | |
boost::shared_ptr< ros::NodeHandle > | nh_ |
Shared pointer to nodehandle. More... | |
boost::shared_ptr< ros::NodeHandle > | pnh_ |
Shared pointer to private nodehandle. More... | |
std::vector< ros::Publisher > | publishers_ |
List of watching publishers. More... | |
bool | subscribed_ |
A flag to check if any publisher is already subscribed or not. More... | |
ros::WallTimer | timer_ |
WallTimer instance for warning about no connection. More... | |
bool | verbose_connection_ |
true if ~verbose_connection or verbose_connection parameter is true. More... | |
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().
|
inlineprotected |
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.
nh | NodeHandle. |
topic | topic name to advertise. |
queue_size | queue size for publisher. |
latch | set true if latch topic publication. |
|
inlineprotected |
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.
nh | NodeHandle. |
topic | topic name to advertise. |
queue_size | queue size for publisher. |
latch | set true if latch topic publication. |
|
inlineprotected |
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.
nh | NodeHandle. |
topic | topic name to advertise. |
queue_size | queue size for publisher. |
latch | set true if latch topic publication. |
|
protectedvirtual |
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 165 of file nodelet.cpp.
|
protectedvirtual |
callback function which is called when new subscriber come for camera image publisher
Definition at line 155 of file nodelet.cpp.
|
protectedvirtual |
callback function which is called when new subscriber come for camera info publisher
Definition at line 160 of file nodelet.cpp.
|
protectedvirtual |
callback function which is called when new subscriber come
Definition at line 73 of file nodelet.cpp.
|
protectedvirtual |
callback function which is called when new subscriber come for image publisher
Definition at line 114 of file nodelet.cpp.
|
protectedvirtual |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Implements nodelet::Nodelet.
Reimplemented in face_recognition::FaceRecognitionNodelet, opencv_apps::FaceRecognitionNodelet, camshift::CamShiftNodelet, color_filter::HSVColorFilterNodelet, color_filter::HLSColorFilterNodelet, color_filter::RGBColorFilterNodelet, hough_circles::HoughCirclesNodelet, opencv_apps::HSVColorFilterNodelet, watershed_segmentation::WatershedSegmentationNodelet, lk_flow::LKFlowNodelet, opencv_apps::CamShiftNodelet, opencv_apps::HoughCirclesNodelet, edge_detection::EdgeDetectionNodelet, hough_lines::HoughLinesNodelet, opencv_apps::LKFlowNodelet, opencv_apps::WatershedSegmentationNodelet, opencv_apps::HLSColorFilterNodelet, contour_moments::ContourMomentsNodelet, segment_objects::SegmentObjectsNodelet, opencv_apps::EdgeDetectionNodelet, general_contours::GeneralContoursNodelet, opencv_apps::HoughLinesNodelet, face_detection::FaceDetectionNodelet, simple_flow::SimpleFlowNodelet, adding_images::AddingImagesNodelet, opencv_apps::ContourMomentsNodelet, convex_hull::ConvexHullNodelet, find_contours::FindContoursNodelet, goodfeature_track::GoodfeatureTrackNodelet, opencv_apps::GeneralContoursNodelet, opencv_apps::SegmentObjectsNodelet, people_detect::PeopleDetectNodelet, fback_flow::FBackFlowNodelet, opencv_apps::AddingImagesNodelet, opencv_apps::SimpleFlowNodelet, smoothing::SmoothingNodelet, phase_corr::PhaseCorrNodelet, opencv_apps::RGBColorFilterNodelet, corner_harris::CornerHarrisNodelet, opencv_apps::FaceDetectionNodelet, opencv_apps::ConvexHullNodelet, opencv_apps::FindContoursNodelet, opencv_apps::GoodfeatureTrackNodelet, discrete_fourier_transform::DiscreteFourierTransformNodelet, opencv_apps::PeopleDetectNodelet, opencv_apps::FBackFlowNodelet, opencv_apps::SmoothingNodelet, opencv_apps::PhaseCorrNodelet, opencv_apps::CornerHarrisNodelet, pyramids::PyramidsNodelet, opencv_apps::DiscreteFourierTransformNodelet, threshold::ThresholdNodelet, opencv_apps::ColorFilterNodelet< Config >, opencv_apps::PyramidsNodelet, opencv_apps::ColorFilterNodelet< opencv_apps::HLSColorFilterConfig >, opencv_apps::ColorFilterNodelet< opencv_apps::HSVColorFilterConfig >, opencv_apps::ColorFilterNodelet< opencv_apps::RGBColorFilterConfig >, and opencv_apps::ThresholdNodelet.
Definition at line 40 of file nodelet.cpp.
|
protectedvirtual |
Post processing of initialization of nodelet. You need to call this method in order to use always_subscribe feature.
Definition at line 57 of file nodelet.cpp.
|
protectedpure virtual |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Implemented in opencv_apps::FaceRecognitionNodelet, opencv_apps::CamShiftNodelet, opencv_apps::HoughCirclesNodelet, opencv_apps::LKFlowNodelet, opencv_apps::WatershedSegmentationNodelet, opencv_apps::EdgeDetectionNodelet, opencv_apps::HoughLinesNodelet, opencv_apps::ContourMomentsNodelet, opencv_apps::GeneralContoursNodelet, opencv_apps::SegmentObjectsNodelet, opencv_apps::SimpleFlowNodelet, opencv_apps::FaceDetectionNodelet, opencv_apps::ConvexHullNodelet, opencv_apps::FindContoursNodelet, opencv_apps::GoodfeatureTrackNodelet, opencv_apps::PeopleDetectNodelet, opencv_apps::FBackFlowNodelet, opencv_apps::SmoothingNodelet, opencv_apps::PhaseCorrNodelet, opencv_apps::CornerHarrisNodelet, opencv_apps::ColorFilterNodelet< Config >, opencv_apps::PyramidsNodelet, opencv_apps::ColorFilterNodelet< opencv_apps::HLSColorFilterConfig >, opencv_apps::ColorFilterNodelet< opencv_apps::HSVColorFilterConfig >, opencv_apps::ColorFilterNodelet< opencv_apps::RGBColorFilterConfig >, opencv_apps::AddingImagesNodelet, opencv_apps::ThresholdNodelet, and opencv_apps::DiscreteFourierTransformNodelet.
|
protectedpure virtual |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.
Implemented in opencv_apps::FaceRecognitionNodelet, opencv_apps::CamShiftNodelet, opencv_apps::HoughCirclesNodelet, opencv_apps::LKFlowNodelet, opencv_apps::WatershedSegmentationNodelet, opencv_apps::EdgeDetectionNodelet, opencv_apps::HoughLinesNodelet, opencv_apps::ContourMomentsNodelet, opencv_apps::GeneralContoursNodelet, opencv_apps::SegmentObjectsNodelet, opencv_apps::SimpleFlowNodelet, opencv_apps::FaceDetectionNodelet, opencv_apps::ConvexHullNodelet, opencv_apps::FindContoursNodelet, opencv_apps::GoodfeatureTrackNodelet, opencv_apps::PeopleDetectNodelet, opencv_apps::FBackFlowNodelet, opencv_apps::SmoothingNodelet, opencv_apps::PhaseCorrNodelet, opencv_apps::CornerHarrisNodelet, opencv_apps::ColorFilterNodelet< Config >, opencv_apps::PyramidsNodelet, opencv_apps::ColorFilterNodelet< opencv_apps::HLSColorFilterConfig >, opencv_apps::ColorFilterNodelet< opencv_apps::HSVColorFilterConfig >, opencv_apps::ColorFilterNodelet< opencv_apps::RGBColorFilterConfig >, opencv_apps::AddingImagesNodelet, opencv_apps::ThresholdNodelet, and opencv_apps::DiscreteFourierTransformNodelet.
|
protectedvirtual |
callback function which is called when walltimer duration run out.
Definition at line 65 of file nodelet.cpp.
|
protected |
|
protected |
|
protected |
mutex to call subscribe() and unsubscribe() in critical section.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |