throttler.h
Go to the documentation of this file.
00001 #ifndef THROTTLER_H
00002 #define THROTTLER_H
00003 
00004 #include <ros/ros.h>
00005 #include "throttled_transport/SetThrottlingParameters.h"
00006 
00007 namespace throttled_transport {
00008 
00009     class Throttler {
00010         public:
00011             Throttler(); 
00012             ~Throttler() {}
00013 
00018             bool can_publish(size_t datasize);
00019         protected:
00020             bool initialized;
00021             bool initialize();
00022 
00023             ros::ServiceServer throttling_server;
00024             bool set_throttling_parameters(SetThrottlingParameters::Request &req, 
00025                     SetThrottlingParameters::Response &res);
00026 
00027         protected:
00028             enum {
00029                 THROTTLE_BY_FREQUENCY,
00030                 THROTTLE_BY_BANDWIDTH
00031             } throttle_mode_;
00032 
00033             ros::Time last_publish_;
00034 
00035             unsigned int message_count_;
00036             double max_freq_;
00037 
00038             unsigned int used_bytes_;
00039             double max_bw_;
00040             bool max_bytes_reached_;
00041     };
00042 
00043 
00044 }; // throttled_transport
00045 
00046 
00047 
00048 #endif // THROTTLER_H


throttled_transport
Author(s): Cedric Pradalier
autogenerated on Sat Dec 28 2013 16:57:08