ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
rate.hpp
1 // Copyright 2014 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__RATE_HPP_
16 #define RCLCPP__RATE_HPP_
17 
18 #include <chrono>
19 #include <memory>
20 #include <thread>
21 
22 #include "rclcpp/macros.hpp"
23 #include "rclcpp/utilities.hpp"
24 #include "rclcpp/visibility_control.hpp"
25 
26 namespace rclcpp
27 {
28 
29 class RateBase
30 {
31 public:
32  RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(RateBase)
33 
34  virtual ~RateBase() {}
35  virtual bool sleep() = 0;
36  virtual bool is_steady() const = 0;
37  virtual void reset() = 0;
38 };
39 
40 using std::chrono::duration;
41 using std::chrono::duration_cast;
42 using std::chrono::nanoseconds;
43 
44 template<class Clock = std::chrono::high_resolution_clock>
45 class GenericRate : public RateBase
46 {
47 public:
48  RCLCPP_SMART_PTR_DEFINITIONS(GenericRate)
49 
50  explicit GenericRate(double rate)
52  duration_cast<nanoseconds>(duration<double>(1.0 / rate)))
53  {}
54  explicit GenericRate(std::chrono::nanoseconds period)
55  : period_(period), last_interval_(Clock::now())
56  {}
57 
58  virtual bool
59  sleep()
60  {
61  // Time coming into sleep
62  auto now = Clock::now();
63  // Time of next interval
64  auto next_interval = last_interval_ + period_;
65  // Detect backwards time flow
66  if (now < last_interval_) {
67  // Best thing to do is to set the next_interval to now + period
68  next_interval = now + period_;
69  }
70  // Calculate the time to sleep
71  auto time_to_sleep = next_interval - now;
72  // Update the interval
73  last_interval_ += period_;
74  // If the time_to_sleep is negative or zero, don't sleep
75  if (time_to_sleep <= std::chrono::seconds(0)) {
76  // If an entire cycle was missed then reset next interval.
77  // This might happen if the loop took more than a cycle.
78  // Or if time jumps forward.
79  if (now > next_interval + period_) {
80  last_interval_ = now + period_;
81  }
82  // Either way do not sleep and return false
83  return false;
84  }
85  // Sleep (will get interrupted by ctrl-c, may not sleep full time)
86  rclcpp::sleep_for(time_to_sleep);
87  return true;
88  }
89 
90  virtual bool
91  is_steady() const
92  {
93  return Clock::is_steady;
94  }
95 
96  virtual void
97  reset()
98  {
99  last_interval_ = Clock::now();
100  }
101 
102  std::chrono::nanoseconds period() const
103  {
104  return period_;
105  }
106 
107 private:
108  RCLCPP_DISABLE_COPY(GenericRate)
109 
110  std::chrono::nanoseconds period_;
111  using ClockDurationNano = std::chrono::duration<typename Clock::rep, std::nano>;
112  std::chrono::time_point<Clock, ClockDurationNano> last_interval_;
113 };
114 
117 
118 } // namespace rclcpp
119 
120 #endif // RCLCPP__RATE_HPP_
RCLCPP_PUBLIC Time now()
Definition: clock.cpp:70
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC 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.