diff --git a/nav2_bringup/CMakeLists.txt b/nav2_bringup/CMakeLists.txt
index 548b021c7a5ee8185e97f227446b5e65b950417f..f9921217779c71e7eea799b347dc43c72e514d65 100644
--- a/nav2_bringup/CMakeLists.txt
+++ b/nav2_bringup/CMakeLists.txt
@@ -8,5 +8,9 @@ find_package(navigation2 REQUIRED)
 nav2_package()
 
 install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})
+install(DIRECTORY maps DESTINATION share/${PROJECT_NAME})
+install(DIRECTORY rviz DESTINATION share/${PROJECT_NAME})
+install(DIRECTORY worlds DESTINATION share/${PROJECT_NAME})
+install(DIRECTORY params DESTINATION share/${PROJECT_NAME})
 
 ament_package()
diff --git a/nav2_bringup/launch/gazebo_rviz2_launch.py b/nav2_bringup/launch/gazebo_rviz2_launch.py
deleted file mode 100644
index 1b3acaf4afd680fedce431c35d789cb23383c8b0..0000000000000000000000000000000000000000
--- a/nav2_bringup/launch/gazebo_rviz2_launch.py
+++ /dev/null
@@ -1,34 +0,0 @@
-# Copyright (c) 2019 Intel Corporation
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-#     http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-import os
-import sys
-from launch import LaunchDescription
-from launch.substitutions import EnvironmentVariable
-import launch.actions
-import launch_ros.actions
-
-def generate_launch_description():
-    world = launch.substitutions.LaunchConfiguration('world')
-
-    return LaunchDescription([
-        launch.actions.DeclareLaunchArgument(
-            'world', description='Full path to world file to load'),
-
-        launch.actions.ExecuteProcess(
-            cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_init.so', world],
-            output='screen'),
-
-        launch_ros.actions.Node(package='rviz2', node_executable='rviz2', output='screen')
-    ])
diff --git a/nav2_bringup/launch/nav2_bringup_launch.py b/nav2_bringup/launch/nav2_bringup_launch.py
index 285bd94837e3e39cf795e871e55a5e38f389600d..079f665f77763107baccc278d1710d563769f147 100644
--- a/nav2_bringup/launch/nav2_bringup_launch.py
+++ b/nav2_bringup/launch/nav2_bringup_launch.py
@@ -14,118 +14,89 @@
 
 import os
 
-from ament_index_python.packages import get_package_prefix
-from ament_index_python.packages import get_package_share_directory
-from launch.conditions import IfCondition
+from ament_index_python.packages import get_package_prefix, get_package_share_directory
 
-import launch.actions
-import launch_ros.actions
-
-from nav2_common.launch import RewrittenYaml
+from launch import LaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir
+from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, IncludeLaunchDescription
+from launch_ros.actions import Node
 
 
 def generate_launch_description():
     # Get the launch directory
-    launch_dir = os.path.join(get_package_share_directory('nav2_bringup'), 'launch')
+    bringup_dir = get_package_share_directory('nav2_bringup')
+    launch_dir = os.path.join(bringup_dir, 'launch')
 
     # Create the launch configuration variables
-    map_yaml_file = launch.substitutions.LaunchConfiguration('map')
-    use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time')
-    params_file = launch.substitutions.LaunchConfiguration('params')
-    bt_xml_file = launch.substitutions.LaunchConfiguration('bt_xml_file')
-    autostart = launch.substitutions.LaunchConfiguration('autostart')
+    map_yaml_file = LaunchConfiguration('map')
+    use_sim_time = LaunchConfiguration('use_sim_time')
+    params_file = LaunchConfiguration('params_file')
+    bt_xml_file = LaunchConfiguration('bt_xml_file')
+    autostart = LaunchConfiguration('autostart')
 
