Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Select behavior Tree in NavigateToPoseAction #1784

Merged
merged 7 commits into from
Jun 12, 2020
Merged
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions nav2_bringup/bringup/launch/bringup_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ def generate_launch_description():
map_yaml_file = LaunchConfiguration('map')
use_sim_time = LaunchConfiguration('use_sim_time')
params_file = LaunchConfiguration('params_file')
bt_xml_file = LaunchConfiguration('bt_xml_file')
default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
fmrico marked this conversation as resolved.
Show resolved Hide resolved
autostart = LaunchConfiguration('autostart')

stdout_linebuf_envvar = SetEnvironmentVariable(
Expand Down Expand Up @@ -73,7 +73,7 @@ def generate_launch_description():
description='Full path to the ROS2 parameters file to use for all launched nodes')

declare_bt_xml_cmd = DeclareLaunchArgument(
'bt_xml_file',
'default_bt_xml_filename',
default_value=os.path.join(
get_package_share_directory('nav2_bt_navigator'),
'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
Expand Down Expand Up @@ -114,7 +114,7 @@ def generate_launch_description():
'use_sim_time': use_sim_time,
'autostart': autostart,
'params_file': params_file,
'bt_xml_file': bt_xml_file,
'default_bt_xml_filename': default_bt_xml_filename,
'use_lifecycle_mgr': 'false',
'map_subscribe_transient_local': 'true'}.items()),
])
Expand Down
8 changes: 4 additions & 4 deletions nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ def generate_launch_description():
# On this example all robots are launched with the same settings
map_yaml_file = LaunchConfiguration('map')

bt_xml_file = LaunchConfiguration('bt_xml_file')
default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
autostart = LaunchConfiguration('autostart')
rviz_config_file = LaunchConfiguration('rviz_config')
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
Expand Down Expand Up @@ -83,7 +83,7 @@ def generate_launch_description():
description='Full path to the ROS2 parameters file to use for robot2 launched nodes')

declare_bt_xml_cmd = DeclareLaunchArgument(
'bt_xml_file',
'default_bt_xml_filename',
default_value=os.path.join(
get_package_share_directory('nav2_bt_navigator'),
'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
Expand Down Expand Up @@ -152,7 +152,7 @@ def generate_launch_description():
'map': map_yaml_file,
'use_sim_time': 'True',
'params_file': params_file,
'bt_xml_file': bt_xml_file,
'default_bt_xml_filename': default_bt_xml_filename,
'autostart': autostart,
'use_rviz': 'False',
'use_simulator': 'False',
Expand All @@ -170,7 +170,7 @@ def generate_launch_description():
msg=[robot['name'], ' params yaml: ', params_file]),
LogInfo(
condition=IfCondition(log_settings),
msg=[robot['name'], ' behavior tree xml: ', bt_xml_file]),
msg=[robot['name'], ' behavior tree xml: ', default_bt_xml_filename]),
LogInfo(
condition=IfCondition(log_settings),
msg=[robot['name'], ' rviz config file: ', rviz_config_file]),
Expand Down
6 changes: 3 additions & 3 deletions nav2_bringup/bringup/launch/navigation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
autostart = LaunchConfiguration('autostart')
params_file = LaunchConfiguration('params_file')
bt_xml_file = LaunchConfiguration('bt_xml_file')
default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local')

lifecycle_nodes = ['controller_server',
Expand All @@ -52,7 +52,7 @@ def generate_launch_description():
# Create our own temporary YAML files that include substitutions
param_substitutions = {
'use_sim_time': use_sim_time,
'bt_xml_filename': bt_xml_file,
'default_bt_xml_filename': default_bt_xml_filename,
'autostart': autostart,
'map_subscribe_transient_local': map_subscribe_transient_local}

Expand Down Expand Up @@ -84,7 +84,7 @@ def generate_launch_description():
description='Full path to the ROS2 parameters file to use'),

