15 #ifndef NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_
16 #define NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_
20 #include "rclcpp/rclcpp.hpp"
21 #include "behaviortree_cpp/bt_factory.h"
22 #include "behaviortree_cpp/behavior_tree.h"
24 namespace nav2_behavior_tree
30 LoopRate(
const rclcpp::Duration & period, BT::Tree * tree)
31 : clock_(std::make_shared<rclcpp::Clock>(RCL_STEADY_TIME)), period_(period),
32 last_interval_(clock_->now()), tree_(tree)
39 auto now = clock_->now();
41 auto next_interval = last_interval_ + period_;
43 if (now < last_interval_) {
45 next_interval = now + period_;
48 last_interval_ += period_;
50 if (next_interval <= now) {
54 if (now > next_interval + period_) {
55 last_interval_ = now + period_;
61 auto time_to_sleep = next_interval - now;
62 std::chrono::nanoseconds time_to_sleep_ns(time_to_sleep.nanoseconds());
64 tree_->sleep(time_to_sleep_ns);
68 std::chrono::nanoseconds period()
const
70 return std::chrono::nanoseconds(period_.nanoseconds());
74 rclcpp::Clock::SharedPtr clock_;
75 rclcpp::Duration period_;
76 rclcpp::Time last_interval_;