35 #ifndef OPENCV_APPS_NODELET_H_ 36 #define OPENCV_APPS_NODELET_H_ 40 #include <boost/thread.hpp> 161 nh.
param(
"latch", latch,
false);
186 nh.
param(
"latch", latch,
false);
214 nh.
param(
"latch", latch,
false);
216 topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb,
ros::VoidPtr(), latch);
boost::shared_ptr< void const > VoidConstPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
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...
virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for image publisher
Demo code to calculate moments.
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
virtual void unsubscribe()=0
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
virtual void cameraConnectionBaseCallback()
callback function which is called when new subscriber come for camera image publisher or camera info ...
virtual void subscribe()=0
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
ros::WallTimer timer_
WallTimer instance for warning about no connection.
std::vector< image_transport::Publisher > image_publishers_
List of watching image publishers.
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera info publisher ...
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
ConnectionStatus
Enum to represent connection status.
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...
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 t...
ConnectionStatus connection_status_
Status of connection.
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera image publisher ...
bool subscribed_
A flag to check if any publisher is already subscribed or not.
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.
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
std::vector< image_transport::CameraPublisher > camera_publishers_
List of watching camera publishers.
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come
std::vector< ros::Publisher > publishers_
List of watching publishers.