-    stdout_linebuf_envvar = launch.actions.SetEnvironmentVariable(
+    stdout_linebuf_envvar = SetEnvironmentVariable(
         'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1')
 
-    # Create our own temporary YAML files that include substitutions
-    param_substitutions = {
-        'use_sim_time': use_sim_time,
-        'yaml_filename': map_yaml_file,
-        'bt_xml_filename': bt_xml_file,
-        'autostart': autostart
-    }
-
-    configured_params = RewrittenYaml(
-        source_file=params_file, rewrites=param_substitutions,
-        convert_types=True)
-
     # Declare the launch arguments
-    declare_map_yaml_cmd = launch.actions.DeclareLaunchArgument(
+    declare_map_yaml_cmd = DeclareLaunchArgument(
         'map',
-        default_value=os.path.join(launch_dir, 'turtlebot3_world.yaml'),
-        description='Full path to map file to load')
+        description='Full path to map yaml file to load')
 
-    declare_use_sim_time_cmd = launch.actions.DeclareLaunchArgument(
+    declare_use_sim_time_cmd = DeclareLaunchArgument(
         'use_sim_time',
         default_value='false',
         description='Use simulation (Gazebo) clock if true')
 
-    declare_params_file_cmd = launch.actions.DeclareLaunchArgument(
-        'params',
-        default_value=os.path.join(launch_dir, 'nav2_params.yaml'),
+    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_autostart_cmd = launch.actions.DeclareLaunchArgument(
-        'autostart', default_value='true',
-        description='Automatically startup the nav2 stack')
-
-    declare_bt_xml_cmd = launch.actions.DeclareLaunchArgument(
+    declare_bt_xml_cmd = DeclareLaunchArgument(
         'bt_xml_file',
-        default_value=os.path.join(get_package_prefix('nav2_bt_navigator'),
+        default_value=os.path.join(
+            get_package_prefix('nav2_bt_navigator'),
             'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
         description='Full path to the behavior tree xml file to use')
 
-    start_map_server_cmd = launch_ros.actions.Node(
-        package='nav2_map_server',
-        node_executable='map_server',
-        node_name='map_server',
-        output='screen',
-        parameters=[configured_params])
-
-    start_localizer_cmd = launch_ros.actions.Node(
-        package='nav2_amcl',
-        node_executable='amcl',
-        node_name='amcl',
-        output='screen',
-        parameters=[configured_params])
-
-    start_dwb_cmd = launch_ros.actions.Node(
-        package='dwb_controller',
-        node_executable='dwb_controller',
-        output='screen',
-        parameters=[configured_params])
-
-    start_planner_cmd = launch_ros.actions.Node(
-        package='nav2_planner',
-        node_executable='planner_server',
-        node_name='planner_server',
-        output='screen',
-        parameters=[configured_params])
-
-    start_recovery_cmd = launch_ros.actions.Node(
-        package='nav2_recoveries',
-        node_executable='recoveries_node',
-        node_name='recoveries',
-        output='screen',
-        parameters=[{'use_sim_time': use_sim_time}])
-
-    start_navigator_cmd = launch_ros.actions.Node(
-        package='nav2_bt_navigator',
-        node_executable='bt_navigator',
-        node_name='bt_navigator',
-        output='screen',
-        parameters=[configured_params])
+    declare_autostart_cmd = DeclareLaunchArgument(
+        'autostart', default_value='true',
+        description='Automatically startup the nav2 stack')
 
-    start_lifecycle_manager_cmd = launch_ros.actions.Node(
+    # Specify the actions
+    start_localization_cmd = IncludeLaunchDescription(
+        PythonLaunchDescriptionSource(os.path.join(launch_dir, 'nav2_localization_launch.py')),
+        launch_arguments={'map': map_yaml_file,
+                          'use_sim_time': use_sim_time,
+                          'autostart': autostart,
+                          'params_file': params_file,
+                          'use_lifecycle_mgr': 'false'}.items())
+
+    start_navigation_cmd = IncludeLaunchDescription(
+        PythonLaunchDescriptionSource(os.path.join(launch_dir, 'nav2_navigation_launch.py')),
+        launch_arguments={'use_sim_time': use_sim_time,
+                          'autostart': autostart,
+                          'params_file': params_file,
+                          'bt_xml_file': bt_xml_file,
+                          'use_lifecycle_mgr': 'false',
+                          'map_subscribe_transient_local': 'true'}.items())
+
+    start_lifecycle_manager_cmd = Node(
         package='nav2_lifecycle_manager',
         node_executable='lifecycle_manager',
         node_name='lifecycle_manager',
         output='screen',
-        parameters=[configured_params])
+        parameters=[{'use_sim_time': use_sim_time},
+                    {'autostart': autostart},
+                    {'node_names': ['map_server',
+                                    'amcl',
+                                    'dwb_controller',
+                                    'planner_server',
+                                    'bt_navigator']}])
 
     # Create the launch description and populate
-    ld = launch.LaunchDescription()
+    ld = LaunchDescription()
 
     # Set environment variables
     ld.add_action(stdout_linebuf_envvar)
@@ -139,11 +110,7 @@ def generate_launch_description():
 
     # Add the actions to launch all of the navigation nodes
     ld.add_action(start_lifecycle_manager_cmd)
-    ld.add_action(start_map_server_cmd)
-    ld.add_action(start_localizer_cmd)
-    ld.add_action(start_dwb_cmd)
-    ld.add_action(start_planner_cmd)
-    ld.add_action(start_recovery_cmd)
-    ld.add_action(start_navigator_cmd)
+    ld.add_action(start_localization_cmd)
+    ld.add_action(start_navigation_cmd)
 
     return ld
diff --git a/nav2_bringup/launch/nav2_localization_launch.py b/nav2_bringup/launch/nav2_localization_launch.py
index 1529361bc12dcc1f2f595af6fca17bdee10c0309..fd0b89ddbc28ac6e4a907a94dd132a1ff6f86897 100644
--- a/nav2_bringup/launch/nav2_localization_launch.py
+++ b/nav2_bringup/launch/nav2_localization_launch.py
@@ -12,73 +12,86 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-import launch.actions
-from launch import LaunchDescription
+import os
 
-import launch_ros.actions
+from ament_index_python.packages import get_package_share_directory
 
 from nav2_common.launch import RewrittenYaml
 
+from launch import LaunchDescription
+from launch.conditions import IfCondition
+from launch.substitutions import LaunchConfiguration
+from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
+from launch_ros.actions import Node
+
 
 def generate_launch_description():
-    map_yaml_file = launch.substitutions.LaunchConfiguration('map')
-    use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time',
-                                                            default='false')
-    autostart = launch.substitutions.LaunchConfiguration('autostart')
-    params_file = launch.substitutions.LaunchConfiguration('params')
+    # Get the launch directory
+    bringup_dir = get_package_share_directory('nav2_bringup')
+
+    map_yaml_file = LaunchConfiguration('map')
+    use_sim_time = LaunchConfiguration('use_sim_time')
+    autostart = LaunchConfiguration('autostart')
+    params_file = LaunchConfiguration('params_file')
+    use_lifecycle_mgr = LaunchConfiguration('use_lifecycle_mgr')
 
     # Create our own temporary YAML files that include substitutions
     param_substitutions = {
         'use_sim_time': use_sim_time,
-        'yaml_filename': map_yaml_file
-    }
+        'yaml_filename': map_yaml_file}
+
     configured_params = RewrittenYaml(
-        source_file=params_file, rewrites=param_substitutions,
+        source_file=params_file,
+        rewrites=param_substitutions,
         convert_types=True)
 
     return LaunchDescription([
         # Set env var to print messages to stdout immediately
-        launch.actions.SetEnvironmentVariable(
-            'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1'),
+        SetEnvironmentVariable('RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1'),
 
-        launch.actions.DeclareLaunchArgument(
-            'map', description='Full path to map file to load'),
+        DeclareLaunchArgument(
+            'map',
+            default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),
+            description='Full path to map yaml file to load'),
 
-        launch.actions.DeclareLaunchArgument(
+        DeclareLaunchArgument(
             'use_sim_time', default_value='false',
             description='Use simulation (Gazebo) clock if true'),
 
-        launch.actions.DeclareLaunchArgument(
+        DeclareLaunchArgument(
             'autostart', default_value='true',
             description='Automatically startup the nav2 stack'),
 
-        launch.actions.DeclareLaunchArgument(
-            'params',
-            default_value=[launch.substitutions.ThisLaunchFileDir(),
-                           '/nav2_params.yaml'],
+        DeclareLaunchArgument(
+            'params_file',
+            default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
             description='Full path to the ROS2 parameters file to use'),
 
-        launch_ros.actions.Node(
+        DeclareLaunchArgument(
+            'use_lifecycle_mgr', default_value='true',
+            description='Whether to launch the lifecycle manager'),
+
+        Node(
             package='nav2_map_server',
             node_executable='map_server',
             node_name='map_server',
             output='screen',
             parameters=[configured_params]),
 
-        launch_ros.actions.Node(
+        Node(
             package='nav2_amcl',
             node_executable='amcl',
             node_name='amcl',
             output='screen',
             parameters=[configured_params]),
 
-        launch_ros.actions.Node(
+        Node(
+            condition=IfCondition(use_lifecycle_mgr),
             package='nav2_lifecycle_manager',
             node_executable='lifecycle_manager',
-            node_name='lifecycle_manager_localize',
+            node_name='lifecycle_manager_localization',
             output='screen',
             parameters=[{'use_sim_time': use_sim_time},
                         {'autostart': autostart},
-                        {'node_names': ['map_server', 'amcl']}]),
-
+                        {'node_names': ['map_server', 'amcl']}])
     ])
diff --git a/nav2_bringup/launch/nav2_navigation_launch.py b/nav2_bringup/launch/nav2_navigation_launch.py
index 3be794f0f116cfac64ac894fc2b5231296f4e03c..c92aa1723c52c797a2b567a1f044bf23404fe375 100644
--- a/nav2_bringup/launch/nav2_navigation_launch.py
+++ b/nav2_bringup/launch/nav2_navigation_launch.py
@@ -14,91 +14,103 @@
 
 import os
 
-from launch import LaunchDescription
-import launch.actions
-
-import launch_ros.actions
-
-from ament_index_python.packages import get_package_prefix
+from ament_index_python.packages import get_package_prefix, get_package_share_directory
 
 from nav2_common.launch import RewrittenYaml
 
+from launch import LaunchDescription
+from launch.conditions import IfCondition
+from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir
+from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
+from launch_ros.actions import Node
+
 
 def generate_launch_description():
-    use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time', 
-                                                            default='false')
-    autostart = launch.substitutions.LaunchConfiguration('autostart')
-    params_file = launch.substitutions.LaunchConfiguration('params')
-    bt_xml_file = launch.substitutions.LaunchConfiguration('bt_xml_file')
+    # Get the launch directory
+    bringup_dir = get_package_share_directory('nav2_bringup')
+
+    use_sim_time = LaunchConfiguration('use_sim_time')
+    autostart = LaunchConfiguration('autostart')
+    params_file = LaunchConfiguration('params_file')
+    bt_xml_file = LaunchConfiguration('bt_xml_file')
+    use_lifecycle_mgr = LaunchConfiguration('use_lifecycle_mgr')
+    map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local')
 
     # Create our own temporary YAML files that include substitutions
     param_substitutions = {
         'use_sim_time': use_sim_time,
         'bt_xml_filename': bt_xml_file,
         'autostart': autostart,
-        'map_subscribe_transient_local': 'False'
-    }
+        'map_subscribe_transient_local': map_subscribe_transient_local}
 
     configured_params = RewrittenYaml(
-        source_file=params_file, rewrites=param_substitutions,
-        convert_types=True)
+            source_file=params_file,
+            rewrites=param_substitutions,
+            convert_types=True)
 
     return LaunchDescription([
         # Set env var to print messages to stdout immediately
-        launch.actions.SetEnvironmentVariable(
-            'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1'),
+        SetEnvironmentVariable('RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1'),
 
-        launch.actions.DeclareLaunchArgument(
+        DeclareLaunchArgument(
             'use_sim_time', default_value='false',
             description='Use simulation (Gazebo) clock if true'),
 
-        launch.actions.DeclareLaunchArgument(
+        DeclareLaunchArgument(
             'autostart', default_value='true',
             description='Automatically startup the nav2 stack'),
 
-        launch.actions.DeclareLaunchArgument(
-            'params',
-            default_value=[launch.substitutions.ThisLaunchFileDir(), 
-                           '/nav2_params.yaml'],
+        DeclareLaunchArgument(
+            'params_file',
+            default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
             description='Full path to the ROS2 parameters file to use'),
 
-        launch.actions.DeclareLaunchArgument(
+        DeclareLaunchArgument(
             'bt_xml_file',
             default_value=os.path.join(get_package_prefix('nav2_bt_navigator'),
                 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
             description='Full path to the behavior tree xml file to use'),
 
-        launch_ros.actions.Node(
+        DeclareLaunchArgument(
+            'use_lifecycle_mgr', default_value='true',
+            description='Whether to launch the lifecycle manager'),
+
+        DeclareLaunchArgument(
+            'map_subscribe_transient_local', default_value='false',
+            description='Whether to set the map subscriber QoS to transient local'),
+
+        Node(
             package='dwb_controller',
             node_executable='dwb_controller',
             output='screen',
             parameters=[configured_params]),
 
-        launch_ros.actions.Node(
+        Node(
             package='nav2_planner',
             node_executable='planner_server',
             node_name='planner_server',
             output='screen',
             parameters=[configured_params]),
 
-        launch_ros.actions.Node(
+        Node(
             package='nav2_recoveries',
             node_executable='recoveries_node',
             node_name='recoveries',
             output='screen',
             parameters=[{'use_sim_time': use_sim_time}]),
 
-        launch_ros.actions.Node(
+        Node(
             package='nav2_bt_navigator',
             node_executable='bt_navigator',
             node_name='bt_navigator',
             output='screen',
             parameters=[configured_params]),
 
-        launch_ros.actions.Node(
+        Node(
+            condition=IfCondition(use_lifecycle_mgr),
             package='nav2_lifecycle_manager',
             node_executable='lifecycle_manager',
-            node_name='lifecycle_manager_control',
+            node_name='lifecycle_manager_navigation',
             output='screen',
             parameters=[{'use_sim_time': use_sim_time},
                         {'autostart': autostart},
diff --git a/nav2_bringup/launch/nav2_simulation_launch.py b/nav2_bringup/launch/nav2_simulation_launch.py
deleted file mode 100644
index 9f3045136e4f9bae25444ee446e3dcb359d6c88a..0000000000000000000000000000000000000000
--- a/nav2_bringup/launch/nav2_simulation_launch.py
+++ /dev/null
@@ -1,222 +0,0 @@
-# Copyright (c) 2018 Intel Corporation
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-#     http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-""" This is all-in-one launch script intended for use by nav2 developers. """
-
-import os
-
-from ament_index_python.packages import get_package_prefix
-from ament_index_python.packages import get_package_share_directory
-from launch.conditions import IfCondition
-from nav2_common.launch import RewrittenYaml
-
-import launch.actions
-import launch_ros.actions
-
-
-def generate_launch_description():
-    # Get the launch directory
-    launch_dir = os.path.join(get_package_share_directory('nav2_bringup'), 'launch')
-
-    # Create the launch configuration variables
-    autostart = launch.substitutions.LaunchConfiguration('autostart')
-    bt_xml_file = launch.substitutions.LaunchConfiguration('bt')
-    map_yaml_file = launch.substitutions.LaunchConfiguration('map')
-    params_file = launch.substitutions.LaunchConfiguration('params')
-    rviz_config_file = launch.substitutions.LaunchConfiguration('rviz_config')
-    simulator = launch.substitutions.LaunchConfiguration('simulator')
-    use_sim_time = launch.substitutions.LaunchConfiguration('use_sim_time')
-    use_simulation = launch.substitutions.LaunchConfiguration('use_simulation')
-    world = launch.substitutions.LaunchConfiguration('world')
-
-    # Create our own temporary YAML files that include the following parameter substitutions
-    param_substitutions = {
-        'autostart': autostart,
-        'bt_xml_filename': bt_xml_file,
-        'use_sim_time': use_sim_time,
-        'yaml_filename': map_yaml_file
-    }
-    configured_params = RewrittenYaml(
-        source_file=params_file, rewrites=param_substitutions, convert_types=True)
-
-    # Declare the launch arguments
-    declare_autostart_cmd = launch.actions.DeclareLaunchArgument(
-        'autostart',
-        default_value='false',
-        description='Automatically startup the nav2 stack')
-
-    declare_bt_xml_cmd = launch.actions.DeclareLaunchArgument(
-        'bt',
-        default_value=os.path.join(
-            get_package_prefix('nav2_bt_navigator'),
-            'behavior_trees/navigate_w_replanning_and_recovery.xml'),
-        description='Full path to the Behavior Tree XML file to use for the BT navigator')
-
-    declare_map_yaml_cmd = launch.actions.DeclareLaunchArgument(
-        'map',
-        default_value='turtlebot3_world.yaml',
-        description='Full path to map file to load')
-
-    declare_params_file_cmd = launch.actions.DeclareLaunchArgument(
-        'params',
-        default_value=[launch.substitutions.ThisLaunchFileDir(), '/nav2_params.yaml'],
-        description='Full path to the ROS2 parameters file to use for all launched nodes')
-
-    declare_rviz_config_file_cmd = launch.actions.DeclareLaunchArgument(
-        'rviz_config',
-        default_value='nav2_default_view.rviz',
-        description='Full path to the RVIZ config file to use')
-
-    declare_simulator_cmd = launch.actions.DeclareLaunchArgument(
-        'simulator',
-        default_value='gazebo',
-        description='The simulator to use (gazebo or gzserver)')
-
-    declare_use_sim_time_cmd = launch.actions.DeclareLaunchArgument(
-        'use_sim_time',
-        default_value='true',
-        description='Use simulation (Gazebo) clock if true')
-
-    declare_use_simulation_cmd = launch.actions.DeclareLaunchArgument(
-        'use_simulation',
-        default_value='True',
-        description='Whether to run in simulation')
-
-    declare_world_cmd = launch.actions.DeclareLaunchArgument(
-        'world',
-        default_value=os.path.join(get_package_share_directory('turtlebot3_gazebo'),
-                                   'worlds/turtlebot3_worlds/waffle.model'),
-        description='Full path to world file to load')
-
-    stdout_linebuf_envvar = launch.actions.SetEnvironmentVariable(
-        'RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED', '1')
-
-    # Specify the actions
-    start_gazebo_cmd = launch.actions.ExecuteProcess(
-        condition=IfCondition(use_simulation),
-        cmd=[simulator, '-s', 'libgazebo_ros_init.so', world],
-        cwd=[launch_dir], output='screen')
-
-    start_robot_state_publisher_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('robot_state_publisher'),
-                'lib/robot_state_publisher/robot_state_publisher'),
-            os.path.join(
-                get_package_share_directory('turtlebot3_description'),
-                'urdf', 'turtlebot3_waffle.urdf'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_rviz_cmd = launch.actions.ExecuteProcess(
-        cmd=[os.path.join(get_package_prefix('rviz2'), 'lib/rviz2/rviz2'),
-            ['-d', rviz_config_file]],
-        cwd=[launch_dir], output='screen')
-
-    exit_event_handler = launch.actions.RegisterEventHandler(
-        event_handler=launch.event_handlers.OnProcessExit(
-            target_action=start_rviz_cmd,
-            on_exit=launch.actions.EmitEvent(event=launch.events.Shutdown(reason='rviz exited'))))
-
-    start_map_server_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('nav2_map_server'),
-                'lib/nav2_map_server/map_server'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_localizer_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('nav2_amcl'),
-                'lib/nav2_amcl/amcl'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_planner_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('nav2_planner'),
-                'lib/nav2_planner/planner_server'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_dwb_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('dwb_controller'),
-                'lib/dwb_controller/dwb_controller'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_navigator_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('nav2_bt_navigator'),
-                'lib/nav2_bt_navigator/bt_navigator'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_recovery_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('nav2_recoveries'),
-                'lib/nav2_recoveries/recoveries_node'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    start_lifecycle_manager_cmd = launch.actions.ExecuteProcess(
-        cmd=[
-            os.path.join(
-                get_package_prefix('nav2_lifecycle_manager'),
-                'lib/nav2_lifecycle_manager/lifecycle_manager'),
-            '--ros-args', '--params-file', configured_params],
-        cwd=[launch_dir], output='screen')
-
-    # Create the launch description and populate
-    ld = launch.LaunchDescription()
-
-    # Declare the launch options
-    ld.add_action(declare_autostart_cmd)
-    ld.add_action(declare_bt_xml_cmd)
-    ld.add_action(declare_map_yaml_cmd)
-    ld.add_action(declare_params_file_cmd)
-    ld.add_action(declare_rviz_config_file_cmd)
-    ld.add_action(declare_simulator_cmd)
-    ld.add_action(declare_use_sim_time_cmd)
-    ld.add_action(declare_use_simulation_cmd)
-    ld.add_action(declare_world_cmd)
-
-    # Set environment variables
-    ld.add_action(stdout_linebuf_envvar)
-
-    # Add any actions to launch in simulation (conditioned on 'use_simulation')
-    ld.add_action(start_gazebo_cmd)
-
-    # Add other nodes and processes we need
-    ld.add_action(start_robot_state_publisher_cmd)
-    ld.add_action(start_rviz_cmd)
-    ld.add_action(exit_event_handler)
-
-    # Add the actions to launch all of the navigation nodes
-    ld.add_action(start_lifecycle_manager_cmd)
-    ld.add_action(start_map_server_cmd)
-    ld.add_action(start_localizer_cmd)
-    ld.add_action(start_dwb_cmd)
-    ld.add_action(start_planner_cmd)
-    ld.add_action(start_navigator_cmd)
-    ld.add_action(start_recovery_cmd)
-
-    return ld
diff --git a/nav2_bringup/launch/nav2_tb3_simulation_launch.py b/nav2_bringup/launch/nav2_tb3_simulation_launch.py
new file mode 100644
index 0000000000000000000000000000000000000000..013a9ae4431617f84ed36da17483cb65084683ac
--- /dev/null
+++ b/nav2_bringup/launch/nav2_tb3_simulation_launch.py
@@ -0,0 +1,171 @@
+# Copyright (c) 2018 Intel Corporation
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+#     http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+
+""" This is all-in-one launch script intended for use by nav2 developers. """
+
+import os
+
+from ament_index_python.packages import get_package_prefix, get_package_share_directory
+
+from launch import LaunchDescription
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.conditions import IfCondition
+from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir
+from launch.actions import (DeclareLaunchArgument, SetEnvironmentVariable,
+    IncludeLaunchDescription, ExecuteProcess, RegisterEventHandler, EmitEvent)
+from launch.event_handlers import OnProcessExit
+from launch.events import Shutdown
+from launch_ros.actions import Node
+
+
+def generate_launch_description():
+    # Get the launch directory
+    bringup_dir = get_package_share_directory('nav2_bringup')
+    launch_dir = os.path.join(bringup_dir, 'launch')
+
+    # Create the launch configuration variables
+    map_yaml_file = LaunchConfiguration('map')
+    use_sim_time = LaunchConfiguration('use_sim_time')
+    params_file = LaunchConfiguration('params_file')
+    bt_xml_file = LaunchConfiguration('bt_xml_file')
+    autostart = LaunchConfiguration('autostart')
+
+    # Launch configuration variables specific to simulation
+    rviz_config_file = LaunchConfiguration('rviz_config_file')
+    use_simulator = LaunchConfiguration('use_simulator')
+    simulator = LaunchConfiguration('simulator')
+    world = LaunchConfiguration('world')
+
+    # Declare the launch arguments
+    declare_map_yaml_cmd = DeclareLaunchArgument(
+        'map',
+        default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),
+        description='Full path to map file to load')
+
+    declare_use_sim_time_cmd = DeclareLaunchArgument(
+        'use_sim_time',
+        default_value='true',
+        description='Use simulation (Gazebo) clock if true')
+
+    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_bt_xml_cmd = DeclareLaunchArgument(
+        'bt_xml_file',
+        default_value=os.path.join(
+            get_package_prefix('nav2_bt_navigator'),
+            'behavior_trees', 'navigate_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 nav2 stack')
+
+    declare_rviz_config_file_cmd = DeclareLaunchArgument(
+        'rviz_config_file',
+        default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
+        description='Full path to the RVIZ config file to use')
+
+    declare_use_simulator_cmd = DeclareLaunchArgument(
+        'use_simulator',
+        default_value='True',
+        description='Whether to start the simulator')
+
+    declare_simulator_cmd = DeclareLaunchArgument(
+        'simulator',
+        default_value='gazebo',
+        description='The simulator to use (gazebo or gzserver)')
+
+    declare_world_cmd = DeclareLaunchArgument(
+        'world',
+        # TODO(orduno) Switch back once ROS argument passing has been fixed upstream
+        #              https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/91
+        # default_value=os.path.join(get_package_share_directory('turtlebot3_gazebo'),
+        #                            'worlds/turtlebot3_worlds/waffle.model'),
+        default_value=os.path.join(bringup_dir, 'worlds', 'waffle.model'),
+        description='Full path to world model file to load')
+
+    # Specify the actions
+    start_gazebo_cmd = ExecuteProcess(
+        condition=IfCondition(use_simulator),
+        cmd=[simulator, '-s', 'libgazebo_ros_init.so', world],
+        cwd=[launch_dir], output='screen')
+
+    urdf = os.path.join(
+        get_package_share_directory('turtlebot3_description'), 'urdf', 'turtlebot3_waffle.urdf')
+
+    start_robot_state_publisher_cmd = Node(
+        package='robot_state_publisher',
+        node_executable='robot_state_publisher',
+        node_name='robot_state_publisher',
+        output='screen',
+        parameters=[{'use_sim_time': use_sim_time}],
+        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.
+    # start_rviz_cmd = Node(
+    #     package='rviz2',
+    #     node_executable='rviz2',
+    #     node_name='rviz2',
+    #     arguments=['-d', rviz_config_file],
+    #     output='screen')
+
+    start_rviz_cmd = ExecuteProcess(
+        cmd=[os.path.join(get_package_prefix('rviz2'), 'lib/rviz2/rviz2'),
+            ['-d', rviz_config_file]],
+        cwd=[launch_dir], output='screen')
+
+    exit_event_handler = RegisterEventHandler(
+        event_handler=OnProcessExit(
+            target_action=start_rviz_cmd,
+            on_exit=EmitEvent(event=Shutdown(reason='rviz exited'))))
+
+    bringup_cmd = IncludeLaunchDescription(
+        PythonLaunchDescriptionSource(os.path.join(launch_dir, 'nav2_bringup_launch.py')),
+        launch_arguments={'map': map_yaml_file,
+                          'use_sim_time': use_sim_time,
+                          'params_file': params_file,
+                          'bt_xml_file': bt_xml_file,
+                          'autostart': autostart}.items())
+
+    # Create the launch description and populate
+    ld = LaunchDescription()
+
+    # Declare the launch options
+    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(declare_bt_xml_cmd)
+    ld.add_action(declare_autostart_cmd)
+
+    ld.add_action(declare_rviz_config_file_cmd)
+    ld.add_action(declare_use_simulator_cmd)
+    ld.add_action(declare_simulator_cmd)
+    ld.add_action(declare_world_cmd)
+
+    # Add any actions to launch in simulation (conditioned on 'use_simulator')
+    ld.add_action(start_gazebo_cmd)
+
+    # Add other nodes and processes we need
+    ld.add_action(start_rviz_cmd)
+    ld.add_action(exit_event_handler)
+
+    # Add the actions to launch all of the navigation nodes
+    ld.add_action(start_robot_state_publisher_cmd)
+    ld.add_action(bringup_cmd)
+
+    return ld
diff --git a/nav2_bringup/launch/turtlebot3_world.pgm b/nav2_bringup/maps/turtlebot3_world.pgm
similarity index 100%
rename from nav2_bringup/launch/turtlebot3_world.pgm
rename to nav2_bringup/maps/turtlebot3_world.pgm
diff --git a/nav2_bringup/launch/turtlebot3_world.yaml b/nav2_bringup/maps/turtlebot3_world.yaml
similarity index 100%
rename from nav2_bringup/launch/turtlebot3_world.yaml
rename to nav2_bringup/maps/turtlebot3_world.yaml
diff --git a/nav2_bringup/package.xml b/nav2_bringup/package.xml
index a72e1233fec3c190b477ef41d4c7147e5896ff50..f09f5fab3c52b1769356254959e083d40c351723 100644
--- a/nav2_bringup/package.xml
+++ b/nav2_bringup/package.xml
@@ -6,6 +6,7 @@
   <description>Bringup scripts and configurations for the navigation2 stack</description>
   <maintainer email="michael.jeronimo@intel.com">Michael Jeronimo</maintainer>
   <maintainer email="stevenmacenski@gmail.com">Steve Macenski</maintainer>
+  <maintainer email="carlos.a.orduno@intel.com">Carlos Orduno</maintainer>
   <license>Apache-2.0</license>
 
   <buildtool_depend>ament_cmake</buildtool_depend>
diff --git a/nav2_bringup/launch/nav2_params.yaml b/nav2_bringup/params/nav2_params.yaml
similarity index 91%
rename from nav2_bringup/launch/nav2_params.yaml
rename to nav2_bringup/params/nav2_params.yaml
index bd19d8632ff2d3f373ab2abfc3ac8f4577519ce5..0be0e53b4d62c12d099939d87d63a6d032d19389 100644
--- a/nav2_bringup/launch/nav2_params.yaml
+++ b/nav2_bringup/params/nav2_params.yaml
@@ -148,21 +148,6 @@ map_server:
     use_sim_time: True
     yaml_filename: "turtlebot3_world.yaml"
 
-lifecycle_manager:
-  ros__parameters:
-    use_sim_time: True
-    autostart: True
-    node_names: ['map_server', 'amcl', 'dwb_controller',
-                 'planner_server', 'bt_navigator']
-
-lifecycle_manager_service_client:
-  ros__parameters:
-    use_sim_time: True
-
-lifecycle_manager_client_service_client:
-  ros__parameters:
-    use_sim_time: True
-
 navfn_planner:
   ros__parameters:
     use_sim_time: True
diff --git a/nav2_bringup/launch/nav2_default_view.rviz b/nav2_bringup/rviz/nav2_default_view.rviz
similarity index 100%
rename from nav2_bringup/launch/nav2_default_view.rviz
rename to nav2_bringup/rviz/nav2_default_view.rviz
diff --git a/nav2_bringup/worlds/waffle.model b/nav2_bringup/worlds/waffle.model
new file mode 100644
index 0000000000000000000000000000000000000000..d065ae1cd88faf5fc2ff93aac00aa8eaee16958a
--- /dev/null
+++ b/nav2_bringup/worlds/waffle.model
@@ -0,0 +1,577 @@
+<?xml version="1.0"?>
+<sdf version="1.6">
+  <world name="default">
+
+    <include>
+      <uri>model://ground_plane</uri>
+    </include>
+
+    <include>
+      <uri>model://sun</uri>
+    </include>
+
+    <scene>
+      <shadows>false</shadows>
+    </scene>
+
+    <gui fullscreen='0'>
+      <camera name='user_camera'>
+        <pose frame=''>0.319654 -0.235002 9.29441 0 1.5138 0.009599</pose>
+        <view_controller>orbit</view_controller>
+        <projection_type>perspective</projection_type>
+      </camera>
+    </gui>
+
+    <physics type="ode">
+      <real_time_update_rate>1000.0</real_time_update_rate>
+      <max_step_size>0.001</max_step_size>
+      <real_time_factor>1</real_time_factor>
+      <ode>
+        <solver>
+          <type>quick</type>
+          <iters>150</iters>
+          <precon_iters>0</precon_iters>
+          <sor>1.400000</sor>
+          <use_dynamic_moi_rescaling>1</use_dynamic_moi_rescaling>
+        </solver>
+        <constraints>
+          <cfm>0.00001</cfm>
+          <erp>0.2</erp>
+          <contact_max_correcting_vel>2000.000000</contact_max_correcting_vel>
+          <contact_surface_layer>0.01000</contact_surface_layer>
+        </constraints>
+      </ode>
+    </physics>
+
+    <model name="turtlebot3_world">
+      <static>1</static>
+      <include>
+        <uri>model://turtlebot3_world</uri>
+      </include>
+    </model>
+
+    <model name="turtlebot3_waffle"> 
+      <pose>-2.0 -0.5 0.01 0.0 0.0 0.0</pose>
+
+      <link name="base_footprint"/>
+
+      <link name="base_link">
+
+        <inertial>
+          <pose>-0.064 0 0.048 0 0 0</pose>
+          <inertia>
+            <ixx>0.001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.001</izz>
+          </inertia>
+          <mass>1.0</mass>
+        </inertial>
+
+        <collision name="base_collision">
+          <pose>-0.064 0 0.048 0 0 0</pose>
+          <geometry>
+            <box>
+              <size>0.265 0.265 0.089</size>
+            </box>
+          </geometry>
+        </collision>
+
+        <visual name="base_visual">
+          <pose>-0.064 0 0 0 0 0</pose>
+          <geometry>
+            <mesh>
+              <uri>model://turtlebot3_waffle/meshes/waffle_base.dae</uri>
+              <scale>0.001 0.001 0.001</scale>
+            </mesh>
+          </geometry>
+        </visual>
+      </link>
+
+      <link name="imu_link">
+        <sensor name="tb3_imu" type="imu">
+          <always_on>true</always_on>
+          <update_rate>200</update_rate>
+          <imu>
+            <angular_velocity>
+              <x>
+                <noise type="gaussian">
+                  <mean>0.0</mean>
+                  <stddev>2e-4</stddev>
+                </noise>
+              </x>
+              <y>
+                <noise type="gaussian">
+                  <mean>0.0</mean>
+                  <stddev>2e-4</stddev>
+                </noise>
+              </y>
+              <z>
+                <noise type="gaussian">
+                  <mean>0.0</mean>
+                  <stddev>2e-4</stddev>
+                </noise>
+              </z>
+            </angular_velocity>
+            <linear_acceleration>
+              <x>
+                <noise type="gaussian">
+                  <mean>0.0</mean>
+                  <stddev>1.7e-2</stddev>
+                </noise>
+              </x>
+              <y>
+                <noise type="gaussian">
+                  <mean>0.0</mean>
+                  <stddev>1.7e-2</stddev>
+                </noise>
+              </y>
+              <z>
+                <noise type="gaussian">
+                  <mean>0.0</mean>
+                  <stddev>1.7e-2</stddev>
+                </noise>
+              </z>
+            </linear_acceleration>
+          </imu>
+          <plugin name="turtlebot3_imu" filename="libgazebo_ros_imu_sensor.so">
+            <ros>
+              <!-- <namespace>/tb3</namespace> -->
+              <argument>--ros-args</argument>
+              <argument>-r</argument>
+              <argument>~/out:=imu</argument>
+            </ros>
+          </plugin>
+        </sensor>
+      </link>
+
+      <link name="base_scan">
+        <inertial>
+          <pose>-0.052 0 0.111 0 0 0</pose>
+          <inertia>
+            <ixx>0.001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.001</izz>
+          </inertia>
+          <mass>0.125</mass>
+        </inertial>
+
+        <collision name="lidar_sensor_collision">
+          <pose>-0.052 0 0.111 0 0 0</pose>
+          <geometry>
+            <cylinder>
+              <radius>0.0508</radius>
+              <length>0.055</length>
+            </cylinder>
+          </geometry>
+        </collision>
+
+        <visual name="lidar_sensor_visual">
+          <pose>-0.064 0 0.121 0 0 0</pose>
+          <geometry>
+            <mesh>
+              <uri>model://turtlebot3_waffle/meshes/lds.dae</uri>
+              <scale>0.001 0.001 0.001</scale>
+            </mesh>
+          </geometry>
+        </visual>
+
+        <sensor name="hls_lfcd_lds" type="ray">
+          <always_on>true</always_on>
+          <visualize>true</visualize>
+          <pose>-0.064 0 0.121 0 0 0</pose>
+          <update_rate>5</update_rate>
+          <ray>
+            <scan>
+              <horizontal>
+                <samples>360</samples>
+                <resolution>1.000000</resolution>
+                <min_angle>0.000000</min_angle>
+                <max_angle>6.280000</max_angle>
+              </horizontal>
+            </scan>
+            <range>
+              <min>0.120000</min>
+              <max>3.5</max>
+              <resolution>0.015000</resolution>
+            </range>
+            <noise>
+              <type>gaussian</type>
+              <mean>0.0</mean>
+              <stddev>0.01</stddev>
+            </noise>
+          </ray>
+          <plugin name="turtlebot3_laserscan" filename="libgazebo_ros_ray_sensor.so">
+            <ros>
+                <!-- <namespace>/tb3</namespace> -->
+                <argument>--ros-args</argument>
+                <argument>-r </argument>
+                <argument>~/out:=scan</argument>
+            </ros>
+            <output_type>sensor_msgs/LaserScan</output_type>
+            <frame_name>base_scan</frame_name>
+          </plugin>
+        </sensor>
+      </link>
+
+      <link name="wheel_left_link">
+
+        <inertial>
+          <pose>0.0 0.144 0.023 -1.57 0 0</pose>
+          <inertia>
+            <ixx>0.001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.001</izz>
+          </inertia>
+          <mass>0.1</mass>
+        </inertial>
+
+        <collision name="wheel_left_collision">
+          <pose>0.0 0.144 0.023 -1.57 0 0</pose>
+          <geometry>
+            <cylinder>
+              <radius>0.033</radius>
+              <length>0.018</length>
+            </cylinder>
+          </geometry>
+          <surface>
+            <!-- This friction pamareter don't contain reliable data!! -->
+            <friction>
+              <ode>
+                <mu>100000.0</mu>
+                <mu2>100000.0</mu2>
+                <fdir1>0 0 0</fdir1>
+                <slip1>0.0</slip1>
+                <slip2>0.0</slip2>
+              </ode>
+            </friction>
+            <contact>
+              <ode>
+                <soft_cfm>0</soft_cfm>
+                <soft_erp>0.2</soft_erp>
+                <kp>1e+5</kp>
+                <kd>1</kd>
+                <max_vel>0.01</max_vel>
+                <min_depth>0.001</min_depth>
+              </ode>
+            </contact>
+          </surface>
+        </collision>
+
+        <visual name="wheel_left_visual">
+          <pose>0.0 0.144 0.023 0 0 0</pose>
+          <geometry>
+            <mesh>
+              <uri>model://turtlebot3_waffle/meshes/left_tire.dae</uri>
+              <scale>0.001 0.001 0.001</scale>
+            </mesh>
+          </geometry>
+        </visual>
+      </link>
+
+      <link name="wheel_right_link">
+
+        <inertial>
+          <pose>0.0 -0.144 0.023 -1.57 0 0</pose>
+          <inertia>
+            <ixx>0.001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.001</izz>
+          </inertia>
+          <mass>0.1</mass>
+        </inertial>
+      
+        <collision name="wheel_right_collision">
+          <pose>0.0 -0.144 0.023 -1.57 0 0</pose>
+          <geometry>
+            <cylinder>
+              <radius>0.033</radius>
+              <length>0.018</length>
+            </cylinder>
+          </geometry>
+          <surface>
+            <!-- This friction pamareter don't contain reliable data!! -->
+            <friction>
+              <ode>
+                <mu>100000.0</mu>
+                <mu2>100000.0</mu2>
+                <fdir1>0 0 0</fdir1>
+                <slip1>0.0</slip1>
+                <slip2>0.0</slip2>
+              </ode>
+            </friction>
+            <contact>
+              <ode>
+                <soft_cfm>0</soft_cfm>
+                <soft_erp>0.2</soft_erp>
+                <kp>1e+5</kp>
+                <kd>1</kd>
+                <max_vel>0.01</max_vel>
+                <min_depth>0.001</min_depth>
+              </ode>
+            </contact>
+          </surface>
+        </collision>
+
+        <visual name="wheel_right_visual">
+          <pose>0.0 -0.144 0.023 0 0 0</pose>
+          <geometry>
+            <mesh>
+              <uri>model://turtlebot3_waffle/meshes/right_tire.dae</uri>
+              <scale>0.001 0.001 0.001</scale>
+            </mesh>
+          </geometry>
+        </visual>
+      </link>
+
+      <link name='caster_back_right_link'>
+        <pose>-0.177 -0.064 -0.004 0 0 0</pose>
+        <inertial>
+          <mass>0.001</mass>
+          <inertia>
+            <ixx>0.00001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.00001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.00001</izz>
+          </inertia>
+        </inertial>
+        <collision name='collision'>
+          <geometry>
+            <sphere>
+              <radius>0.005000</radius>
+            </sphere>
+          </geometry>
+          <surface>
+            <contact>
+              <ode>
+                <soft_cfm>0</soft_cfm>
+                <soft_erp>0.2</soft_erp>
+                <kp>1e+5</kp>
+                <kd>1</kd>
+                <max_vel>0.01</max_vel>
+                <min_depth>0.001</min_depth>
+              </ode>
+            </contact>
+          </surface>
+        </collision>
+      </link>
+
+      <link name='caster_back_left_link'>
+        <pose>-0.177 0.064 -0.004 0 0 0</pose>
+        <inertial>
+          <mass>0.001</mass>
+          <inertia>
+            <ixx>0.00001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.00001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.00001</izz>
+          </inertia>
+        </inertial>
+        <collision name='collision'>
+          <geometry>
+            <sphere>
+              <radius>0.005000</radius>
+            </sphere>
+          </geometry>
+          <surface>
+            <contact>
+              <ode>
+                <soft_cfm>0</soft_cfm>
+                <soft_erp>0.2</soft_erp>
+                <kp>1e+5</kp>
+                <kd>1</kd>
+                <max_vel>0.01</max_vel>
+                <min_depth>0.001</min_depth>
+              </ode>
+            </contact>
+          </surface>
+        </collision>
+      </link>
+
+      <link name="camera_link"/>
+
+      <link name="camera_rgb_frame">
+        <inertial>
+          <pose>0.069 -0.047 0.107 0 0 0</pose>
+          <inertia>
+            <ixx>0.001</ixx>
+            <ixy>0.000</ixy>
+            <ixz>0.000</ixz>
+            <iyy>0.001</iyy>
+            <iyz>0.000</iyz>
+            <izz>0.001</izz>
+          </inertia>
+          <mass>0.035</mass>
+        </inertial>
+
+        <collision name="collision">
+          <pose>0 0.047 0 0 0 0</pose>
+          <geometry>
+            <box>
+              <size>0.008 0.130 0.022</size>
+            </box>
+          </geometry>
+        </collision>
+        <pose>0.069 -0.047 0.107 0 0 0</pose>
+        <sensor name="camera" type="camera">
+          <always_on>true</always_on>
+          <visualize>true</visualize>
+          <update_rate>30</update_rate>
+          <camera name="intel_realsense_r200">
+            <horizontal_fov>1.02974</horizontal_fov>
+            <image>
+              <width>1920</width>
+              <height>1080</height>
+              <format>R8G8B8</format>
+            </image>
+            <clip>
+              <near>0.02</near>
+              <far>300</far>
+            </clip>
+            <noise>
+              <type>gaussian</type>
+              <!-- Noise is sampled independently per pixel on each frame.
+                    That pixel's noise value is added to each of its color
+                    channels, which at that point lie in the range [0,1]. -->
+              <mean>0.0</mean>
+              <stddev>0.007</stddev>
+            </noise>
+          </camera>
+            <plugin name="camera_driver" filename="libgazebo_ros_camera.so">
+              <ros>
+                <!-- <namespace>test_cam</namespace> -->
+                <!-- <argument>image_raw:=image_demo</argument> -->
+                <!-- <argument>camera_info:=camera_info_demo</argument> -->
+              </ros>
+              <!-- camera_name>omit so it defaults to sensor name</camera_name-->
+              <!-- frame_name>omit so it defaults to link name</frameName-->
+              <!-- <hack_baseline>0.07</hack_baseline> -->
+            </plugin>
+        </sensor>
+      </link>
+
+      <joint name="base_joint" type="fixed">
+        <parent>base_footprint</parent>
+        <child>base_link</child>
+        <pose>0.0 0.0 0.010 0 0 0</pose>
+      </joint>
+
+      <joint name="wheel_left_joint" type="revolute">
+        <parent>base_link</parent>
+        <child>wheel_left_link</child>
+        <pose>0.0 0.144 0.023 -1.57 0 0</pose>
+        <axis>
+          <xyz>0 0 1</xyz>
+        </axis>
+      </joint>
+
+      <joint name="wheel_right_joint" type="revolute">
+        <parent>base_link</parent>
+        <child>wheel_right_link</child>
+        <pose>0.0 -0.144 0.023 -1.57 0 0</pose>
+        <axis>
+          <xyz>0 0 1</xyz>
+        </axis>
+      </joint>
+
+      <joint name='caster_back_right_joint' type='ball'>
+        <parent>base_link</parent>
+        <child>caster_back_right_link</child>
+      </joint>
+
+      <joint name='caster_back_left_joint' type='ball'>
+        <parent>base_link</parent>
+        <child>caster_back_left_link</child>
+      </joint>
+
+      <joint name="lidar_joint" type="fixed">
+        <parent>base_link</parent>
+        <child>base_scan</child>
+        <pose>-0.064 0 0.121 0 0 0</pose>
+        <axis>
+          <xyz>0 0 1</xyz>
+        </axis>
+      </joint>
+
+      <joint name="camera_joint" type="fixed">
+        <parent>base_link</parent>
+        <child>camera_link</child>
+        <pose>0.064 -0.065 0.094 0 0 0</pose>
+        <axis>
+          <xyz>0 0 1</xyz>
+        </axis>
+      </joint>
+
+      <joint name="camera_rgb_joint" type="fixed">
+        <parent>camera_link</parent>
+        <child>camera_rgb_frame</child>
+        <pose>0.005 0.018 0.013 0 0 0</pose>
+        <axis>
+          <xyz>0 0 1</xyz>
+        </axis>
+      </joint>
+
+      <plugin name="turtlebot3_diff_drive" filename="libgazebo_ros_diff_drive.so">
+
+        <ros>
+          <!-- <namespace>/tb3</namespace> -->
+        </ros>
+
+        <update_rate>30</update_rate>
+
+        <!-- wheels -->
+        <left_joint>wheel_left_joint</left_joint>
+        <right_joint>wheel_right_joint</right_joint>
+
+        <!-- kinematics -->
+        <wheel_separation>0.287</wheel_separation>
+        <wheel_diameter>0.066</wheel_diameter>
+
+        <!-- limits -->
+        <max_wheel_torque>20</max_wheel_torque>
+        <max_wheel_acceleration>1.0</max_wheel_acceleration>
+
+        <command_topic>cmd_vel</command_topic>
+
+        <!-- output -->
+        <publish_odom>true</publish_odom>
+        <publish_odom_tf>true</publish_odom_tf>
+        <publish_wheel_tf>false</publish_wheel_tf>
+
+        <odometry_topic>odom</odometry_topic>
+        <odometry_frame>odom</odometry_frame>
+        <robot_base_frame>base_footprint</robot_base_frame>
+
+      </plugin>
+
+      <plugin name="turtlebot3_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
+        <ros>
+          <!-- <namespace>/tb3</namespace> -->
+            <argument>--ros-args</argument>
+            <argument>-r </argument>
+            <argument>~/out:=joint_states</argument>
+        </ros>
+        <update_rate>30</update_rate>
+        <joint_name>wheel_left_joint</joint_name>
+        <joint_name>wheel_right_joint</joint_name>
+      </plugin>
+
+    </model>
+
+  </world>
+</sdf>