15 """This is all-in-one launch script intended for use by nav2 developers."""
20 from ament_index_python.packages
import get_package_share_directory
22 from launch
import LaunchDescription
23 from launch.actions
import (
24 AppendEnvironmentVariable,
25 DeclareLaunchArgument,
27 IncludeLaunchDescription,
31 from launch.conditions
import IfCondition
32 from launch.event_handlers
import OnShutdown
33 from launch.launch_description_sources
import PythonLaunchDescriptionSource
34 from launch.substitutions
import Command, LaunchConfiguration, PythonExpression
36 from launch_ros.actions
import Node
39 def generate_launch_description():
41 bringup_dir = get_package_share_directory(
'nav2_bringup')
42 launch_dir = os.path.join(bringup_dir,
'launch')
45 sim_dir = get_package_share_directory(
'nav2_minimal_tb4_sim')
46 desc_dir = get_package_share_directory(
'nav2_minimal_tb4_description')
49 slam = LaunchConfiguration(
'slam')
50 namespace = LaunchConfiguration(
'namespace')
51 use_namespace = LaunchConfiguration(
'use_namespace')
52 map_yaml_file = LaunchConfiguration(
'map')
53 use_sim_time = LaunchConfiguration(
'use_sim_time')
54 params_file = LaunchConfiguration(
'params_file')
55 autostart = LaunchConfiguration(
'autostart')
56 use_composition = LaunchConfiguration(
'use_composition')
57 use_respawn = LaunchConfiguration(
'use_respawn')
60 rviz_config_file = LaunchConfiguration(
'rviz_config_file')
61 use_simulator = LaunchConfiguration(
'use_simulator')
62 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
63 use_rviz = LaunchConfiguration(
'use_rviz')
64 headless = LaunchConfiguration(
'headless')
65 world = LaunchConfiguration(
'world')
67 'x': LaunchConfiguration(
'x_pose', default=
'-8.00'),
68 'y': LaunchConfiguration(
'y_pose', default=
'0.00'),
69 'z': LaunchConfiguration(
'z_pose', default=
'0.01'),
70 'R': LaunchConfiguration(
'roll', default=
'0.00'),
71 'P': LaunchConfiguration(
'pitch', default=
'0.00'),
72 'Y': LaunchConfiguration(
'yaw', default=
'0.00'),
74 robot_name = LaunchConfiguration(
'robot_name')
75 robot_sdf = LaunchConfiguration(
'robot_sdf')
77 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
80 declare_namespace_cmd = DeclareLaunchArgument(
81 'namespace', default_value=
'', description=
'Top-level namespace'
84 declare_use_namespace_cmd = DeclareLaunchArgument(
86 default_value=
'false',
87 description=
'Whether to apply a namespace to the navigation stack',
90 declare_slam_cmd = DeclareLaunchArgument(
91 'slam', default_value=
'False', description=
'Whether run a SLAM'
94 declare_map_yaml_cmd = DeclareLaunchArgument(
96 default_value=os.path.join(bringup_dir,
'maps',
'depot.yaml'),
97 description=
'Full path to map file to load',
100 declare_use_sim_time_cmd = DeclareLaunchArgument(
102 default_value=
'true',
103 description=
'Use simulation (Gazebo) clock if true',
106 declare_params_file_cmd = DeclareLaunchArgument(
108 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
109 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
112 declare_autostart_cmd = DeclareLaunchArgument(
114 default_value=
'true',
115 description=
'Automatically startup the nav2 stack',
118 declare_use_composition_cmd = DeclareLaunchArgument(
120 default_value=
'True',
121 description=
'Whether to use composed bringup',
124 declare_use_respawn_cmd = DeclareLaunchArgument(
126 default_value=
'False',
127 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
130 declare_rviz_config_file_cmd = DeclareLaunchArgument(
132 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
133 description=
'Full path to the RVIZ config file to use',
136 declare_use_simulator_cmd = DeclareLaunchArgument(
138 default_value=
'True',
139 description=
'Whether to start the simulator',
142 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
143 'use_robot_state_pub',
144 default_value=
'True',
145 description=
'Whether to start the robot state publisher',
148 declare_use_rviz_cmd = DeclareLaunchArgument(
149 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
152 declare_simulator_cmd = DeclareLaunchArgument(
153 'headless', default_value=
'True', description=
'Whether to execute gzclient)'
156 declare_world_cmd = DeclareLaunchArgument(
158 default_value=os.path.join(sim_dir,
'worlds',
'depot.sdf'),
159 description=
'Full path to world model file to load',
162 declare_robot_name_cmd = DeclareLaunchArgument(
163 'robot_name', default_value=
'nav2_turtlebot4', description=
'name of the robot'
166 declare_robot_sdf_cmd = DeclareLaunchArgument(
168 default_value=os.path.join(desc_dir,
'urdf',
'standard',
'turtlebot4.urdf.xacro'),
169 description=
'Full path to robot sdf file to spawn the robot in gazebo',
172 start_robot_state_publisher_cmd = Node(
173 condition=IfCondition(use_robot_state_pub),
174 package=
'robot_state_publisher',
175 executable=
'robot_state_publisher',
176 name=
'robot_state_publisher',
180 {
'use_sim_time': use_sim_time,
'robot_description': Command([
'xacro',
' ', robot_sdf])}
182 remappings=remappings,
185 rviz_cmd = IncludeLaunchDescription(
186 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'rviz_launch.py')),
187 condition=IfCondition(use_rviz),
189 'namespace': namespace,
190 'use_namespace': use_namespace,
191 'use_sim_time': use_sim_time,
192 'rviz_config': rviz_config_file,
196 bringup_cmd = IncludeLaunchDescription(
197 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'bringup_launch.py')),
199 'namespace': namespace,
200 'use_namespace': use_namespace,
202 'map': map_yaml_file,
203 'use_sim_time': use_sim_time,
204 'params_file': params_file,
205 'autostart': autostart,
206 'use_composition': use_composition,
207 'use_respawn': use_respawn,
216 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
217 world_sdf_xacro = ExecuteProcess(
218 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=', headless], world])
219 gazebo_server = ExecuteProcess(
220 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
222 condition=IfCondition(use_simulator)
225 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
227 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
230 set_env_vars_resources = AppendEnvironmentVariable(
231 'GZ_SIM_RESOURCE_PATH',
232 os.path.join(sim_dir,
'worlds'))
233 gazebo_client = IncludeLaunchDescription(
234 PythonLaunchDescriptionSource(
235 os.path.join(get_package_share_directory(
'ros_gz_sim'),
239 condition=IfCondition(PythonExpression(
240 [use_simulator,
' and not ', headless])),
241 launch_arguments={
'gz_args': [
'-v4 -g ']}.items(),
244 gz_robot = IncludeLaunchDescription(
245 PythonLaunchDescriptionSource(
246 os.path.join(sim_dir,
'launch',
'spawn_tb4.launch.py')),
247 launch_arguments={
'namespace': namespace,
248 'use_simulator': use_simulator,
249 'use_sim_time': use_sim_time,
250 'robot_name': robot_name,
251 'robot_sdf': robot_sdf,
257 'yaw': pose[
'Y']}.items())
260 ld = LaunchDescription()
263 ld.add_action(declare_namespace_cmd)
264 ld.add_action(declare_use_namespace_cmd)
265 ld.add_action(declare_slam_cmd)
266 ld.add_action(declare_map_yaml_cmd)
267 ld.add_action(declare_use_sim_time_cmd)
268 ld.add_action(declare_params_file_cmd)
269 ld.add_action(declare_autostart_cmd)
270 ld.add_action(declare_use_composition_cmd)
272 ld.add_action(declare_rviz_config_file_cmd)
273 ld.add_action(declare_use_simulator_cmd)
274 ld.add_action(declare_use_robot_state_pub_cmd)
275 ld.add_action(declare_use_rviz_cmd)
276 ld.add_action(declare_simulator_cmd)
277 ld.add_action(declare_world_cmd)
278 ld.add_action(declare_robot_name_cmd)
279 ld.add_action(declare_robot_sdf_cmd)
280 ld.add_action(declare_use_respawn_cmd)
282 ld.add_action(set_env_vars_resources)
283 ld.add_action(world_sdf_xacro)
284 ld.add_action(remove_temp_sdf_file)
285 ld.add_action(gz_robot)
286 ld.add_action(gazebo_server)
287 ld.add_action(gazebo_client)
290 ld.add_action(start_robot_state_publisher_cmd)
291 ld.add_action(rviz_cmd)
292 ld.add_action(bringup_cmd)