1 #ifndef _NODELET_TOPIC_TOOLS_NODELET_THROTTLE_H_ 2 #define _NODELET_TOPIC_TOOLS_NODELET_THROTTLE_H_ 36 #include <dynamic_reconfigure/server.h> 37 #include <nodelet_topic_tools/NodeletThrottleConfig.h> 39 #include <boost/thread/locks.hpp> 40 #include <boost/thread/mutex.hpp> 63 dynamic_reconfigure::Server<nodelet_topic_tools::NodeletThrottleConfig>*
srv_;
70 srv_ =
new dynamic_reconfigure::Server<nodelet_topic_tools::NodeletThrottleConfig>(private_nh);
71 dynamic_reconfigure::Server<nodelet_topic_tools::NodeletThrottleConfig>::CallbackType
f = boost::bind(&
NodeletThrottle::reconfigure,
this, _1, _2);
83 boost::lock_guard<boost::mutex> lock(connect_mutex_);
89 if (max_update_rate_ > 0.0)
103 void reconfigure(nodelet_topic_tools::NodeletThrottleConfig &config, uint32_t level)
105 max_update_rate_ = config.update_rate;
109 boost::lock_guard<boost::mutex> lock(connect_mutex_);
117 boost::lock_guard<boost::mutex> lock(connect_mutex_);
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::NodeHandle & getPrivateNodeHandle() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
uint32_t getNumSubscribers() const
CallbackQueueInterface * getCallbackQueue() const
boost::shared_ptr< void > VoidPtr
#define NODELET_DEBUG(...)