Skip to content

Commit 5d82c7e

Browse files
tonynajjarmasf7g
authored andcommitted
Use BT.CPP Tree::sleep (ros-navigation#4761)
* Use BT.cpp sleep Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Implement BT Loop Rate Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Fix formatting Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * Fix formatting Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * move to nav2_behavior_tree Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * fix lint Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> * cache Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com> --------- Signed-off-by: Tony Najjar <tony.najjar.1997@gmail.com>
1 parent 645804b commit 5d82c7e

File tree

4 files changed

+89
-5
lines changed

4 files changed

+89
-5
lines changed

.circleci/config.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -33,12 +33,12 @@ _commands:
3333
- restore_cache:
3434
name: Restore Cache << parameters.key >>
3535
keys:
36-
- "<< parameters.key >>-v24\
36+
- "<< parameters.key >>-v29\
3737
-{{ arch }}\
3838
-{{ .Branch }}\
3939
-{{ .Environment.CIRCLE_PR_NUMBER }}\
4040
-{{ checksum \"<< parameters.workspace >>/lockfile.txt\" }}"
41-
- "<< parameters.key >>-v24\
41+
- "<< parameters.key >>-v29\
4242
-{{ arch }}\
4343
-main\
4444
-<no value>\
@@ -58,7 +58,7 @@ _commands:
5858
steps:
5959
- save_cache:
6060
name: Save Cache << parameters.key >>
61-
key: "<< parameters.key >>-v24\
61+
key: "<< parameters.key >>-v29\
6262
-{{ arch }}\
6363
-{{ .Branch }}\
6464
-{{ .Environment.CIRCLE_PR_NUMBER }}\
Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
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_

nav2_behavior_tree/src/behavior_tree_engine.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include "rclcpp/rclcpp.hpp"
2323
#include "behaviortree_cpp/utils/shared_library.h"
24+
#include "nav2_behavior_tree/utils/loop_rate.hpp"
2425

2526
namespace nav2_behavior_tree
2627
{
@@ -46,7 +47,7 @@ BehaviorTreeEngine::run(
4647
std::function<bool()> cancelRequested,
4748
std::chrono::milliseconds loopTimeout)
4849
{
49-
rclcpp::WallRate loopRate(loopTimeout);
50+
nav2_behavior_tree::LoopRate loopRate(loopTimeout, tree);
5051
BT::NodeStatus result = BT::NodeStatus::RUNNING;
5152

5253
// Loop until something happens with ROS or the node completes

nav2_behavior_tree/test/plugins/action/test_bt_action_node.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525

2626
#include "behaviortree_cpp/bt_factory.h"
2727
#include "nav2_behavior_tree/bt_action_node.hpp"
28+
#include "nav2_behavior_tree/utils/loop_rate.hpp"
2829

2930
#include "test_msgs/action/fibonacci.hpp"
3031

@@ -267,7 +268,7 @@ TEST_F(BTActionNodeTestFixture, test_server_timeout_success)
267268
BT::NodeStatus result = BT::NodeStatus::RUNNING;
268269

269270
// BT loop execution rate
270-
rclcpp::WallRate loopRate(10ms);
271+
nav2_behavior_tree::LoopRate loopRate(10ms, tree_.get());
271272

272273
// main BT execution loop
273274
while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {

0 commit comments

Comments
 (0)