38 #ifndef NODELET_LAZY_H_ 39 #define NODELET_LAZY_H_ 43 #include <boost/thread.hpp> 84 ros::param::param<bool>(
"~use_multithread_callback", use_multithread,
true);
107 double duration_to_warn_no_connection;
108 pnh_->param(
"duration_to_warn_no_connection",
109 duration_to_warn_no_connection, 5.0);
110 if (duration_to_warn_no_connection > 0)
142 NODELET_INFO(
"New connection or disconnection is detected");
188 NODELET_WARN(
"This node/nodelet subscribes topics only when subscribed.");
220 std::string topic,
int queue_size,
bool latch=
false)
289 #endif // NODELET_LAZY_H_
boost::shared_ptr< void const > VoidConstPtr
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_WARN(...)
ros::NodeHandle & getMTNodeHandle() const
ros::NodeHandle & getPrivateNodeHandle() const
ros::NodeHandle & getMTPrivateNodeHandle() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
#define NODELET_INFO(...)
uint32_t getNumSubscribers() const
#define NODELET_DEBUG(...)