diff --git a/nav2_bringup/bringup/launch/bringup_launch.py b/nav2_bringup/bringup/launch/bringup_launch.py
index a8205e93225ff35de1082ed4665d6d5f576f2ff7..8d357ff5ad3d9238a1a35fe743fc86b26046048f 100644
--- a/nav2_bringup/bringup/launch/bringup_launch.py
+++ b/nav2_bringup/bringup/launch/bringup_launch.py
@@ -37,8 +37,6 @@ def generate_launch_description():
     map_yaml_file = LaunchConfiguration('map')
     use_sim_time = LaunchConfiguration('use_sim_time')
     params_file = LaunchConfiguration('params_file')
-    default_nav_through_poses_bt_xml = LaunchConfiguration('default_nav_through_poses_bt_xml')
-    default_nav_to_pose_bt_xml = LaunchConfiguration('default_nav_to_pose_bt_xml')
     autostart = LaunchConfiguration('autostart')
 
     stdout_linebuf_envvar = SetEnvironmentVariable(
@@ -73,20 +71,6 @@ def generate_launch_description():
         default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
         description='Full path to the ROS2 parameters file to use for all launched nodes')
 
-    default_nav_through_poses_bt_xml_cmd = DeclareLaunchArgument(
-        'default_nav_through_poses_bt_xml',
-        default_value=os.path.join(
-            get_package_share_directory('nav2_bt_navigator'),
-            'behavior_trees', 'navigate_through_poses_w_replanning_and_recovery.xml'),
-        description='Full path to the behavior tree xml file to use')
-
-    default_nav_to_pose_bt_xml_cmd = DeclareLaunchArgument(
-        'default_nav_to_pose_bt_xml',
-        default_value=os.path.join(
-            get_package_share_directory('nav2_bt_navigator'),
-            'behavior_trees', 'navigate_to_pose_w_replanning_and_recovery.xml'),
-        description='Full path to the behavior tree xml file to use')
-
     declare_autostart_cmd = DeclareLaunchArgument(
         'autostart', default_value='true',
         description='Automatically startup the nav2 stack')
@@ -122,8 +106,6 @@ def generate_launch_description():
                               'use_sim_time': use_sim_time,
                               'autostart': autostart,
                               'params_file': params_file,
-                              'default_nav_through_poses_bt_xml': default_nav_through_poses_bt_xml,
-                              'default_nav_to_pose_bt_xml': default_nav_to_pose_bt_xml,
                               'use_lifecycle_mgr': 'false',
                               'map_subscribe_transient_local': 'true'}.items()),
     ])
@@ -142,8 +124,6 @@ def generate_launch_description():
     ld.add_action(declare_use_sim_time_cmd)
     ld.add_action(declare_params_file_cmd)
     ld.add_action(declare_autostart_cmd)
-    ld.add_action(default_nav_through_poses_bt_xml_cmd)
-    ld.add_action(default_nav_to_pose_bt_xml_cmd)
 
     # Add the actions to launch all of the navigation nodes
     ld.add_action(bringup_cmd_group)
diff --git a/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py b/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py
index e9f89ef34e4d0f94d99a55b10ce4a41bddc87f0e..dd13fae8bbd18e1a120152af8ad895a1ccbe286d 100644
--- a/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py
+++ b/nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py
@@ -49,8 +49,6 @@ def generate_launch_description():
     # On this example all robots are launched with the same settings
     map_yaml_file = LaunchConfiguration('map')
 
-    default_nav_through_poses_bt_xml = LaunchConfiguration('default_nav_through_poses_bt_xml')
-    default_nav_to_pose_bt_xml = LaunchConfiguration('default_nav_to_pose_bt_xml')
     autostart = LaunchConfiguration('autostart')
     rviz_config_file = LaunchConfiguration('rviz_config')
     use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
@@ -83,20 +81,6 @@ def generate_launch_description():
         default_value=os.path.join(bringup_dir, 'params', 'nav2_multirobot_params_2.yaml'),
         description='Full path to the ROS2 parameters file to use for robot2 launched nodes')
 
-    default_nav_through_poses_bt_xml_cmd = DeclareLaunchArgument(
-        'default_nav_through_poses_bt_xml',
-        default_value=os.path.join(
-            get_package_share_directory('nav2_bt_navigator'),
-            'behavior_trees', 'navigate_through_poses_w_replanning_and_recovery.xml'),
-        description='Full path to the behavior tree xml file to use')
-
-    default_nav_to_pose_bt_xml_cmd = DeclareLaunchArgument(
-        'default_nav_to_pose_bt_xml',
-        default_value=os.path.join(
-            get_package_share_directory('nav2_bt_navigator'),
-            'behavior_trees', 'navigate_to_pose_w_replanning_and_recovery.xml'),
-        description='Full path to the behavior tree xml file to use')
-
     declare_autostart_cmd = DeclareLaunchArgument(
         'autostart', default_value='false',
         description='Automatically startup the stacks')
