|
| 1 | +// Copyright (c) 2024 Angsa Robotics |
| 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 NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_ |
| 16 | +#define NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_ |
| 17 | + |
| 18 | +#include <memory> |
| 19 | + |
| 20 | +#include "rclcpp/rclcpp.hpp" |
| 21 | +#include "behaviortree_cpp/bt_factory.h" |
| 22 | +#include "behaviortree_cpp/behavior_tree.h" |
| 23 | + |
| 24 | +namespace nav2_behavior_tree |
| 25 | +{ |
| 26 | + |
| 27 | +class LoopRate |
| 28 | +{ |
| 29 | +public: |
| 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) |
| 33 | + {} |
| 34 | + |
| 35 | + // Similar to rclcpp::WallRate::sleep() but using tree_->sleep() |
| 36 | + bool sleep() |
| 37 | + { |
| 38 | + // Time coming into sleep |
| 39 | + auto now = clock_->now(); |
| 40 | + // Time of next interval |
| 41 | + auto next_interval = last_interval_ + period_; |
| 42 | + // Detect backwards time flow |
| 43 | + if (now < last_interval_) { |
| 44 | + // Best thing to do is to set the next_interval to now + period |
| 45 | + next_interval = now + period_; |
| 46 | + } |
| 47 | + // Update the interval |
| 48 | + last_interval_ += period_; |
| 49 | + // If the time_to_sleep is negative or zero, don't sleep |
| 50 | + if (next_interval <= now) { |
| 51 | + // If an entire cycle was missed then reset next interval. |
| 52 | + // This might happen if the loop took more than a cycle. |
| 53 | + // Or if time jumps forward. |
| 54 | + if (now > next_interval + period_) { |
| 55 | + last_interval_ = now + period_; |
| 56 | + } |
| 57 | + // Either way do not sleep and return false |
| 58 | + return false; |
| 59 | + } |
| 60 | + // Calculate the time to sleep |
| 61 | + auto time_to_sleep = next_interval - now; |
| 62 | + std::chrono::nanoseconds time_to_sleep_ns(time_to_sleep.nanoseconds()); |
| 63 | + // Sleep (can get interrupted by emitWakeUpSignal()) |
| 64 | + tree_->sleep(time_to_sleep_ns); |
| 65 | + return true; |
| 66 | + } |
| 67 | + |
| 68 | + std::chrono::nanoseconds period() const |
| 69 | + { |
| 70 | + return std::chrono::nanoseconds(period_.nanoseconds()); |
| 71 | + } |
| 72 | + |
| 73 | +private: |
| 74 | + rclcpp::Clock::SharedPtr clock_; |
| 75 | + rclcpp::Duration period_; |
| 76 | + rclcpp::Time last_interval_; |
| 77 | + BT::Tree * tree_; |
| 78 | +}; |
| 79 | + |
| 80 | +} // namespace nav2_behavior_tree |
| 81 | + |
| 82 | +#endif // NAV2_BEHAVIOR_TREE__UTILS__LOOP_RATE_HPP_ |
0 commit comments