Go to the documentation of this file.
37 #if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2...
38 #ifndef BOOST_PLAEHOLDERS
39 #define BOOST_PLAEHOLDERS
42 namespace placeholders
55 #endif // BOOST_PLAEHOLDERS
56 #endif // BOOST_VERSION < 106000
97 NODELET_INFO(
"New connection or disconnection is detected");
104 if (pub.getNumSubscribers() > 0)
138 NODELET_INFO(
"New image connection or disconnection is detected");
189 NODELET_INFO(
"New image connection or disconnection is detected");
196 if (pub.getNumSubscribers() > 0)
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
ConnectionStatus connection_status_
Status of connection.
std::vector< image_transport::Publisher > image_publishers_
List of watching image publishers.
std::vector< ros::Publisher > publishers_
List of watching publishers.
ros::NodeHandle & getMTPrivateNodeHandle() const
#define NODELET_WARN(...)
uint32_t getNumSubscribers() const
virtual void connectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come
virtual void cameraInfoConnectionCallback(const ros::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera info publisher
ros::WallTimer timer_
WallTimer instance for warning about no connection.
virtual void cameraConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for camera image publisher
virtual void unsubscribe()=0
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
virtual void imageConnectionCallback(const image_transport::SingleSubscriberPublisher &pub)
callback function which is called when new subscriber come for image publisher
virtual void warnNeverSubscribedCallback(const ros::WallTimerEvent &event)
callback function which is called when walltimer duration run out.
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
bool verbose_connection_
true if ~verbose_connection or verbose_connection parameter is true.
Demo code to calculate moments.
#define NODELET_INFO(...)
virtual void cameraConnectionBaseCallback()
callback function which is called when new subscriber come for camera image publisher or camera info ...
std::vector< image_transport::CameraPublisher > camera_publishers_
List of watching camera publishers.
virtual void subscribe()=0
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
bool ever_subscribed_
A flag to check if the node has been ever subscribed or not.
const std::string & getName() const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
boost::mutex connection_mutex_
mutex to call subscribe() and unsubscribe() in critical section.
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
ros::NodeHandle & getMTNodeHandle() const
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49