Class RateLimiter
Defined in File rate_limiter.h
Inheritance Relationships
Derived Types
public cras::ThrottleLimiter(Class ThrottleLimiter)public cras::TokenBucketLimiter(Class TokenBucketLimiter)
Class Documentation
-
class RateLimiter
Generic rate-limiter interface.
Subclassed by cras::ThrottleLimiter, cras::TokenBucketLimiter
Public Functions
-
explicit RateLimiter(const ::rclcpp::Rate &rate)
Create limiter with the given rate.
- Parameters:
rate – [in] The desired rate of messages.
Create limiter with rate corresponding to the given period.
- Parameters:
clock – [in] The clock to use.
period – [in] Average delay between two desired output messages.
-
virtual ~RateLimiter()
-
virtual bool shouldPublish(const ::rclcpp::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.
- Parameters:
stamp – [in] Time when the message should be sent (usually not header.stamp!).
- Returns:
Whether to continue publishing the message.
-
virtual void reset()
Reset the rate-limiter as if it were newly created with the same parameters.
-
void setJumpBackTolerance(const ::rclcpp::Duration &tolerance)
Set the limit for recognizing backward time jumps.
- Parameters:
tolerance – [in] If a new message comes that is
toleranceseconds older than the last seen message, it should be treated as a jump.
-
void setJumpBackTolerance(const ::rcl_jump_threshold_t &tolerance)
Set the limit for recognizing time jumps.
- Parameters:
tolerance – [in] The tolerance parameters.
Protected Functions
-
virtual void onJump(const rcl_time_jump_t &timeJump)
Callback called when time jumped.
- Parameters:
timeJump – [in] Parameters of the time jump.
Protected Attributes
-
::rclcpp::Rate rate
The desired rate (1/period).
-
::rclcpp::Duration period
The desired period between message (1/rate).
-
::rcl_jump_threshold_t jumpBackTolerance = {true, 0, -3000000000}
Threshold for time jump detection.
-
::rclcpp::JumpHandler::SharedPtr jumpHandler = {nullptr}
Handler of time jumps.
-
::std::optional<::std::tuple<::rclcpp::Time, ::rcl_time_jump_t>> lastJump = {}
Parameters of the last time jump.
-
explicit RateLimiter(const ::rclcpp::Rate &rate)