rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP__RATE_HPP_
16 #define RCLCPP__RATE_HPP_
35 virtual bool sleep() = 0;
37 virtual void reset() = 0;
44 template<
class Clock = std::chrono::high_resolution_clock>
64 auto next_interval = last_interval_ + period_;
66 if (now < last_interval_) {
68 next_interval = now + period_;
71 auto time_to_sleep = next_interval - now;
73 last_interval_ += period_;
79 if (now > next_interval + period_) {
80 last_interval_ = now + period_;
93 return Clock::is_steady;
120 #endif // RCLCPP__RATE_HPP_
virtual bool sleep()
Definition: rate.hpp:59
virtual bool is_steady() const =0
#define RCLCPP_DISABLE_COPY(...)
Definition: macros.hpp:26
virtual void reset()
Definition: rate.hpp:97
std::chrono::nanoseconds period() const
Definition: rate.hpp:102
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
bool sleep_for(const std::chrono::nanoseconds &nanoseconds, rclcpp::Context::SharedPtr context=nullptr)
Use the global condition variable to block for the specified amount of time.
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
GenericRate(std::chrono::nanoseconds period)
Definition: rate.hpp:54
virtual bool is_steady() const
Definition: rate.hpp:91
T duration_cast(T... args)
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
Definition: macros.hpp:51