Skip to content

Commit

Permalink
Select behavior Tree in NavigateToPoseAction (ros-navigation#1784)
Browse files Browse the repository at this point in the history
* Select BT in NavigateToPose action

Signed-off-by: Francisco Martin Rico <[email protected]>

* Change to unique_ptr. Default bt_xml to a valid file

Signed-off-by: Francisco Martin Rico <[email protected]>

* Return tree to stack

Signed-off-by: Francisco Martin Rico <[email protected]>

* Removed default_bt_xml_filename default value

Signed-off-by: Francisco Martin Rico <[email protected]>

* Failing fast, early and loud when BT is not valid

Signed-off-by: Francisco Martin Rico <[email protected]>

* Return inmediately after terminate

Signed-off-by: Francisco Martin Rico <[email protected]>
  • Loading branch information
fmrico authored Jun 12, 2020
1 parent be166f3 commit 31db461
Show file tree
Hide file tree
Showing 7 changed files with 16 additions and 16 deletions.
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')
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

0 comments on commit 31db461

Please sign in to comment.