77 NODELET_INFO(
"New connection or disconnection is detected");
84 if (pub.getNumSubscribers() > 0)
118 NODELET_INFO(
"New image connection or disconnection is detected");
169 NODELET_INFO(
"New image connection or disconnection is detected");
176 if (pub.getNumSubscribers() > 0)
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
#define NODELET_WARN(...)
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.
const std::string & getName() const
ros::NodeHandle & getMTNodeHandle() const
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 ...
uint32_t getNumSubscribers() const
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.
ros::NodeHandle & getMTPrivateNodeHandle() const
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...
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
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 connection_status_
Status of connection.
#define NODELET_INFO(...)
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 ...
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.