16 #include "nav2_behavior_tree/behavior_tree_engine.hpp"
22 #include "rclcpp/rclcpp.hpp"
23 #include "behaviortree_cpp/utils/shared_library.h"
25 namespace nav2_behavior_tree
29 const std::vector<std::string> & plugin_libraries, rclcpp::Node::SharedPtr node)
31 BT::SharedLibrary loader;
32 for (
const auto & p : plugin_libraries) {
33 factory_.registerFromPlugin(loader.getOSName(p));
37 clock_ = node->get_clock();
41 BT::ReactiveSequence::EnableException(
false);
42 BT::ReactiveFallback::EnableException(
false);
48 std::function<
void()> onLoop,
49 std::function<
bool()> cancelRequested,
50 std::chrono::milliseconds loopTimeout)
52 rclcpp::WallRate loopRate(loopTimeout);
53 BT::NodeStatus result = BT::NodeStatus::RUNNING;
57 while (rclcpp::ok() && result == BT::NodeStatus::RUNNING) {
58 if (cancelRequested()) {
60 return BtStatus::CANCELED;
63 result = tree->tickOnce();
67 if (!loopRate.sleep()) {
68 RCLCPP_DEBUG_THROTTLE(
69 rclcpp::get_logger(
"BehaviorTreeEngine"),
71 "Behavior Tree tick rate %0.2f was exceeded!",
72 1.0 / (loopRate.period().count() * 1.0e-9));
75 }
catch (
const std::exception & ex) {
77 rclcpp::get_logger(
"BehaviorTreeEngine"),
78 "Behavior tree threw exception: %s. Exiting with failure.", ex.what());
79 return BtStatus::FAILED;
82 return (result == BT::NodeStatus::SUCCESS) ? BtStatus::SUCCEEDED : BtStatus::FAILED;
87 const std::string & xml_string,
88 BT::Blackboard::Ptr blackboard)
90 return factory_.createTreeFromText(xml_string, blackboard);
95 const std::string & file_path,
96 BT::Blackboard::Ptr blackboard)
98 return factory_.createTreeFromFile(file_path, blackboard);
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.