Go to the documentation of this file.
47 virtual void reset() = 0;
64 bool jumpedBack(const ::ros::Time& stamp, const ::ros::Time& previousStamp)
const;
87 void reset()
override;
128 void reset()
override;
double initialTokensAvailable
The number of tokens that are initially in the buffer (and after reset).
::ros::Time lastCheckTime
Stamp of the last incoming message. Zero at the beginning.
bool shouldPublish(const ::ros::Time &stamp) override
Call this function whenever a message is received. It tells whether the message has passed the rate-l...
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.
Token bucket rate limiting algorithm.
::ros::Duration jumpBackTolerance
Threshold for jump back detection.
void setJumpBackTolerance(const ::ros::Duration &tolerance)
Set the limit for telling between small and large backwards time jumps. Small jumps result in ignorin...
RateLimiter(const ::ros::Rate &rate)
Create limiter with the given rate.
Generic rate-limiter interface.
::ros::Rate rate
The desired rate (1/period).
::ros::Time lastPublishTime
Stamp of the last message for which shouldPublish() returned trued.
ThrottleLimiter(const ::ros::Rate &rate)
size_t bucketCapacity
Number of tokens that can fit into the bucket. This influences the maximum burst size.
The (not so clever) algorithm used by topic_tools/throttle node.
TokenBucketLimiter(const ::ros::Rate &rate, size_t bucketCapacity=2, double initialTokensAvailable=1.0)
Create the rate-limiter limiting to the desired rate.
void reset() override
Reset the rate-limiter as if it were newly created with the same parameters.
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...
bool shouldPublish(const ::ros::Time &stamp) override
Call this function whenever a message is received. It tells whether the message has passed the rate-l...
ros::Duration tokensAvailable
The number of currently available tokens. This units of this number are actually not seconds,...
::ros::Duration period
The desired period between message (1/rate).
void reset() override
Reset the rate-limiter as if it were newly created with the same parameters.
cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sun Jan 5 2025 03:50:32