Skip to content

Commit 57a639e

Browse files
authored
Support loading multiple behavior tree files as subtrees (#5426)
* Support loading multiple behavior tree files as subtrees Signed-off-by: Jad El Hajj <[email protected]> * Fix code style Signed-off-by: Jad El Hajj <[email protected]> * Added default param value Signed-off-by: Jad El Hajj <[email protected]> * Added recursive check to loadBehaviorTree and adapted unit test accordingly Signed-off-by: Jad El Hajj <[email protected]> * Removed nested loadBehaviorTree check in navigators Signed-off-by: Jad El Hajj <[email protected]> * Removed whitespace cpplint Signed-off-by: Jad El Hajj <[email protected]> * Fixed goalReceived Signed-off-by: Jad El Hajj <[email protected]> * Let loadbehaviorTree use its own search_directories var Signed-off-by: Jad El Hajj <[email protected]> * PR fixes-format-lint and test Signed-off-by: Jad El Hajj <[email protected]> * fix pointer Signed-off-by: Jad El Hajj <[email protected]> * Added unit test for BT xml validity Signed-off-by: Jad El Hajj <[email protected]> * CPPLint Signed-off-by: Jad El Hajj <[email protected]> * Check non existent search directory for bt Signed-off-by: Jad El Hajj <[email protected]> * CPPLint Signed-off-by: Jad El Hajj <[email protected]> * Fixed BT tests Signed-off-by: Jad El Hajj <[email protected]> * Fixed BT tests Signed-off-by: Jad El Hajj <[email protected]> --------- Signed-off-by: Jad El Hajj <[email protected]>
1 parent 1856b67 commit 57a639e

File tree

9 files changed

+232
-81
lines changed

9 files changed

+232
-81
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/behavior_tree_engine.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -98,6 +98,12 @@ class BehaviorTreeEngine
9898
*/
9999
void resetGrootMonitor();
100100

101+
/**
102+
* @brief Function to register a BT from an XML file
103+
* @param file_path Path to BT XML file
104+
*/
105+
void registerTreeFromFile(const std::string & file_path);
106+
101107
/**
102108
* @brief Function to explicitly reset all BT nodes to initial state
103109
* @param tree Tree to halt

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ class BtActionServer
5353
const std::string & action_name,
5454
const std::vector<std::string> & plugin_lib_names,
5555
const std::string & default_bt_xml_filename,
56+
const std::vector<std::string> & search_directories,
5657
OnGoalReceivedCallback on_goal_received_callback,
5758
OnLoopCallback on_loop_callback,
5859
OnPreemptCallback on_preempt_callback,
@@ -102,7 +103,8 @@ class BtActionServer
102103
* @return bool true if the resulting BT correspond to the one in bt_xml_filename. false
103104
* if something went wrong, and previous BT is maintained
104105
*/
105-
bool loadBehaviorTree(const std::string & bt_xml_filename = "");
106+
bool loadBehaviorTree(
107+
const std::string & bt_xml_filename = "");
106108

107109
/**
108110
* @brief Getter function for BT Blackboard
@@ -245,6 +247,7 @@ class BtActionServer
245247
// The XML file that contains the Behavior Tree to create
246248
std::string current_bt_xml_filename_;
247249
std::string default_bt_xml_filename_;
250+
std::vector<std::string> search_directories_;
248251

249252
// The wrapper class for the BT functionality
250253
std::unique_ptr<nav2_behavior_tree::BehaviorTreeEngine> bt_;

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

Lines changed: 30 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -39,12 +39,14 @@ BtActionServer<ActionT, NodeT>::BtActionServer(
3939
const std::string & action_name,
4040
const std::vector<std::string> & plugin_lib_names,
4141
const std::string & default_bt_xml_filename,
42+
const std::vector<std::string> & search_directories,
4243
OnGoalReceivedCallback on_goal_received_callback,
4344
OnLoopCallback on_loop_callback,
4445
OnPreemptCallback on_preempt_callback,
4546
OnCompletionCallback on_completion_callback)
4647
: action_name_(action_name),
4748
default_bt_xml_filename_(default_bt_xml_filename),
49+
search_directories_(search_directories),
4850
plugin_lib_names_(plugin_lib_names),
4951
node_(parent),
5052
on_goal_received_callback_(on_goal_received_callback),
@@ -246,6 +248,8 @@ void BtActionServer<ActionT, NodeT>::setGrootMonitoring(
246248
template<class ActionT, class NodeT>
247249
bool BtActionServer<ActionT, NodeT>::loadBehaviorTree(const std::string & bt_xml_filename)
248250
{
251+
namespace fs = std::filesystem;
252+
249253
// Empty filename is default for backward compatibility
250254
auto filename = bt_xml_filename.empty() ? default_bt_xml_filename_ : bt_xml_filename;
251255

@@ -255,19 +259,38 @@ bool BtActionServer<ActionT, NodeT>::loadBehaviorTree(const std::string & bt_xml
255259
return true;
256260
}
257261

258-
// if a new tree is created, than the Groot2 Publisher must be destroyed
262+
// Reset any existing Groot2 monitoring
259263
bt_->resetGrootMonitor();
260264

261-
// Read the input BT XML from the specified file into a string
262265
std::ifstream xml_file(filename);
263-
264266
if (!xml_file.good()) {
265267
setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
266-
"Couldn't open input XML file: " + filename);
268+
"Couldn't open BT XML file: " + filename);
267269
return false;
268270
}
269271

270-
// Create the Behavior Tree from the XML input
272+
const auto canonical_main_bt = fs::canonical(filename);
273+
274+
// Register all XML behavior Subtrees found in the given directories
275+
for (const auto & directory : search_directories_) {
276+
try {
277+
for (const auto & entry : fs::directory_iterator(directory)) {
278+
if (entry.path().extension() == ".xml") {
279+
// Skip registering the main tree file
280+
if (fs::equivalent(fs::canonical(entry.path()), canonical_main_bt)) {
281+
continue;
282+
}
283+
bt_->registerTreeFromFile(entry.path().string());
284+
}
285+
}
286+
} catch (const std::exception & e) {
287+
setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
288+
"Exception reading behavior tree directory: " + std::string(e.what()));
289+
return false;
290+
}
291+
}
292+
293+
// Try to load the main BT tree
271294
try {
272295
tree_ = bt_->createTreeFromFile(filename, blackboard_);
273296
for (auto & subtree : tree_.subtrees) {
@@ -281,15 +304,15 @@ bool BtActionServer<ActionT, NodeT>::loadBehaviorTree(const std::string & bt_xml
281304
}
282305
} catch (const std::exception & e) {
283306
setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
284-
std::string("Exception when loading BT: ") + e.what());
307+
std::string("Exception when creating BT tree from file: ") + e.what());
285308
return false;
286309
}
287310

311+
// Optional logging and monitoring
288312
topic_logger_ = std::make_unique<RosTopicLogger>(client_node_, tree_);
289313

290314
current_bt_xml_filename_ = filename;
291315

292-
// Enable monitoring with Groot2
293316
if (enable_groot_monitoring_) {
294317
bt_->addGrootMonitoring(&tree_, groot_server_port_);
295318
RCLCPP_DEBUG(

nav2_behavior_tree/src/behavior_tree_engine.cpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -102,6 +102,13 @@ BehaviorTreeEngine::createTreeFromFile(
102102
return factory_.createTreeFromFile(file_path, blackboard);
103103
}
104104

105+
/// @brief Register a tree from an XML file and return the tree
106+
void BehaviorTreeEngine::registerTreeFromFile(
107+
const std::string & file_path)
108+
{
109+
factory_.registerBehaviorTreeFromFile(file_path);
110+
}
111+
105112
void
106113
BehaviorTreeEngine::addGrootMonitoring(
107114
BT::Tree * tree,

nav2_bringup/params/nav2_params.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,8 @@ bt_navigator:
5858
plugin: "nav2_bt_navigator::NavigateThroughPosesNavigator"
5959
enable_groot_monitoring: false
6060
groot_server_port: 1669
61+
bt_search_directories:
62+
- $(find-pkg-share nav2_bt_navigator)/behavior_trees
6163
# 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
6264
# nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
6365
# nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml

nav2_bt_navigator/src/navigators/navigate_through_poses.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,6 @@ bool
7373
NavigateThroughPosesNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
7474
{
7575
auto bt_xml_filename = goal->behavior_tree;
76-
7776
if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
7877
bt_action_server_->setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
7978
"Error loading XML file: " + bt_xml_filename + ". Navigation canceled.");

nav2_bt_navigator/src/navigators/navigate_to_pose.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,6 @@ bool
8383
NavigateToPoseNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
8484
{
8585
auto bt_xml_filename = goal->behavior_tree;
86-
8786
if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
8887
bt_action_server_->setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
8988
std::string("Error loading XML file: ") + bt_xml_filename + ". Navigation canceled.");

nav2_core/include/nav2_core/behavior_tree_navigator.hpp

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -201,13 +201,20 @@ class BehaviorTreeNavigator : public NavigatorBase
201201
// get the default behavior tree for this navigator
202202
std::string default_bt_xml_filename = getDefaultBTFilepath(parent_node);
203203

204+
auto search_directories = node->declare_or_get_parameter(
205+
"bt_search_directories",
206+
std::vector<std::string>{ament_index_cpp::get_package_share_directory(
207+
"nav2_bt_navigator") + "/behavior_trees"}
208+
);
209+
204210
// Create the Behavior Tree Action Server for this navigator
205211
bt_action_server_ =
206212
std::make_unique<nav2_behavior_tree::BtActionServer<ActionT, nav2::LifecycleNode>>(
207213
node,
208214
getName(),
209215
plugin_lib_names,
210216
default_bt_xml_filename,
217+
search_directories,
211218
std::bind(&BehaviorTreeNavigator::onGoalReceived, this, std::placeholders::_1),
212219
std::bind(&BehaviorTreeNavigator::onLoop, this),
213220
std::bind(&BehaviorTreeNavigator::onPreempt, this, std::placeholders::_1),

0 commit comments

Comments
 (0)