diff --git a/nav2_bringup/bringup/launch/nav2_localization_launch.py b/nav2_bringup/bringup/launch/nav2_localization_launch.py
index a460e0bbfaf9f4be135b3bc383bf44523fac3882..9a92ba4ce46809a37eabc7039fa4f3fd8554f838 100644
--- a/nav2_bringup/bringup/launch/nav2_localization_launch.py
+++ b/nav2_bringup/bringup/launch/nav2_localization_launch.py
@@ -41,12 +41,8 @@ def generate_launch_description():
     #              https://github.com/ros2/launch_ros/issues/56
     remappings = [((namespace, '/tf'), '/tf'),
                   ((namespace, '/tf_static'), '/tf_static'),
-                  ('/scan', 'scan'),
                   ('/tf', 'tf'),
-                  ('/tf_static', 'tf_static'),
-                  ('/cmd_vel', 'cmd_vel'),
-                  ('/map', 'map'),
-                  ('/goal_pose', 'goal_pose')]
+                  ('/tf_static', 'tf_static')]
 
     # Create our own temporary YAML files that include substitutions
     param_substitutions = {
diff --git a/nav2_bringup/bringup/launch/nav2_multi_tb3_simulation_launch.py b/nav2_bringup/bringup/launch/nav2_multi_tb3_simulation_launch.py
index 49e306ef1112dcf01c97bc186ea199c16d108809..abcc87c4507dc4e3a18f0c7ce8ea4dc6dd2f3138 100644
--- a/nav2_bringup/bringup/launch/nav2_multi_tb3_simulation_launch.py
+++ b/nav2_bringup/bringup/launch/nav2_multi_tb3_simulation_launch.py
@@ -50,7 +50,7 @@ def generate_launch_description():
 
     # On this example all robots are launched with the same settings
     map_yaml_file = LaunchConfiguration('map')
-    params_file = LaunchConfiguration('params_file')
+
     bt_xml_file = LaunchConfiguration('bt_xml_file')
     autostart = LaunchConfiguration('autostart')
     rviz_config_file = LaunchConfiguration('rviz_config')
@@ -74,10 +74,15 @@ def generate_launch_description():
         default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),
         description='Full path to map file to load')
 
