Skip to content

Commit

Permalink
Fixing subtree issues with blackboard shared resources (3640) (open-n…
Browse files Browse the repository at this point in the history
…avigation#3911)

* fixing subtree issues

* Update bt_action_server_impl.hpp
  • Loading branch information
SteveMacenski committed Oct 28, 2023
1 parent 57fa22f commit 4b4465d
Showing 1 changed file with 5 additions and 0 deletions.
Expand Up @@ -231,6 +231,11 @@ bool BtActionServer<ActionT>::loadBehaviorTree(const std::string & bt_xml_filena
// Create the Behavior Tree from the XML input
try {
tree_ = bt_->createTreeFromFile(filename, blackboard_);
for (auto & blackboard : tree_.blackboard_stack) {
blackboard->set<rclcpp::Node::SharedPtr>("node", client_node_);
blackboard->set<std::chrono::milliseconds>("server_timeout", default_server_timeout_);
blackboard->set<std::chrono::milliseconds>("bt_loop_duration", bt_loop_duration_);
}
} catch (const std::exception & e) {
RCLCPP_ERROR(logger_, "Exception when loading BT: %s", e.what());
return false;
Expand Down

0 comments on commit 4b4465d

Please sign in to comment.