Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cras::RateLimiter Class Referenceabstract

Generic rate-limiter interface. More...

#include <rate_limiter.h>

Inheritance diagram for cras::RateLimiter:
Inheritance graph
[legend]

Public Member Functions

 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...
 

Protected Member Functions

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...
 

Protected Attributes

::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...
 

Detailed Description

Generic rate-limiter interface.

Definition at line 21 of file rate_limiter.h.

Constructor & Destructor Documentation

◆ RateLimiter() [1/2]

cras::RateLimiter::RateLimiter ( const ::ros::Rate rate)
explicit

Create limiter with the given rate.

Parameters
[in]rateThe desired rate of messages.

◆ RateLimiter() [2/2]

cras::RateLimiter::RateLimiter ( const ::ros::Duration period)
explicit

Create limiter with rate corresponding to the given period.

Parameters
[in]periodAverage delay between two desired output messages.

Member Function Documentation

◆ 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]stampReception time of the new message.
[in]previousStampReception 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

Reset the rate-limiter as if it were newly created with the same parameters.

Implemented in cras::TokenBucketLimiter, and cras::ThrottleLimiter.

◆ 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]toleranceIf 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]stampTime when the message should be sent (usually not header.stamp!).
Returns
Whether to continue publishing the message.

Implemented in cras::TokenBucketLimiter, and cras::ThrottleLimiter.

Member Data Documentation

◆ jumpBackTolerance

::ros::Duration cras::RateLimiter::jumpBackTolerance {3, 0}
protected

Threshold for jump back detection.

Definition at line 73 of file rate_limiter.h.

◆ period

::ros::Duration cras::RateLimiter::period
protected

The desired period between message (1/rate).

Definition at line 70 of file rate_limiter.h.

◆ rate

::ros::Rate cras::RateLimiter::rate
protected

The desired rate (1/period).

Definition at line 67 of file rate_limiter.h.


The documentation for this class was generated from the following file:


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:04