The (not so clever) algorithm used by topic_tools/throttle node. More...
#include <rate_limiter.h>

Public Member Functions | |
| void | reset () override |
| Reset the rate-limiter as if it were newly created with the same parameters. More... | |
| bool | shouldPublish (const ::ros::Time &stamp) override |
| 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... | |
| ThrottleLimiter (const ::ros::Duration &period) | |
| ThrottleLimiter (const ::ros::Rate &rate) | |
Public Member Functions inherited from cras::RateLimiter | |
| 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... | |
| 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... | |
Protected Attributes | |
| ::ros::Time | lastPublishTime {0, 0} |
Stamp of the last message for which shouldPublish() returned trued. More... | |
Protected Attributes inherited from cras::RateLimiter | |
| ::ros::Duration | jumpBackTolerance {3, 0} |
| Threshold for jump back detection. More... | |
| ::ros::Duration | period |
| The desired period between message (1/rate). More... | |
| ::ros::Rate | rate |
| The desired rate (1/period). More... | |
Additional Inherited Members | |
Protected Member Functions inherited from cras::RateLimiter | |
| 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... | |
The (not so clever) algorithm used by topic_tools/throttle node.
Definition at line 80 of file rate_limiter.h.
|
explicit |
|
explicit |
|
overridevirtual |
Reset the rate-limiter as if it were newly created with the same parameters.
Implements cras::RateLimiter.
|
overridevirtual |
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.
| [in] | stamp | Time when the message should be sent (usually not header.stamp!). |
Implements cras::RateLimiter.
|
protected |
Stamp of the last message for which shouldPublish() returned trued.
Definition at line 91 of file rate_limiter.h.