Generic rate-limiter interface.
More...
#include <rate_limiter.h>
|
| RateLimiter (const ::ros::Duration &period) |
| Create limiter with rate corresponding to the given period. More...
|
|
| RateLimiter (const ::ros::Rate &rate) |
| Create limiter with the given rate. More...
|
|
virtual void | reset ()=0 |
| Reset the rate-limiter as if it were newly created with the same parameters. More...
|
|
void | setJumpBackTolerance (const ::ros::Duration &tolerance) |
| Set the limit for telling between small and large backwards time jumps. Small jumps result in ignoring the messages, while a large jump results in a reset of the rate-limter. More...
|
|
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-limiting and should be published, or whether it should be skipped. More...
|
|
|
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. More...
|
|
Generic rate-limiter interface.
Definition at line 21 of file rate_limiter.h.
◆ RateLimiter() [1/2]
cras::RateLimiter::RateLimiter |
( |
const ::ros::Rate & |
rate | ) |
|
|
explicit |
Create limiter with the given rate.
- Parameters
-
[in] | rate | The desired rate of messages. |
◆ RateLimiter() [2/2]
Create limiter with rate corresponding to the given period.
- Parameters
-
[in] | period | Average delay between two desired output messages. |
◆ jumpedBack()
bool cras::RateLimiter::jumpedBack |
( |
const ::ros::Time & |
stamp, |
|
|
const ::ros::Time & |
previousStamp |
|
) |
| const |
|
protected |
Decide whether the newly coming message should be treated as a backwards jump in time.
- Parameters
-
[in] | stamp | Reception time of the new message. |
[in] | previousStamp | Reception time of the previous message. |
- Returns
- True if the message should be treated as a large time jump.
◆ reset()
virtual void cras::RateLimiter::reset |
( |
| ) |
|
|
pure virtual |
◆ setJumpBackTolerance()
void cras::RateLimiter::setJumpBackTolerance |
( |
const ::ros::Duration & |
tolerance | ) |
|
Set the limit for telling between small and large backwards time jumps. Small jumps result in ignoring the messages, while a large jump results in a reset of the rate-limter.
- Parameters
-
[in] | tolerance | If a new message comes that is tolerance seconds older than the last seen message, it should be treated as a large jump. |
◆ shouldPublish()
virtual bool cras::RateLimiter::shouldPublish |
( |
const ::ros::Time & |
stamp | ) |
|
|
pure virtual |
Call this function whenever a message is received. It tells whether the message has passed the rate-limiting and should be published, or whether it should be skipped.
- Parameters
-
[in] | stamp | Time when the message should be sent (usually not header.stamp!). |
- Returns
- Whether to continue publishing the message.
Implemented in cras::TokenBucketLimiter, and cras::ThrottleLimiter.
◆ jumpBackTolerance
Threshold for jump back detection.
Definition at line 73 of file rate_limiter.h.
◆ period
The desired period between message (1/rate).
Definition at line 70 of file rate_limiter.h.
◆ rate
The documentation for this class was generated from the following file: