rate_limiter.h
Go to the documentation of this file.
1 #pragma once
2 
11 #include <ros/duration.h>
12 #include <ros/rate.h>
13 #include <ros/time.h>
14 
15 namespace cras
16 {
17 
22 {
23 public:
28  explicit RateLimiter(const ::ros::Rate& rate);
29 
34  explicit RateLimiter(const ::ros::Duration& period);
35 
42  virtual bool shouldPublish(const ::ros::Time& stamp) = 0;
43 
47  virtual void reset() = 0;
48 
55  void setJumpBackTolerance(const ::ros::Duration& tolerance);
56 
57 protected:
64  bool jumpedBack(const ::ros::Time& stamp, const ::ros::Time& previousStamp) const;
65 
68 
71 
74 };
75 
81 {
82 public:
83  explicit ThrottleLimiter(const ::ros::Rate& rate);
84  explicit ThrottleLimiter(const ::ros::Duration& period);
85 
86  bool shouldPublish(const ::ros::Time& stamp) override;
87  void reset() override;
88 
89 protected:
91  ::ros::Time lastPublishTime {0, 0};
92 };
93 
104 {
105 public:
114  explicit TokenBucketLimiter(const ::ros::Rate& rate, size_t bucketCapacity = 2, double initialTokensAvailable = 1.0);
115 
124  explicit TokenBucketLimiter(const ::ros::Duration& period, size_t bucketCapacity = 2,
125  double initialTokensAvailable = 1.0);
126 
127  bool shouldPublish(const ::ros::Time& stamp) override;
128  void reset() override;
129 
130 protected:
132  ::ros::Time lastCheckTime {0, 0};
133 
136 
140 
143 };
144 
145 }
virtual bool shouldPublish(const ::ros::Time &stamp)=0
Call this function whenever a message is received. It tells whether the message has passed the rate-l...
RateLimiter(const ::ros::Rate &rate)
Create limiter with the given rate.
size_t bucketCapacity
Number of tokens that can fit into the bucket. This influences the maximum burst size.
Definition: rate_limiter.h:135
::ros::Rate rate
The desired rate (1/period).
Definition: rate_limiter.h:67
Generic rate-limiter interface.
Definition: rate_limiter.h:21
The (not so clever) algorithm used by topic_tools/throttle node.
Definition: rate_limiter.h:80
void setJumpBackTolerance(const ::ros::Duration &tolerance)
Set the limit for telling between small and large backwards time jumps. Small jumps result in ignorin...
::ros::Duration period
The desired period between message (1/rate).
Definition: rate_limiter.h:70
double initialTokensAvailable
The number of tokens that are initially in the buffer (and after reset).
Definition: rate_limiter.h:142
ros::Duration tokensAvailable
The number of currently available tokens. This units of this number are actually not seconds...
Definition: rate_limiter.h:139
Definition: any.hpp:15
Token bucket rate limiting algorithm.
Definition: rate_limiter.h:103
::ros::Duration jumpBackTolerance
Threshold for jump back detection.
Definition: rate_limiter.h:73
bool jumpedBack(const ::ros::Time &stamp, const ::ros::Time &previousStamp) const
Decide whether the newly coming message should be treated as a backwards jump in time.
virtual void reset()=0
Reset the rate-limiter as if it were newly created with the same parameters.


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53