DeclareLaunchArgument(
'bt_xml_file',
'default_bt_xml_filename',
default_value=os.path.join(
get_package_share_directory('nav2_bt_navigator'),
'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
Expand Down
6 changes: 3 additions & 3 deletions nav2_bringup/bringup/launch/tb3_simulation_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ def generate_launch_description():
map_yaml_file = LaunchConfiguration('map')
use_sim_time = LaunchConfiguration('use_sim_time')
params_file = LaunchConfiguration('params_file')
bt_xml_file = LaunchConfiguration('bt_xml_file')
default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
autostart = LaunchConfiguration('autostart')

# Launch configuration variables specific to simulation
Expand Down Expand Up @@ -90,7 +90,7 @@ def generate_launch_description():
description='Full path to the ROS2 parameters file to use for all launched nodes')

declare_bt_xml_cmd = DeclareLaunchArgument(
'bt_xml_file',
'default_bt_xml_filename',
default_value=os.path.join(
get_package_share_directory('nav2_bt_navigator'),
'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
Expand Down Expand Up @@ -173,7 +173,7 @@ def generate_launch_description():
'map': map_yaml_file,
'use_sim_time': use_sim_time,
'params_file': params_file,
'bt_xml_file': bt_xml_file,
'default_bt_xml_filename': default_bt_xml_filename,
'autostart': autostart}.items())

# Create the launch description and populate
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ bt_navigator:
use_sim_time: True
global_frame: map
robot_base_frame: base_link
bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ bt_navigator:
use_sim_time: True
global_frame: map
robot_base_frame: base_link
bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ bt_navigator:
use_sim_time: True
global_frame: map
robot_base_frame: base_link
bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
plugin_lib_names:
- nav2_compute_path_to_pose_action_bt_node
- nav2_follow_path_action_bt_node
Expand Down
13 changes: 11 additions & 2 deletions nav2_bt_navigator/include/nav2_bt_navigator/bt_navigator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,13 +112,22 @@ class BtNavigator : public nav2_util::LifecycleNode
void onGoalPoseReceived(const geometry_msgs::msg::PoseStamped::SharedPtr pose);
rclcpp::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr goal_sub_;

/**
* @brief Replace current BT with another one
* @param bt_xml_filename The file containing the new BT
* @return true if the resulting BT correspond to the one in bt_xml_filename. false
* if something went wrong, and previous BT is mantained
*/
bool loadBehaviorTree(const std::string & bt_id);

BT::Tree tree_;

// The blackboard shared by all of the nodes in the tree
BT::Blackboard::Ptr blackboard_;

// The XML string that defines the Behavior Tree to create
std::string xml_string_;
// The XML fiñe that cointains the Behavior Tree to create
std::string current_bt_xml_filename_;
std::string default_bt_xml_filename_;

// The wrapper class for the BT functionality
std::unique_ptr<nav2_behavior_tree::BehaviorTreeEngine> bt_;
Expand Down
44 changes: 35 additions & 9 deletions nav2_bt_navigator/src/bt_navigator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ BtNavigator::BtNavigator()
};

// Declare this node's parameters
declare_parameter("bt_xml_filename");
declare_parameter("default_bt_xml_filename");
declare_parameter("plugin_lib_names", plugin_libs);
declare_parameter("transform_tolerance", rclcpp::ParameterValue(0.1));
declare_parameter("global_frame", std::string("map"));
Expand Down Expand Up @@ -127,28 +127,44 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
blackboard_->set<int>("number_recoveries", 0); // NOLINT

// Get the BT filename to use from the node parameter
std::string bt_xml_filename;
get_parameter("bt_xml_filename", bt_xml_filename);
get_parameter("default_bt_xml_filename", default_bt_xml_filename_);

if (!loadBehaviorTree(default_bt_xml_filename_)) {
RCLCPP_ERROR(get_logger(), "Error loading XML file: %s", default_bt_xml_filename_.c_str());
return nav2_util::CallbackReturn::FAILURE;
}

return nav2_util::CallbackReturn::SUCCESS;
}

bool
BtNavigator::loadBehaviorTree(const std::string & bt_xml_filename)
{
// Use previous BT if it is the existing one
if (current_bt_xml_filename_ == bt_xml_filename) {
return true;
}

// Read the input BT XML from the specified file into a string
std::ifstream xml_file(bt_xml_filename);

if (!xml_file.good()) {
RCLCPP_ERROR(get_logger(), "Couldn't open input XML file: %s", bt_xml_filename.c_str());
return nav2_util::CallbackReturn::FAILURE;
return false;
}

xml_string_ = std::string(
auto xml_string = std::string(
std::istreambuf_iterator<char>(xml_file),
std::istreambuf_iterator<char>());

RCLCPP_DEBUG(get_logger(), "Behavior Tree file: '%s'", bt_xml_filename.c_str());
RCLCPP_DEBUG(get_logger(), "Behavior Tree XML: %s", xml_string_.c_str());
RCLCPP_DEBUG(get_logger(), "Behavior Tree XML: %s", xml_string.c_str());

// Create the Behavior Tree from the XML input
tree_ = bt_->buildTreeFromText(xml_string_, blackboard_);
tree_ = bt_->buildTreeFromText(xml_string, blackboard_);
current_bt_xml_filename_ = bt_xml_filename;

return nav2_util::CallbackReturn::SUCCESS;
return true;
}

nav2_util::CallbackReturn
Expand Down Expand Up @@ -188,7 +204,6 @@ BtNavigator::on_cleanup(const rclcpp_lifecycle::State & /*state*/)

action_server_.reset();
plugin_lib_names_.clear();
xml_string_.clear();
blackboard_.reset();
bt_->haltAllActions(tree_.rootNode());
bt_.reset();
Expand Down Expand Up @@ -259,6 +274,17 @@ BtNavigator::navigateToPose()
action_server_->publish_feedback(feedback_msg);
};

auto bt_xml_filename = action_server_->get_current_goal()->behavior_tree;

// Empty id in request is default for backward compatibility
bt_xml_filename = bt_xml_filename == "" ? default_bt_xml_filename_ : bt_xml_filename;

if (!loadBehaviorTree(bt_xml_filename)) {
fmrico marked this conversation as resolved.
Show resolved Hide resolved
RCLCPP_WARN(
get_logger(), "BT file not found: %s. Using previous %s",
bt_xml_filename.c_str(), current_bt_xml_filename_.c_str());
}

// Execute the BT that was previously created in the configure step
nav2_behavior_tree::BtStatus rc = bt_->run(&tree_, on_loop, is_canceling);
// Make sure that the Bt is not in a running state from a previous execution
Expand Down
1 change: 1 addition & 0 deletions nav2_msgs/action/NavigateToPose.action
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#goal definition
geometry_msgs/PoseStamped pose
string behavior_tree
---
#result definition
std_msgs/Empty result
Expand Down