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 102 virtual void onInit();
109 virtual void onInitPostProcess();
140 virtual void cameraConnectionBaseCallback();
177 boost::mutex::scoped_lock lock(connection_mutex_);
182 nh.
param(
"latch", latch,
false);
184 publishers_.push_back(ret);
203 boost::mutex::scoped_lock lock(connection_mutex_);
209 nh.
param(
"latch", latch,
false);
212 image_publishers_.push_back(pub);
231 boost::mutex::scoped_lock lock(connection_mutex_);
241 nh.
param(
"latch", latch,
false);
243 topic, 1, connect_cb, disconnect_cb, info_connect_cb, info_disconnect_cb,
ros::VoidPtr(), latch);
244 camera_publishers_.push_back(pub);
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...
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.
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 param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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.
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.
std::vector< ros::Publisher > publishers_
List of watching publishers.