-    declare_params_file_cmd = DeclareLaunchArgument(
-        'params_file',
-        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')
+    declare_robot1_params_file_cmd = DeclareLaunchArgument(
+        'robot1_params_file',
+        default_value=os.path.join(bringup_dir, 'params', 'nav2_multirobot_params_1.yaml'),
+        description='Full path to the ROS2 parameters file to use for robot1 launched nodes')
+
+    declare_robot2_params_file_cmd = DeclareLaunchArgument(
+        'robot2_params_file',
+        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')
 
     declare_bt_xml_cmd = DeclareLaunchArgument(
         'bt_xml_file',
@@ -132,6 +137,8 @@ def generate_launch_description():
             source_file=rviz_config_file,
             replacements={'<robot_namespace>': ('/' + robot['name'])})
 
+        params_file = LaunchConfiguration(robot['name'] + '_params_file')
+
         group = GroupAction([
             # TODO(orduno)
             # Each `action.Node` within the `localization` and `navigation` launch
@@ -204,7 +211,8 @@ def generate_launch_description():
     ld.add_action(declare_simulator_cmd)
     ld.add_action(declare_world_cmd)
     ld.add_action(declare_map_yaml_cmd)
-    ld.add_action(declare_params_file_cmd)
+    ld.add_action(declare_robot1_params_file_cmd)
+    ld.add_action(declare_robot2_params_file_cmd)
     ld.add_action(declare_bt_xml_cmd)
     ld.add_action(declare_use_rviz_cmd)
     ld.add_action(declare_autostart_cmd)
diff --git a/nav2_bringup/bringup/launch/nav2_navigation_launch.py b/nav2_bringup/bringup/launch/nav2_navigation_launch.py
index 20c2377ec1c74f1bf3e3785904080bdcd6903405..dc3f2a58b219c62643f8d813712ee7d0eb27c63a 100644
--- a/nav2_bringup/bringup/launch/nav2_navigation_launch.py
+++ b/nav2_bringup/bringup/launch/nav2_navigation_launch.py
@@ -42,12 +42,8 @@ def generate_launch_description():
     #              https://github.com/ros2/launch_ros/issues/56
     remappings = [((namespace, '/tf'), '/tf'),
                   ((namespace, '/tf_static'), '/tf_static'),
-                  ('/scan', 'scan'),
                   ('/tf', 'tf'),
-                  ('/tf_static', 'tf_static'),
-                  ('/cmd_vel', 'cmd_vel'),
-                  ('/map', 'map'),
-                  ('/goal_pose', 'goal_pose')]
+                  ('/tf_static', 'tf_static')]
 
     # Create our own temporary YAML files that include substitutions
     param_substitutions = {
diff --git a/nav2_bringup/bringup/launch/nav2_tb3_simulation_launch.py b/nav2_bringup/bringup/launch/nav2_tb3_simulation_launch.py
index 08fbe1a26a1a3b143ba8c1c82cb9d55bc046de40..c6534a506b70d9d007fc65c9dd70142babd57ea1 100644
--- a/nav2_bringup/bringup/launch/nav2_tb3_simulation_launch.py
+++ b/nav2_bringup/bringup/launch/nav2_tb3_simulation_launch.py
@@ -16,7 +16,7 @@
 
 import os
 
-from ament_index_python.packages import get_package_prefix, get_package_share_directory
+from ament_index_python.packages import get_package_share_directory
 
 from launch import LaunchDescription
 from launch.actions import (DeclareLaunchArgument, EmitEvent, ExecuteProcess,
@@ -56,11 +56,8 @@ def generate_launch_description():
     #              https://github.com/ros2/launch_ros/issues/56
     remappings = [((namespace, '/tf'), '/tf'),
                   ((namespace, '/tf_static'), '/tf_static'),
-                  ('/scan', 'scan'),
                   ('/tf', 'tf'),
-                  ('/tf_static', 'tf_static'),
-                  ('/cmd_vel', 'cmd_vel'),
-                  ('/map', 'map')]
+                  ('/tf_static', 'tf_static')]
 
     # Declare the launch arguments
     declare_namespace_cmd = DeclareLaunchArgument(
@@ -152,37 +149,19 @@ def generate_launch_description():
         remappings=remappings,
         arguments=[urdf])
 
-    # TODO(orduno) RVIZ crashing if launched as a node: https://github.com/ros2/rviz/issues/442
-    #              Launching as node works after applying the change described on the github issue.
-    #              Once fixed, launch by providing the remappings:
-    # rviz_remappings = [('/tf', 'tf'),
-    #                    ('/tf_static', 'tf_static'),
-    #                    ('goal_pose', 'goal_pose'),
-    #                    ('/clicked_point', 'clicked_point'),
-    #                    ('/initialpose', 'initialpose'),
-    #                    ('/parameter_events', 'parameter_events'),
-    #                    ('/rosout', 'rosout')]
-
-    # start_rviz_cmd = Node(
-    #     package='rviz2',
-    #     node_executable='rviz2',
-    #     node_name='rviz2',
-    #     arguments=['-d', rviz_config_file],
-    #     output='screen',
-    #     use_remappings=IfCondition(use_remappings),
-    #     remappings=rviz_remappings)
-
-    start_rviz_cmd = ExecuteProcess(
+    start_rviz_cmd = Node(
         condition=IfCondition(use_rviz),
-        cmd=[os.path.join(get_package_prefix('rviz2'), 'lib/rviz2/rviz2'),
-             ['-d', rviz_config_file],
-             ['__ns:=/', namespace],
-             '/tf:=tf',
-             '/tf_static:=tf_static',
-             '/goal_pose:=goal_pose',
-             '/clicked_point:=clicked_point',
-             '/initialpose:=initialpose'],
-        cwd=[launch_dir], output='screen')
+        package='rviz2',
+        node_executable='rviz2',
+        node_name='rviz2',
+        arguments=['-d', rviz_config_file],
+        output='screen',
+        use_remappings=IfCondition(use_remappings),
+        remappings=[('/tf', 'tf'),
+                    ('/tf_static', 'tf_static'),
+                    ('goal_pose', 'goal_pose'),
+                    ('/clicked_point', 'clicked_point'),
+                    ('/initialpose', 'initialpose')])
 
     exit_event_handler = RegisterEventHandler(
         event_handler=OnProcessExit(
diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..6c138d09972bbff6985263fb4fb7ad77540767e0
--- /dev/null
+++ b/nav2_bringup/bringup/params/nav2_multirobot_params_1.yaml
@@ -0,0 +1,171 @@
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    alpha1: 0.2
+    alpha2: 0.2
+    alpha3: 0.2
+    alpha4: 0.2
+    alpha5: 0.2
+    base_frame_id: "base_footprint"
+    beam_skip_distance: 0.5
+    beam_skip_error_threshold: 0.9
+    beam_skip_threshold: 0.3
+    do_beamskip: false
+    global_frame_id: "map"
+    lambda_short: 0.1
+    laser_likelihood_max_dist: 2.0
+    laser_max_range: 100.0
+    laser_min_range: -1.0
+    laser_model_type: "likelihood_field"
+    max_beams: 60
+    max_particles: 2000
+    min_particles: 500
+    odom_frame_id: "odom"
+    pf_err: 0.05
+    pf_z: 0.99
+    recovery_alpha_fast: 0.0
+    recovery_alpha_slow: 0.0
+    resample_interval: 1
+    robot_model_type: "differential"
+    save_pose_rate: 0.5
+    sigma_hit: 0.2
+    tf_broadcast: true
+    transform_tolerance: 1.0
+    update_min_a: 0.2
+    update_min_d: 0.25
+    z_hit: 0.5
+    z_max: 0.05
+    z_rand: 0.5
+    z_short: 0.05
+
+amcl_map_client:
+  ros__parameters:
+    use_sim_time: True
+
+amcl_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
+
+bt_navigator_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    debug_trajectory_details: True
+    min_vel_x: 0.0
+    min_vel_y: 0.0
+    max_vel_x: 0.26
+    max_vel_y: 0.0
+    max_vel_theta: 1.0
+    min_speed_xy: 0.0
+    max_speed_xy: 0.26
+    min_speed_theta: 0.0
+    min_x_velocity_threshold: 0.001
+    # Add high threshold velocity for turtlebot 3 issue.
+    # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    acc_lim_x: 2.5
+    acc_lim_y: 0.0
+    acc_lim_theta: 3.2
+    decel_lim_x: -2.5
+    decel_lim_y: 0.0
+    decel_lim_theta: -3.2
+    vx_samples: 20
+    vy_samples: 5
+    vtheta_samples: 20
+    sim_time: 1.7
+    linear_granularity: 0.05
+    xy_goal_tolerance: 0.25
+    transform_tolerance: 0.2
+    critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+    BaseObstacle.scale: 0.02
+    PathAlign.scale: 0.0
+    GoalAlign.scale: 0.0
+    PathDist.scale: 32.0
+    GoalDist.scale: 24.0
+    RotateToGoal.scale: 32.0
+
+controller_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      use_sim_time: True
+      global_frame: odom
+      plugin_names: ["obstacle_layer", "inflation_layer"]
+      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"]
+      rolling_window: true
+      width: 3
+      height: 3
+      resolution: 0.05
+      robot_radius: 0.22
+      inflation_layer.cost_scaling_factor: 3.0
+      obstacle_layer:
+        enabled: True
+        scan:
+          topic: /robot1/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+      observation_sources: scan
+  local_costmap_client:
+    ros__parameters:
+      use_sim_time: True
+  local_costmap_rclcpp_node:
+    ros__parameters:
+      use_sim_time: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      use_sim_time: True
+      robot_radius: 0.22
+      obstacle_layer:
+        enabled: True
+        scan:
+          topic: /robot1/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+      observation_sources: scan
+  global_costmap_client:
+    ros__parameters:
+      use_sim_time: True
+  global_costmap_rclcpp_node:
+    ros__parameters:
+      use_sim_time: True
+
+map_server:
+  ros__parameters:
+    use_sim_time: True
+    yaml_filename: "turtlebot3_world.yaml"
+
+planner_server:
+  ros__parameters:
+    use_sim_time: True
+    tolerance: 0.0
+    use_astar: false
+
+planner_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
diff --git a/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..d1f52ba296c5f410db96bb2610d988dd2571f78f
--- /dev/null
+++ b/nav2_bringup/bringup/params/nav2_multirobot_params_2.yaml
@@ -0,0 +1,171 @@
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    alpha1: 0.2
+    alpha2: 0.2
+    alpha3: 0.2
+    alpha4: 0.2
+    alpha5: 0.2
+    base_frame_id: "base_footprint"
+    beam_skip_distance: 0.5
+    beam_skip_error_threshold: 0.9
+    beam_skip_threshold: 0.3
+    do_beamskip: false
+    global_frame_id: "map"
+    lambda_short: 0.1
+    laser_likelihood_max_dist: 2.0
+    laser_max_range: 100.0
+    laser_min_range: -1.0
+    laser_model_type: "likelihood_field"
+    max_beams: 60
+    max_particles: 2000
+    min_particles: 500
+    odom_frame_id: "odom"
+    pf_err: 0.05
+    pf_z: 0.99
+    recovery_alpha_fast: 0.0
+    recovery_alpha_slow: 0.0
+    resample_interval: 1
+    robot_model_type: "differential"
+    save_pose_rate: 0.5
+    sigma_hit: 0.2
+    tf_broadcast: true
+    transform_tolerance: 1.0
+    update_min_a: 0.2
+    update_min_d: 0.25
+    z_hit: 0.5
+    z_max: 0.05
+    z_rand: 0.5
+    z_short: 0.05
+
+amcl_map_client:
+  ros__parameters:
+    use_sim_time: True
+
+amcl_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
+
+bt_navigator_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    debug_trajectory_details: True
+    min_vel_x: 0.0
+    min_vel_y: 0.0
+    max_vel_x: 0.26
+    max_vel_y: 0.0
+    max_vel_theta: 1.0
+    min_speed_xy: 0.0
+    max_speed_xy: 0.26
+    min_speed_theta: 0.0
+    min_x_velocity_threshold: 0.001
+    # Add high threshold velocity for turtlebot 3 issue.
+    # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    acc_lim_x: 2.5
+    acc_lim_y: 0.0
+    acc_lim_theta: 3.2
+    decel_lim_x: -2.5
+    decel_lim_y: 0.0
+    decel_lim_theta: -3.2
+    vx_samples: 20
+    vy_samples: 5
+    vtheta_samples: 20
+    sim_time: 1.7
+    linear_granularity: 0.05
+    xy_goal_tolerance: 0.25
+    transform_tolerance: 0.2
+    critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+    BaseObstacle.scale: 0.02
+    PathAlign.scale: 0.0
+    GoalAlign.scale: 0.0
+    PathDist.scale: 32.0
+    GoalDist.scale: 24.0
+    RotateToGoal.scale: 32.0
+
+controller_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      use_sim_time: True
+      global_frame: odom
+      plugin_names: ["obstacle_layer", "inflation_layer"]
+      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"]
+      rolling_window: true
+      width: 3
+      height: 3
+      resolution: 0.05
+      robot_radius: 0.22
+      inflation_layer.cost_scaling_factor: 3.0
+      obstacle_layer:
+        enabled: True
+        scan:
+          topic: /robot2/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+      observation_sources: scan
+  local_costmap_client:
+    ros__parameters:
+      use_sim_time: True
+  local_costmap_rclcpp_node:
+    ros__parameters:
+      use_sim_time: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      use_sim_time: True
+      robot_radius: 0.22
+      obstacle_layer:
+        enabled: True
+        scan:
+          topic: /robot2/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+      observation_sources: scan
+  global_costmap_client:
+    ros__parameters:
+      use_sim_time: True
+  global_costmap_rclcpp_node:
+    ros__parameters:
+      use_sim_time: True
+
+map_server:
+  ros__parameters:
+    use_sim_time: True
+    yaml_filename: "turtlebot3_world.yaml"
+
+planner_server:
+  ros__parameters:
+    use_sim_time: True
+    tolerance: 0.0
+    use_astar: false
+
+planner_server_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
diff --git a/nav2_bringup/bringup/params/nav2_params.yaml b/nav2_bringup/bringup/params/nav2_params.yaml
index d8c522f305621fcc809ac17213263301dbc7bd0b..634fced80e7195593823fd8393141f521031f8ac 100644
--- a/nav2_bringup/bringup/params/nav2_params.yaml
+++ b/nav2_bringup/bringup/params/nav2_params.yaml
@@ -102,25 +102,42 @@ local_costmap:
     ros__parameters:
       use_sim_time: True
       global_frame: odom
-      plugin_names: ["obstacle_layer", "inflation_layer"]
-      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"]
+      plugin_names: ["obstacle_layer", "voxel_layer", "inflation_layer"]
+      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
       rolling_window: true
       width: 3
       height: 3
       resolution: 0.05
       robot_radius: 0.22
-      inflation_layer.cost_scaling_factor: 3.0
+      inflation_layer:
+        cost_scaling_factor: 3.0
       obstacle_layer:
         enabled: True
+        observation_sources: scan
         scan:
           topic: /scan
           max_obstacle_height: 2.0
           clearing: True
           marking: True
+          data_type: "LaserScan"
+      voxel_layer:
+        enabled: True
+        publish_voxel_map: True
+        origin_z: 0.0
+        z_resolution: 0.2
+        z_voxels: 10
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: pointcloud
+        pointcloud:
+          topic: /intel_realsense_r200_depth/points
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "PointCloud2"
       static_layer:
         map_subscribe_transient_local: True
       always_send_full_costmap: True
-      observation_sources: scan
   local_costmap_client:
     ros__parameters:
       use_sim_time: True
@@ -132,18 +149,36 @@ global_costmap:
   global_costmap:
     ros__parameters:
       use_sim_time: True
+      plugin_names: ["static_layer", "obstacle_layer", "voxel_layer", "inflation_layer"]
+      plugin_types: ["nav2_costmap_2d::StaticLayer", "nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
       robot_radius: 0.22
       obstacle_layer:
         enabled: True
+        observation_sources: scan
         scan:
           topic: /scan
           max_obstacle_height: 2.0
           clearing: True
           marking: True
+          data_type: "LaserScan"
+      voxel_layer:
+        enabled: True
+        publish_voxel_map: True
+        origin_z: 0.0
+        z_resolution: 0.2
+        z_voxels: 10
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: pointcloud
+        pointcloud:
+          topic: /intel_realsense_r200_depth/points
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "PointCloud2"
       static_layer:
         map_subscribe_transient_local: True
       always_send_full_costmap: True
-      observation_sources: scan
   global_costmap_client:
     ros__parameters:
       use_sim_time: True
diff --git a/nav2_bt_navigator/src/bt_navigator.cpp b/nav2_bt_navigator/src/bt_navigator.cpp
index 9a9a0ad1e5221a93ffd45ff98a7f382475c3599f..ee63854d3a63a0b0a14b3890fde7fc08f3261e41 100644
--- a/nav2_bt_navigator/src/bt_navigator.cpp
+++ b/nav2_bt_navigator/src/bt_navigator.cpp
@@ -62,7 +62,7 @@ BtNavigator::on_configure(const rclcpp_lifecycle::State & /*state*/)
   tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_, this, false);
 
   goal_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>(
-    "/goal_pose",
+    "goal_pose",
     rclcpp::SystemDefaultsQoS(),
     std::bind(&BtNavigator::onGoalPoseReceived, this, std::placeholders::_1));
 
diff --git a/nav2_controller/README.md b/nav2_controller/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..833526829cf2f98b22381e568cb94c096652d3d4
--- /dev/null
+++ b/nav2_controller/README.md
@@ -0,0 +1,8 @@
+# Nav2 Controller
+
+The Nav2 Controller is an [Execution Module](../doc/requirements/requirements.md) that implements the `nav2_msgs::action::FollowPath` action server.
+
+An execution module implementing the `nav2_msgs::action::FollowPath` action server is responsible for generating command velocities for the robot, given the computed path from the planner module in `nav2_planner`. The nav2_controller package is designed to be loaded with plugins for path execution. The plugins need to implement functions in the virtual base class defined in the `local_planner` header file in `nav2_core` package.
+
+
+Currently available controller plugins are: DWB, and [TEB (dashing release)](https://github.com/rst-tu-dortmund/teb_local_planner/tree/dashing-devel).
\ No newline at end of file
diff --git a/nav2_controller/src/nav2_controller.cpp b/nav2_controller/src/nav2_controller.cpp
index 3d31f96278cffc0e7161f94864e2e3fe796b4c06..5e0d1ccd94f5f3c447f0106cb043d023b58fdbe4 100644
--- a/nav2_controller/src/nav2_controller.cpp
+++ b/nav2_controller/src/nav2_controller.cpp
@@ -95,7 +95,7 @@ ControllerServer::on_configure(const rclcpp_lifecycle::State & state)
   RCLCPP_INFO(get_logger(), "Controller frequency set to %.4fHz", controller_frequency_);
 
   odom_sub_ = std::make_unique<nav_2d_utils::OdomSubscriber>(node);
-  vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 1);
+  vel_publisher_ = create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);
 
   // Create the action server that we implement with our followPath method
   action_server_ = std::make_unique<ActionServer>(rclcpp_node_, "FollowPath",
diff --git a/nav2_core/README.md b/nav2_core/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..72a8630c96780f393cd01ab02679f1dc512be91b
--- /dev/null
+++ b/nav2_core/README.md
@@ -0,0 +1,7 @@
+# Nav2 Core
+
+This package hosts the abstract interface (virtual base classes) for plugins to be used with the following:
+- global planner (e.g., `nav2_navfn_planner`)
+- local planner (i.e, path execution controller, e.g `nav2_dwb_controller`)
+- goal checker
+- recovery behaviors
diff --git a/nav2_core/include/nav2_core/local_planner.hpp b/nav2_core/include/nav2_core/local_planner.hpp
index 0ab8f9eeb1cddac6b522acb4cbd02fb82cde44bd..e45ad652974b1467c9833cfb6c94c03e3b22069d 100644
--- a/nav2_core/include/nav2_core/local_planner.hpp
+++ b/nav2_core/include/nav2_core/local_planner.hpp
@@ -54,7 +54,7 @@ namespace nav2_core
 
 /**
  * @class LocalPlanner
- * @brief planner interface that will be inherited by all local planners
+ * @brief planner interface that acts as a virtual base class for all local planner plugins
  */
 class LocalPlanner
 {
diff --git a/nav2_costmap_2d/CMakeLists.txt b/nav2_costmap_2d/CMakeLists.txt
index ca42f6f9a5f893e927aab7226de1b52c6a2b7a80..56b405648c731daf7bfe9080a33ef5a367aced1f 100644
--- a/nav2_costmap_2d/CMakeLists.txt
+++ b/nav2_costmap_2d/CMakeLists.txt
@@ -110,6 +110,10 @@ target_link_libraries(nav2_costmap_2d_markers
   nav2_costmap_2d_core
 )
 
+ament_target_dependencies(nav2_costmap_2d_markers
+  ${dependencies}
+)
+
 add_executable(nav2_costmap_2d_cloud src/costmap_2d_cloud.cpp)
 target_link_libraries(nav2_costmap_2d_cloud
   nav2_costmap_2d_core
@@ -125,7 +129,7 @@ target_link_libraries(nav2_costmap_2d
   layers
 )
 
-install(TARGETS nav2_costmap_2d_core nav2_costmap_2d layers nav2_costmap_2d_client
+install(TARGETS nav2_costmap_2d_core nav2_costmap_2d layers nav2_costmap_2d_client nav2_costmap_2d_markers
   ARCHIVE DESTINATION lib
   LIBRARY DESTINATION lib
   RUNTIME DESTINATION lib/${PROJECT_NAME}
diff --git a/nav2_costmap_2d/README.md b/nav2_costmap_2d/README.md
index 405b9683a6e7be01b8f6f08d8b086c0f6debf360..9dd12247e12e81f63c4bd8c8f3c00c63c4b3a765 100644
--- a/nav2_costmap_2d/README.md
+++ b/nav2_costmap_2d/README.md
@@ -10,7 +10,86 @@ ROS2 port of the ROS1 navigation stack version, with minimal noteable changes ne
 widespread discussion throughout the navigation stack (see issue https://github.com/ros-planning/navigation2/issues/177) and 
 general ROS2 community. A proposal temporary replacement has been submitted as a PR here: https://github.com/ros-planning/navigation2/pull/196
 
+## How to configure using Voxel Layer plugin:
+By default, the navigation stack uses the _Obstacle Layer_ to avoid obstacles in 2D. The _Voxel Layer_ allows for detecting obstacles in 3D using Pointcloud2 data. It requires Pointcloud2 data being published on some topic. For simulation, a Gazebo model of the robot with depth camera enabled will publish a pointcloud topic.
+
+The Voxel Layer plugin can be used to update the local costmap, glocal costmap or both, depending on how you define it in the `nav2_params.yaml` file in the nav2_bringup directory. The voxel layer plugin has to be added to the list of ```plugin_names``` and ```plugin_types``` in the global/local costmap scopes in the param file. If these are not defined in the param file, the default plugins set in nav2_costmap_2d will be used.
+
+Inside each costmap layer (voxel, obstacle, etc) define `observation_sources` param. Here you can define multiple sources to be used with the layer. The param configuration example below shows the way you can configure costmaps to use voxel layer.
+
+The `voxel_layer` param has `observation_source: pointcloud` in it's scope, and the param `pointcloud` has `topic`, and `data_type` inside it's scope. By default, the data_type is `LaserScan`, thus you need to specify `PointCloud2` if you are using PointCould2 data from a depth sensor.
+
+Example param configuration snippet for enabling voxel layer in local costmap is shown below (not all params are shown):
+```
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      plugin_names: ["obstacle_layer", "voxel_layer", "inflation_layer"]
+      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::VoxelLayer", "nav2_costmap_2d::InflationLayer"]
+      obstacle_layer:
+        enabled: True
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+      voxel_layer:
+        enabled: True
+        publish_voxel_map: True
+        origin_z: 0.0
+        z_resolution: 0.2
+        z_voxels: 10
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: pointcloud
+        pointcloud:
+          topic: /intel_realsense_r200_depth/points
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "PointCloud2"
+```
+Please note that not all params needed to run the navigation stack are shown here. This example only shows how you can add different costmap layers, with multiple input sources of different types.
+
+### To visualize the voxels in RVIZ:
+- Make sure `publish_voxel_map` in `voxel_layer` param's scope is set to `True`.
+- Open a new terminal and run:
+  ```ros2 run nav2_costmap_2d nav2_costmap_2d_markers voxel_grid:=/local_costmap/voxel_grid visualization_marker:=/my_marker```
+    Here you can change `my_marker` to any topic name you like for the markers to be published on.
+
+- Then add `my_marker` to RVIZ using the GUI.
+
+
+####Errata:
+- To see the markers in 3D, you will need to change the _view_ in RVIZ to a 3 dimensional view (e.g. orbit) from the RVIZ GUI.
+- Currently due to some bug in rviz, you need to set the `fixed_frame` in the rviz display, to `odom` frame.
+- Using pointcloud data from a saved bag file while using gazebo simulation can be troublesome due to the clock time skipping to an earlier time.
+
+## How to use multiple sensor sources:
+Multiple sources can be added into a costmap layer (e.g., obstacle layer), by listing them under the 'observation_sources' for that layer.
+For example, to add laser scan and pointcloud as two different sources of inputs to the obstacle layer, you can define them in the params file as shown below for the local costmap:
+```
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      plugin_names: ["obstacle_layer", "inflation_layer"]
+      plugin_types: ["nav2_costmap_2d::ObstacleLayer", "nav2_costmap_2d::InflationLayer"]
+      obstacle_layer:
+        enabled: True
+        observation_sources: scan pointcloud
+        scan:
+          topic: /scan
+          data_type: "LaserScan"
+        pointcloud:
+          topic: /intel_realsense_r200_depth/points
+          data_type: "PointCloud2"
+```
+In order to add multiple sources to the global costmap, follow the same procedure shown in the example above, but now adding the sources and their specific params under the `global_costmap` scope.
+
 ## Future Plans
 - Conceptually, the costmap_2d model acts as a world model of what is known from the map, sensor, robot pose, etc. We'd like
 to broaden this world model concept and use costmap's layer concept as motivation for providing a service-style interface to
 potential clients needing information about the world (see issue https://github.com/ros-planning/navigation2/issues/18)
+
diff --git a/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp b/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp
index 22dc74fdfa8b943c4bc2c477d82e469aa50ee2c2..5e963c4f977fed0c9f964619be746c7b2c3965b7 100644
--- a/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp
+++ b/nav2_costmap_2d/include/nav2_costmap_2d/voxel_layer.hpp
@@ -94,7 +94,7 @@ private:
     double * max_y);
 
   bool publish_voxel_;
-  rclcpp::Publisher<nav2_msgs::msg::VoxelGrid>::SharedPtr voxel_pub_;
+  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::VoxelGrid>::SharedPtr voxel_pub_;
   nav2_voxel_grid::VoxelGrid voxel_grid_;
   double z_resolution_, origin_z_;
   int unknown_threshold_, mark_threshold_, size_z_;
diff --git a/nav2_costmap_2d/plugins/obstacle_layer.cpp b/nav2_costmap_2d/plugins/obstacle_layer.cpp
index 347a139bb9c30b39dea6a94e06f42692505fcb6a..e40b02039c8f38e2af7bc4071aca301df3f2de36 100644
--- a/nav2_costmap_2d/plugins/obstacle_layer.cpp
+++ b/nav2_costmap_2d/plugins/obstacle_layer.cpp
@@ -80,6 +80,7 @@ void ObstacleLayer::onInitialize()
     rclcpp::ParameterValue(true));
   declareParameter("max_obstacle_height", rclcpp::ParameterValue(2.0));
   declareParameter("combination_method", rclcpp::ParameterValue(1));
+  declareParameter("observation_sources", rclcpp::ParameterValue(std::string("")));
 
   node_->get_parameter(name_ + "." + "enabled", enabled_);
   node_->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
@@ -87,7 +88,7 @@ void ObstacleLayer::onInitialize()
   node_->get_parameter(name_ + "." + "combination_method", combination_method_);
   node_->get_parameter("track_unknown_space", track_unknown_space);
   node_->get_parameter("transform_tolerance", transform_tolerance);
-  node_->get_parameter("observation_sources", topics_string);
+  node_->get_parameter(name_ + "." + "observation_sources", topics_string);
 
   RCLCPP_INFO(node_->get_logger(), "Subscribed to Topics: %s", topics_string.c_str());
 
diff --git a/nav2_costmap_2d/plugins/voxel_layer.cpp b/nav2_costmap_2d/plugins/voxel_layer.cpp
index 105b88a1492b500b3ab43a811c819cee6b1cd89e..526b6200f4faee854f5d6c9e9a3ac3b81f8854c1 100644
--- a/nav2_costmap_2d/plugins/voxel_layer.cpp
+++ b/nav2_costmap_2d/plugins/voxel_layer.cpp
@@ -88,6 +88,8 @@ void VoxelLayer::onInitialize()
       "voxel_grid", custom_qos);
   }
 
+  voxel_pub_->on_activate();
+
   clearing_endpoints_pub_ = node_->create_publisher<sensor_msgs::msg::PointCloud>(
     "clearing_endpoints", custom_qos);
 
@@ -108,11 +110,12 @@ void VoxelLayer::matchSize()
 
 void VoxelLayer::reset()
 {
+  voxel_pub_->on_deactivate();
   deactivate();
   resetMaps();
-  voxel_grid_.reset();
   activate();
   undeclareAllParameters();
+  voxel_pub_->on_activate();
 }
 
 void VoxelLayer::resetMaps()
diff --git a/nav2_costmap_2d/src/costmap_2d_markers.cpp b/nav2_costmap_2d/src/costmap_2d_markers.cpp
index 423573213692d7a4002d9a232bf9a94fa86924cc..2f1af4f78dc614dcc264f6642096433801c83d37 100644
--- a/nav2_costmap_2d/src/costmap_2d_markers.cpp
+++ b/nav2_costmap_2d/src/costmap_2d_markers.cpp
@@ -62,7 +62,8 @@ float g_colors_a[] = {0.0f, 0.5f, 1.0f};
 
 V_Cell g_cells;
 nav2_util::LifecycleNode::SharedPtr g_node;
-rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr pub;
+rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::Marker>::SharedPtr pub;
+
 void voxelCallback(const nav2_msgs::msg::VoxelGrid::ConstSharedPtr grid)
 {
   if (grid->data.empty()) {
@@ -150,6 +151,7 @@ int main(int argc, char ** argv)
 
   pub = g_node->create_publisher<visualization_msgs::msg::Marker>(
     "visualization_marker", 1);
+  pub->on_activate();
 
   auto sub = g_node->create_subscription<nav2_msgs::msg::VoxelGrid>(
     "voxel_grid", rclcpp::SystemDefaultsQoS(), voxelCallback);
diff --git a/nav2_costmap_2d/src/costmap_2d_publisher.cpp b/nav2_costmap_2d/src/costmap_2d_publisher.cpp
index 32499c8b4afa7f01408dfeaa5c3142e8fd0d698d..5e6e414c183cecb78d04b842af7b2373a473b114 100644
--- a/nav2_costmap_2d/src/costmap_2d_publisher.cpp
+++ b/nav2_costmap_2d/src/costmap_2d_publisher.cpp
@@ -165,8 +165,10 @@ void Costmap2DPublisher::prepareCostmap()
 
 void Costmap2DPublisher::publishCostmap()
 {
-  prepareCostmap();
-  costmap_raw_pub_->publish(costmap_raw_);
+  if (node_->count_subscribers(costmap_raw_pub_->get_topic_name()) > 0) {
+    prepareCostmap();
+    costmap_raw_pub_->publish(costmap_raw_);
+  }
   float resolution = costmap_->getResolution();
 
   if (always_send_full_costmap_ || grid_.info.resolution != resolution ||
@@ -175,28 +177,31 @@ void Costmap2DPublisher::publishCostmap()
     saved_origin_x_ != costmap_->getOriginX() ||
     saved_origin_y_ != costmap_->getOriginY())
   {
-    prepareGrid();
-    costmap_pub_->publish(grid_);
+    if (node_->count_subscribers(costmap_pub_->get_topic_name()) > 0) {
+      prepareGrid();
+      costmap_pub_->publish(grid_);
+    }
   } else if (x0_ < xn_) {
-    std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
-    // Publish Just an Update
-    map_msgs::msg::OccupancyGridUpdate update;
-    update.header.stamp = rclcpp::Time();
-    update.header.frame_id = global_frame_;
-    update.x = x0_;
-    update.y = y0_;
-    update.width = xn_ - x0_;
-    update.height = yn_ - y0_;
-    update.data.resize(update.width * update.height);
-
-    unsigned int i = 0;
-    for (unsigned int y = y0_; y < yn_; y++) {
-      for (unsigned int x = x0_; x < xn_; x++) {
-        unsigned char cost = costmap_->getCost(x, y);
-        update.data[i++] = cost_translation_table_[cost];
+    if (node_->count_subscribers(costmap_update_pub_->get_topic_name()) > 0) {
+      std::unique_lock<Costmap2D::mutex_t> lock(*(costmap_->getMutex()));
+      // Publish Just an Update
+      map_msgs::msg::OccupancyGridUpdate update;
+      update.header.stamp = rclcpp::Time();
+      update.header.frame_id = global_frame_;
+      update.x = x0_;
+      update.y = y0_;
+      update.width = xn_ - x0_;
+      update.height = yn_ - y0_;
+      update.data.resize(update.width * update.height);
+      unsigned int i = 0;
+      for (unsigned int y = y0_; y < yn_; y++) {
+        for (unsigned int x = x0_; x < xn_; x++) {
+          unsigned char cost = costmap_->getCost(x, y);
+          update.data[i++] = cost_translation_table_[cost];
+        }
       }
+      costmap_update_pub_->publish(update);
     }
-    costmap_update_pub_->publish(update);
   }
 
   xn_ = yn_ = 0;
diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp
index 3c846558f60acfc08f50c744841d49377876cdc0..c6789f045291e940af33fb8dd1c834f0bf1071f2 100644
--- a/nav2_costmap_2d/src/costmap_2d_ros.cpp
+++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp
@@ -89,7 +89,7 @@ Costmap2DROS::Costmap2DROS(
   declare_parameter("height", rclcpp::ParameterValue(10));
   declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
   declare_parameter("map_topic", rclcpp::ParameterValue(
-      (parent_namespace_ == "/" ? "" : parent_namespace_ ) + std::string("/map")));
+      (parent_namespace_ == "/" ? "/" : parent_namespace_ + "/") + std::string("map")));
   declare_parameter("observation_sources", rclcpp::ParameterValue(std::string("")));
   declare_parameter("origin_x", rclcpp::ParameterValue(0.0));
   declare_parameter("origin_y", rclcpp::ParameterValue(0.0));
diff --git a/nav2_costmap_2d/test/integration/inflation_tests.cpp b/nav2_costmap_2d/test/integration/inflation_tests.cpp
index cd7e1c89472fb748fbd05ef8ce7edf5e64a616da..357852b6df58dd6031da35c4b4832f94f1cfbe41 100644
--- a/nav2_costmap_2d/test/integration/inflation_tests.cpp
+++ b/nav2_costmap_2d/test/integration/inflation_tests.cpp
@@ -183,7 +183,7 @@ void TestNode::initNode(double inflation_radius)
     "inflation_test_node", "", false, options);
 
   // Declare non-plugin specific costmap parameters
-  node_->declare_parameter("map_topic", rclcpp::ParameterValue(std::string("/map")));
+  node_->declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
   node_->declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
   node_->declare_parameter("use_maximum", rclcpp::ParameterValue(false));
   node_->declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
diff --git a/nav2_costmap_2d/test/integration/obstacle_tests.cpp b/nav2_costmap_2d/test/integration/obstacle_tests.cpp
index 25b41e5d20004cb970f47a9cd499a4dea5ced4c6..0f1ddd3928226202530ca1dbb231ebc59caa97de 100644
--- a/nav2_costmap_2d/test/integration/obstacle_tests.cpp
+++ b/nav2_costmap_2d/test/integration/obstacle_tests.cpp
@@ -104,7 +104,7 @@ public:
   TestNode()
   {
     node_ = std::make_shared<TestLifecycleNode>("obstacle_test_node");
-    node_->declare_parameter("map_topic", rclcpp::ParameterValue(std::string("/map")));
+    node_->declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
     node_->declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
     node_->declare_parameter("use_maximum", rclcpp::ParameterValue(false));
     node_->declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
diff --git a/nav2_costmap_2d/test/integration/test_collision_checker.cpp b/nav2_costmap_2d/test/integration/test_collision_checker.cpp
index a7a79c07d81f30353562568f6309de3ca0a5ac1d..01e78ffcf169ed1aa3b4e3a140b7ed468aeaeb0e 100644
--- a/nav2_costmap_2d/test/integration/test_collision_checker.cpp
+++ b/nav2_costmap_2d/test/integration/test_collision_checker.cpp
@@ -90,7 +90,7 @@ public:
     global_frame_("map")
   {
     // Declare non-plugin specific costmap parameters
-    declare_parameter("map_topic", rclcpp::ParameterValue(std::string("/map")));
+    declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
     declare_parameter("track_unknown_space", rclcpp::ParameterValue(true));
     declare_parameter("use_maximum", rclcpp::ParameterValue(false));
     declare_parameter("lethal_cost_threshold", rclcpp::ParameterValue(100));
diff --git a/nav2_system_tests/package.xml b/nav2_system_tests/package.xml
index ada78f783ef07f55a7da253451a8ce811b7d4574..afd4b166743466c7500bc3de38cc46ecaca35885 100644
--- a/nav2_system_tests/package.xml
+++ b/nav2_system_tests/package.xml
@@ -45,8 +45,6 @@
   <exec_depend>std_msgs</exec_depend>
   <exec_depend>tf2_geometry_msgs</exec_depend>
   <exec_depend>gazebo_ros_pkgs</exec_depend>
-  <exec_depend>launch_ros</exec_depend>
-  <exec_depend>launch_testing</exec_depend>
   <exec_depend>navigation2</exec_depend>
   <exec_depend>lcov</exec_depend>
   <exec_depend>robot_state_publisher</exec_depend>
diff --git a/nav2_system_tests/src/localization/test_localization_node.cpp b/nav2_system_tests/src/localization/test_localization_node.cpp
index bf543f192888b300e62eac236a3caac103a95c94..32ecf2145150af3de83acb410aab8dd5cb675b4f 100644
--- a/nav2_system_tests/src/localization/test_localization_node.cpp
+++ b/nav2_system_tests/src/localization/test_localization_node.cpp
@@ -43,7 +43,7 @@ public:
 
     node = rclcpp::Node::make_shared("localization_test");
 
-    while (node->count_subscribers("/scan") < 1) {
+    while (node->count_subscribers("scan") < 1) {
       std::this_thread::sleep_for(100ms);
       rclcpp::spin_some(node);
     }
diff --git a/nav2_system_tests/src/system/test_multi_robot_launch.py b/nav2_system_tests/src/system/test_multi_robot_launch.py
index 292b1d40f1afd295f706fb303dc23d78b0bd02a3..dc8270a79a4b81bd733dfd491a528b87e09244f7 100755
--- a/nav2_system_tests/src/system/test_multi_robot_launch.py
+++ b/nav2_system_tests/src/system/test_multi_robot_launch.py
@@ -40,7 +40,10 @@ def generate_launch_description():
                                os.getenv('BT_NAVIGATOR_XML'))
 
     bringup_dir = get_package_share_directory('nav2_bringup')
-    params_file = os.path.join(bringup_dir, 'params/nav2_params.yaml')
+    robot1_params_file = os.path.join(bringup_dir,  # noqa: F841
+        'params/nav2_multirobot_params_1.yaml')
+    robot2_params_file = os.path.join(bringup_dir,  # noqa: F841
+        'params/nav2_multirobot_params_2.yaml')
 
     # Names and poses of the robots
     robots = [
@@ -86,6 +89,8 @@ def generate_launch_description():
     # Define commands for launching the navigation instances
     nav_instances_cmds = []
     for robot in robots:
+        params_file = eval(robot['name'] + '_params_file')
+
         group = GroupAction([
             # Instances use the robot's name for namespace
             PushRosNamespace(robot['name']),
diff --git a/tools/ros2_dependencies.repos b/tools/ros2_dependencies.repos
index 6b58b64a308d4cdf94999189d41359c0ec0d73e9..71a7cdf3dec23a7dc6de94f220ca3977302bfd10 100644
--- a/tools/ros2_dependencies.repos
+++ b/tools/ros2_dependencies.repos
@@ -2,7 +2,7 @@ repositories:
   BehaviorTree.CPP:
     type: git
     url: https://github.com/BehaviorTree/BehaviorTree.CPP.git
-    version: ros2-dev
+    version: 3.0.9
   angles:
     type: git
     url: https://github.com/ros/angles.git
diff --git a/tools/run_test_suite.bash b/tools/run_test_suite.bash
index df3480e53799a02072bdf2ec383ff3f5ced156fe..b4e2c45a23631cbe8555e7e62893032d848f1057 100755
--- a/tools/run_test_suite.bash
+++ b/tools/run_test_suite.bash
@@ -25,3 +25,4 @@ $SCRIPT_DIR/ctest_retry.bash -r 3 -d build/nav2_system_tests -t test_planner_ran
 $SCRIPT_DIR/ctest_retry.bash -r 3 -d build/nav2_system_tests -t test_bt_navigator$
 $SCRIPT_DIR/ctest_retry.bash -r 3 -d build/nav2_system_tests -t test_bt_navigator_with_dijkstra$
 $SCRIPT_DIR/ctest_retry.bash -r 3 -d build/nav2_system_tests -t test_dynamic_obstacle$
+$SCRIPT_DIR/ctest_retry.bash -r 3 -d build/nav2_system_tests -t test_multi_robot$