69 Sent(
double _t, uint32_t _len) : t(_t), len(_len) { }
94 if (connection_header)
96 ros::M_string::const_iterator it = connection_header->find(
"latching");
97 if ((it != connection_header->end()) && (it->second ==
"1"))
99 ROS_DEBUG(
"input topic is latched; latching output topic to match");
136 if (g_last_time > now)
138 ROS_WARN(
"Detected jump back in time, resetting throttle period to now for.");
141 if((now - g_last_time) > g_period)
155 const double t = now.
toSec();
160 for (deque<Sent>::iterator i =
g_sent.begin(); i !=
g_sent.end(); ++i)
171 #define USAGE "\nusage: \n"\ 172 " throttle messages IN_TOPIC MSGS_PER_SEC [OUT_TOPIC]]\n"\ 174 " throttle bytes IN_TOPIC BYTES_PER_SEC WINDOW [OUT_TOPIC]]\n\n"\ 175 " This program will drop messages from IN_TOPIC so that either: the \n"\ 176 " average bytes per second on OUT_TOPIC, averaged over WINDOW \n"\ 177 " seconds, remains below BYTES_PER_SEC, or: the minimum inter-message\n"\ 178 " period is 1/MSGS_PER_SEC. The messages are output \n"\ 179 " to OUT_TOPIC, or (if not supplied), to IN_TOPIC_throttle.\n\n" 181 int main(
int argc,
char **argv)
191 std::string topic_name;
195 ros::init(argc, argv, topic_name +
string(
"_throttle"),
197 bool unreliable =
false;
200 pnh.
getParam(
"unreliable", unreliable);
207 if(!strcmp(argv[1],
"messages"))
209 else if(!strcmp(argv[1],
"bytes"))
240 g_bps = atoi(argv[3]);
const boost::shared_ptr< ConstMessage > & getConstMessage() const
TransportHints & reliable()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool is_latching(const boost::shared_ptr< const ros::M_string > &connection_header)
void publish(const boost::shared_ptr< M > &message) const
TransportHints & unreliable()
bool getParam(const std::string &key, std::string &s) const
void conn_cb(const ros::SingleSubscriberPublisher &)
Sent(double _t, uint32_t _len)
const boost::shared_ptr< M_string > & getConnectionHeaderPtr() const
void in_cb(const ros::MessageEvent< ShapeShifter > &msg_event)
uint32_t getNumSubscribers() const