Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
behavior_tree_engine.cpp
1 // Copyright (c) 2018 Intel Corporation
2 // Copyright (c) 2020 Florian Gramss
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #include "nav2_behavior_tree/behavior_tree_engine.hpp"
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "rclcpp/rclcpp.hpp"
23 #include "behaviortree_cpp/utils/shared_library.h"
24 
25 namespace nav2_behavior_tree
26 {
27 
29  const std::vector<std::string> & plugin_libraries, rclcpp::Node::SharedPtr node)
30 {
31  BT::SharedLibrary loader;
32  for (const auto & p : plugin_libraries) {
33  factory_.registerFromPlugin(loader.getOSName(p));
34  }
35 
36  // clock for throttled debug log
37  clock_ = node->get_clock();
38 
39  // FIXME: the next two line are needed for back-compatibility with BT.CPP 3.8.x
40  // Note that the can be removed, once we migrate from BT.CPP 4.5.x to 4.6+
41  BT::ReactiveSequence::EnableException(false);
42  BT::ReactiveFallback::EnableException(false);
43 }
44 
45 BtStatus
47  BT::Tree * tree,
48  std::function<void()> onLoop,
49  std::function<bool()> cancelRequested,
50  std::chrono::milliseconds loopTimeout)
51 {
52  rclcpp::WallRate loopRate(loopTimeout);
53  BT::NodeStatus result = BT::NodeStatus::RUNNING;
54 
55  // Loop until something happens with ROS or the node completes
56  try {
57  while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
58  if (cancelRequested()) {
59  tree->haltTree();
60  return BtStatus::CANCELED;
61  }
62 
63  result = tree->tickOnce();
64 
65  onLoop();
66 
67  if (!loopRate.sleep()) {
68  RCLCPP_DEBUG_THROTTLE(
69  rclcpp::get_logger("BehaviorTreeEngine"),
70  *clock_, 1000,
71  "Behavior Tree tick rate %0.2f was exceeded!",
72  1.0 / (loopRate.period().count() * 1.0e-9));
73  }
74  }
75  } catch (const std::exception & ex) {
76  RCLCPP_ERROR(
77  rclcpp::get_logger("BehaviorTreeEngine"),
78  "Behavior tree threw exception: %s. Exiting with failure.", ex.what());
79  return BtStatus::FAILED;
80  }
81 
82  return (result == BT::NodeStatus::SUCCESS) ? BtStatus::SUCCEEDED : BtStatus::FAILED;
83 }
84 
85 BT::Tree
87  const std::string & xml_string,
88  BT::Blackboard::Ptr blackboard)
89 {
90  return factory_.createTreeFromText(xml_string, blackboard);
91 }
92 
93 BT::Tree
95  const std::string & file_path,
96  BT::Blackboard::Ptr blackboard)
97 {
98  return factory_.createTreeFromFile(file_path, blackboard);
99 }
100 
101 // In order to re-run a Behavior Tree, we must be able to reset all nodes to the initial state
102 void
104 {
105  // this halt signal should propagate through the entire tree.
106  tree.haltTree();
107 }
108 
109 } // namespace nav2_behavior_tree
BehaviorTreeEngine(const std::vector< std::string > &plugin_libraries, rclcpp::Node::SharedPtr node)
A constructor for nav2_behavior_tree::BehaviorTreeEngine.
BT::Tree createTreeFromFile(const std::string &file_path, BT::Blackboard::Ptr blackboard)
Function to create a BT from an XML file.
BT::Tree createTreeFromText(const std::string &xml_string, BT::Blackboard::Ptr blackboard)
Function to create a BT from a XML string.
void haltAllActions(BT::Tree &tree)
Function to explicitly reset all BT nodes to initial state.
BtStatus run(BT::Tree *tree, std::function< void()> onLoop, std::function< bool()> cancelRequested, std::chrono::milliseconds loopTimeout=std::chrono::milliseconds(10))
Function to execute a BT at a specific rate.