Go to the documentation of this file.
35 #ifndef OPENCV_APPS_NODELET_H_
36 #define OPENCV_APPS_NODELET_H_
40 #include <boost/thread.hpp>
42 #if BOOST_VERSION < 106000 // since 1.60.0, boost uses placeholders namesapce for _1,_2...
43 #ifndef BOOST_PLAEHOLDERS
44 #define BOOST_PLAEHOLDERS
47 namespace placeholders
49 extern boost::arg<1>
_1;
50 extern boost::arg<2>
_2;
51 extern boost::arg<3>
_3;
52 extern boost::arg<4>
_4;
53 extern boost::arg<5>
_5;
54 extern boost::arg<6>
_6;
55 extern boost::arg<7>
_7;
56 extern boost::arg<8>
_8;
57 extern boost::arg<9>
_9;
60 #endif // BOOST_PLAEHOLDERS
61 #endif // BOOST_VERSION < 106000
182 nh.
param(
"latch", latch,
false);
209 nh.
param(
"latch", latch,
false);
241 nh.
param(
"latch", latch,
false);
243 topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb,
ros::VoidPtr(), latch);
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.
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
std::vector< ros::Publisher > publishers_
List of watching publishers.
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....
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Publisher advertise(AdvertiseOptions &ops)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
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
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....
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
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...
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
boost::shared_ptr< void const > VoidConstPtr
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.
bool subscribed_
A flag to check if any publisher is already subscribed or not.
ConnectionStatus
Enum to represent connection status.
Demo code to calculate moments.
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.
T param(const std::string ¶m_name, const T &default_val) const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
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.
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49