@@ -160,10 +144,6 @@ def generate_launch_description():
                                   'map': map_yaml_file,
                                   'use_sim_time': 'True',
                                   'params_file': params_file,
-                                  'default_nav_through_poses_bt_xml':
-                                      default_nav_through_poses_bt_xml,
-                                  'default_nav_to_pose_bt_xml':
-                                      default_nav_to_pose_bt_xml,
                                   'autostart': autostart,
                                   'use_rviz': 'False',
                                   'use_simulator': 'False',
@@ -179,14 +159,6 @@ def generate_launch_description():
             LogInfo(
                 condition=IfCondition(log_settings),
                 msg=[robot['name'], ' params yaml: ', params_file]),
-            LogInfo(
-                condition=IfCondition(log_settings),
-                msg=[robot['name'], ' Nav to Pose behavior tree xml: ',
-                                    default_nav_to_pose_bt_xml]),
-            LogInfo(
-                condition=IfCondition(log_settings),
-                msg=[robot['name'], ' Nav Through Poses behavior tree xml: ',
-                                    default_nav_through_poses_bt_xml]),
             LogInfo(
                 condition=IfCondition(log_settings),
                 msg=[robot['name'], ' rviz config file: ', rviz_config_file]),
@@ -209,8 +181,6 @@ def generate_launch_description():
     ld.add_action(declare_map_yaml_cmd)
     ld.add_action(declare_robot1_params_file_cmd)
     ld.add_action(declare_robot2_params_file_cmd)
-    ld.add_action(default_nav_through_poses_bt_xml_cmd)
-    ld.add_action(default_nav_to_pose_bt_xml_cmd)
     ld.add_action(declare_use_rviz_cmd)
     ld.add_action(declare_autostart_cmd)
     ld.add_action(declare_rviz_config_file_cmd)
diff --git a/nav2_bringup/bringup/launch/navigation_launch.py b/nav2_bringup/bringup/launch/navigation_launch.py
index 07b4507b6781415ac24ddfbf8240714c0a10fcc4..0e54413565728e3eb5aabd5c4ce2c01899d5e64d 100644
--- a/nav2_bringup/bringup/launch/navigation_launch.py
+++ b/nav2_bringup/bringup/launch/navigation_launch.py
@@ -31,9 +31,6 @@ def generate_launch_description():
     use_sim_time = LaunchConfiguration('use_sim_time')
     autostart = LaunchConfiguration('autostart')
     params_file = LaunchConfiguration('params_file')
-    default_nav_through_poses_bt_xml = LaunchConfiguration('default_nav_through_poses_bt_xml')
-    default_nav_to_pose_bt_xml = LaunchConfiguration('default_nav_to_pose_bt_xml')
-    map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local')
 
     lifecycle_nodes = ['controller_server',
                        'planner_server',
@@ -53,10 +50,7 @@ def generate_launch_description():
     # Create our own temporary YAML files that include substitutions
     param_substitutions = {
         'use_sim_time': use_sim_time,
-        'default_nav_through_poses_bt_xml': default_nav_through_poses_bt_xml,
-        'default_nav_to_pose_bt_xml': default_nav_to_pose_bt_xml,
-        'autostart': autostart,
-        'map_subscribe_transient_local': map_subscribe_transient_local}
+        'autostart': autostart}
 
     configured_params = RewrittenYaml(
             source_file=params_file,
@@ -85,24 +79,6 @@ def generate_launch_description():
             default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
             description='Full path to the ROS2 parameters file to use'),
 
-        DeclareLaunchArgument(
-            'default_nav_through_poses_bt_xml',
-            default_value=os.path.join(
-                get_package_share_directory('nav2_bt_navigator'),
-                'behavior_trees', 'navigate_through_poses_w_replanning_and_recovery.xml'),
-            description='Full path to the behavior tree xml file to use'),
-
-        DeclareLaunchArgument(
-            'default_nav_to_pose_bt_xml',
-            default_value=os.path.join(
-                get_package_share_directory('nav2_bt_navigator'),
-                'behavior_trees', 'navigate_to_pose_w_replanning_and_recovery.xml'),
-            description='Full path to the behavior tree xml file to use'),
-
-        DeclareLaunchArgument(
-            'map_subscribe_transient_local', default_value='false',
-            description='Whether to set the map subscriber QoS to transient local'),
-
         Node(
             package='nav2_controller',
             executable='controller_server',
diff --git a/nav2_bringup/bringup/launch/tb3_simulation_launch.py b/nav2_bringup/bringup/launch/tb3_simulation_launch.py
index 7144b4f2ebbda1ad9b43839dc636b398333cce62..5fad6db3f8adb5da097abfdae34a052933beae9d 100644
--- a/nav2_bringup/bringup/launch/tb3_simulation_launch.py
+++ b/nav2_bringup/bringup/launch/tb3_simulation_launch.py
@@ -38,8 +38,6 @@ def generate_launch_description():
     map_yaml_file = LaunchConfiguration('map')
     use_sim_time = LaunchConfiguration('use_sim_time')
     params_file = LaunchConfiguration('params_file')
-    default_nav_through_poses_bt_xml = LaunchConfiguration('default_nav_through_poses_bt_xml')
-    default_nav_to_pose_bt_xml = LaunchConfiguration('default_nav_to_pose_bt_xml')
     autostart = LaunchConfiguration('autostart')
 
     # Launch configuration variables specific to simulation
@@ -91,20 +89,6 @@ def generate_launch_description():
         default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
         description='Full path to the ROS2 parameters file to use for all launched nodes')
 
