Skip to content

Commit

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

* fixing subtree issues

* Update bt_action_server_impl.hpp

(cherry picked from commit 4b4465d)

Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
  • Loading branch information
mergify[bot] and SteveMacenski authored Oct 30, 2023
1 parent 629e27c commit dc7b98e
Showing 1 changed file with 5 additions and 0 deletions.
Original file line number Diff line number Diff line change
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 dc7b98e

Please sign in to comment.