-    default_nav_through_poses_bt_xml_cmd = DeclareLaunchArgument(
-        'default_nav_through_poses_bt_xml',
-        default_value=os.path.join(
-            get_package_share_directory('nav2_bt_navigator'),
-            'behavior_trees', 'navigate_through_poses_w_replanning_and_recovery.xml'),
-        description='Full path to the behavior tree xml file to use')
-
-    default_nav_to_pose_bt_xml_cmd = DeclareLaunchArgument(
-        'default_nav_to_pose_bt_xml',
-        default_value=os.path.join(
-            get_package_share_directory('nav2_bt_navigator'),
-            'behavior_trees', 'navigate_to_pose_w_replanning_and_recovery.xml'),
-        description='Full path to the behavior tree xml file to use')
-
     declare_autostart_cmd = DeclareLaunchArgument(
         'autostart', default_value='true',
         description='Automatically startup the nav2 stack')
@@ -186,8 +170,6 @@ def generate_launch_description():
                           'map': map_yaml_file,
                           'use_sim_time': use_sim_time,
                           'params_file': params_file,
-                          'default_nav_through_poses_bt_xml': default_nav_through_poses_bt_xml,
-                          'default_nav_to_pose_bt_xml': default_nav_to_pose_bt_xml,
                           'autostart': autostart}.items())
 
     # Create the launch description and populate
@@ -200,8 +182,6 @@ def generate_launch_description():
     ld.add_action(declare_map_yaml_cmd)
     ld.add_action(declare_use_sim_time_cmd)
     ld.add_action(declare_params_file_cmd)
-    ld.add_action(default_nav_through_poses_bt_xml_cmd)
-    ld.add_action(default_nav_to_pose_bt_xml_cmd)
     ld.add_action(declare_autostart_cmd)
 
     ld.add_action(declare_rviz_config_file_cmd)
diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
index e95c52eb440e7bed3a0d50ae3bf3e12301769396..37c2532818ece7dab97f59b1a4e93587cae3ce4a 100644
--- a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
+++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
@@ -53,10 +53,10 @@ bt_navigator:
     global_frame: map
     robot_base_frame: base_link
     odom_topic: /odom
-    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are set in the launch
-    # files to allow for a commandline change default used is the 
-    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml & 
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
     # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
     plugin_lib_names:
     - nav2_compute_path_to_pose_action_bt_node
     - nav2_compute_path_through_poses_action_bt_node
diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
index 36668e6c9c921fa8b7d0897e2b22d930b24bbcc8..f07e5858467066f832235bedc166b9e17a37b9ba 100644
--- a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
+++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
@@ -53,10 +53,10 @@ bt_navigator:
     global_frame: map
     robot_base_frame: base_link
     odom_topic: /odom
-    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are set in the launch
-    # files to allow for a commandline change default used is the 
-    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml & 
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
     # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
     plugin_lib_names:
     - nav2_compute_path_to_pose_action_bt_node
     - nav2_compute_path_through_poses_action_bt_node
diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml
index aac42e46af2b87e08ea67c18a0934ce34754662c..f6a323781259074ecd37fdd1ed38ad88d11ebba6 100644
--- a/nav2_bringup/bringup/params/nav2_params.yaml
+++ b/nav2_bringup/bringup/params/nav2_params.yaml
@@ -56,10 +56,10 @@ bt_navigator:
     enable_groot_monitoring: True
     groot_zmq_publisher_port: 1666
     groot_zmq_server_port: 1667
-    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are set in the launch
-    # files to allow for a commandline change default used is the 
-    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml & 
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
     # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
     plugin_lib_names:
     - nav2_compute_path_to_pose_action_bt_node
     - nav2_compute_path_through_poses_action_bt_node