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
21 from launch
import LaunchDescription
22 from launch.actions
import (AppendEnvironmentVariable, DeclareLaunchArgument, ExecuteProcess,
23 IncludeLaunchDescription, OpaqueFunction, RegisterEventHandler)
24 from launch.conditions
import IfCondition
25 from launch.event_handlers
import OnShutdown
26 from launch.launch_description_sources
import PythonLaunchDescriptionSource
27 from launch.substitutions
import Command, LaunchConfiguration, PythonExpression
28 from launch_ros.actions
import Node
34 'x': -8.00,
'y': 0.00,
'z': 0.01,
35 'R': 0.00,
'P': 0.00,
'Y': 0.00
38 'x': 2.00,
'y': -19.65,
'z': 0.01,
39 'R': 0.00,
'P': 0.00,
'Y': 1.57
45 def generate_launch_description() -> LaunchDescription:
47 bringup_dir = get_package_share_directory(
'nav2_bringup')
48 launch_dir = os.path.join(bringup_dir,
'launch')
51 sim_dir = get_package_share_directory(
'nav2_minimal_tb4_sim')
52 desc_dir = get_package_share_directory(
'nav2_minimal_tb4_description')
55 slam = LaunchConfigAsBool(
'slam')
56 namespace = LaunchConfiguration(
'namespace')
57 map_yaml_file = LaunchConfiguration(
'map')
58 keepout_mask_yaml_file = LaunchConfiguration(
'keepout_mask')
59 speed_mask_yaml_file = LaunchConfiguration(
'speed_mask')
60 graph_filepath = LaunchConfiguration(
'graph')
61 use_sim_time = LaunchConfigAsBool(
'use_sim_time')
62 params_file = LaunchConfiguration(
'params_file')
63 autostart = LaunchConfigAsBool(
'autostart')
64 use_composition = LaunchConfigAsBool(
'use_composition')
65 use_respawn = LaunchConfigAsBool(
'use_respawn')
66 use_keepout_zones = LaunchConfigAsBool(
'use_keepout_zones')
67 use_speed_zones = LaunchConfigAsBool(
'use_speed_zones')
70 rviz_config_file = LaunchConfiguration(
'rviz_config_file')
71 use_simulator = LaunchConfigAsBool(
'use_simulator')
72 use_robot_state_pub = LaunchConfigAsBool(
'use_robot_state_pub')
73 use_rviz = LaunchConfigAsBool(
'use_rviz')
74 headless = LaunchConfigAsBool(
'headless')
75 world = LaunchConfiguration(
'world')
77 'x': LaunchConfiguration(
'x_pose', default=MAP_POSES_DICT[MAP_TYPE][
'x']),
78 'y': LaunchConfiguration(
'y_pose', default=MAP_POSES_DICT[MAP_TYPE][
'y']),
79 'z': LaunchConfiguration(
'z_pose', default=MAP_POSES_DICT[MAP_TYPE][
'z']),
80 'R': LaunchConfiguration(
'roll', default=MAP_POSES_DICT[MAP_TYPE][
'R']),
81 'P': LaunchConfiguration(
'pitch', default=MAP_POSES_DICT[MAP_TYPE][
'P']),
82 'Y': LaunchConfiguration(
'yaw', default=MAP_POSES_DICT[MAP_TYPE][
'Y']),
84 robot_name = LaunchConfiguration(
'robot_name')
85 robot_sdf = LaunchConfiguration(
'robot_sdf')
87 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
90 declare_namespace_cmd = DeclareLaunchArgument(
91 'namespace', default_value=
'', description=
'Top-level namespace'
94 declare_slam_cmd = DeclareLaunchArgument(
95 'slam', default_value=
'False', description=
'Whether run a SLAM'
98 declare_map_yaml_cmd = DeclareLaunchArgument(
100 default_value=os.path.join(bringup_dir,
'maps', f
'{MAP_TYPE}.yaml'),
101 description=
'Full path to map file to load',
104 declare_keepout_mask_yaml_cmd = DeclareLaunchArgument(
106 default_value=os.path.join(bringup_dir,
'maps', f
'{MAP_TYPE}_keepout.yaml'),
107 description=
'Full path to keepout mask file to load',
110 declare_speed_mask_yaml_cmd = DeclareLaunchArgument(
112 default_value=os.path.join(bringup_dir,
'maps', f
'{MAP_TYPE}_speed.yaml'),
113 description=
'Full path to speed mask file to load',
116 declare_graph_file_cmd = DeclareLaunchArgument(
118 default_value=os.path.join(bringup_dir,
'graphs', f
'{MAP_TYPE}_graph.geojson'),
121 declare_use_sim_time_cmd = DeclareLaunchArgument(
123 default_value=
'true',
124 description=
'Use simulation (Gazebo) clock if true',
127 declare_params_file_cmd = DeclareLaunchArgument(
129 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
130 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
133 declare_autostart_cmd = DeclareLaunchArgument(
135 default_value=
'true',
136 description=
'Automatically startup the nav2 stack',
139 declare_use_composition_cmd = DeclareLaunchArgument(
141 default_value=
'True',
142 description=
'Whether to use composed bringup',
145 declare_use_respawn_cmd = DeclareLaunchArgument(
147 default_value=
'False',
148 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
151 declare_use_keepout_zones_cmd = DeclareLaunchArgument(
152 'use_keepout_zones', default_value=
'True',
153 description=
'Whether to enable keepout zones or not'
156 declare_use_speed_zones_cmd = DeclareLaunchArgument(
157 'use_speed_zones', default_value=
'True',
158 description=
'Whether to enable speed zones or not'
161 declare_rviz_config_file_cmd = DeclareLaunchArgument(
163 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
164 description=
'Full path to the RVIZ config file to use',
167 declare_use_simulator_cmd = DeclareLaunchArgument(
169 default_value=
'True',
170 description=
'Whether to start the simulator',
173 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
174 'use_robot_state_pub',
175 default_value=
'True',
176 description=
'Whether to start the robot state publisher',
179 declare_use_rviz_cmd = DeclareLaunchArgument(
180 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
183 declare_simulator_cmd = DeclareLaunchArgument(
184 'headless', default_value=
'True', description=
'Whether to execute gzclient)'
187 declare_world_cmd = DeclareLaunchArgument(
189 default_value=os.path.join(sim_dir,
'worlds', f
'{MAP_TYPE}.sdf'),
190 description=
'Full path to world model file to load',
193 declare_robot_name_cmd = DeclareLaunchArgument(
194 'robot_name', default_value=
'nav2_turtlebot4', description=
'name of the robot'
197 declare_robot_sdf_cmd = DeclareLaunchArgument(
199 default_value=os.path.join(desc_dir,
'urdf',
'standard',
'turtlebot4.urdf.xacro'),
200 description=
'Full path to robot sdf file to spawn the robot in gazebo',
203 start_robot_state_publisher_cmd = Node(
204 condition=IfCondition(use_robot_state_pub),
205 package=
'robot_state_publisher',
206 executable=
'robot_state_publisher',
207 name=
'robot_state_publisher',
211 {
'use_sim_time': use_sim_time,
'robot_description': Command([
'xacro',
' ', robot_sdf])}
213 remappings=remappings,
216 rviz_cmd = IncludeLaunchDescription(
217 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'rviz_launch.py')),
218 condition=IfCondition(use_rviz),
220 'namespace': namespace,
221 'use_sim_time': use_sim_time,
222 'rviz_config': rviz_config_file,
226 bringup_cmd = IncludeLaunchDescription(
227 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'bringup_launch.py')),
229 'namespace': namespace,
231 'map': map_yaml_file,
232 'keepout_mask': keepout_mask_yaml_file,
233 'speed_mask': speed_mask_yaml_file,
234 'graph': graph_filepath,
235 'use_sim_time': use_sim_time,
236 'params_file': params_file,
237 'autostart': autostart,
238 'use_composition': use_composition,
239 'use_respawn': use_respawn,
240 'use_keepout_zones': use_keepout_zones,
241 'use_speed_zones': use_speed_zones,
250 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
251 world_sdf_xacro = ExecuteProcess(
252 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=', headless], world])
253 gazebo_server = ExecuteProcess(
254 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
256 condition=IfCondition(use_simulator)
259 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
261 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
264 set_env_vars_resources = AppendEnvironmentVariable(
265 'GZ_SIM_RESOURCE_PATH',
266 os.path.join(sim_dir,
'worlds'))
267 gazebo_client = IncludeLaunchDescription(
268 PythonLaunchDescriptionSource(
269 os.path.join(get_package_share_directory(
'ros_gz_sim'),
273 condition=IfCondition(PythonExpression(
274 [use_simulator,
' and not ', headless])),
275 launch_arguments={
'gz_args': [
'-v4 -g ']}.items(),
278 gz_robot = IncludeLaunchDescription(
279 PythonLaunchDescriptionSource(
280 os.path.join(sim_dir,
'launch',
'spawn_tb4.launch.py')),
281 launch_arguments={
'namespace': namespace,
282 'use_simulator': use_simulator,
283 'use_sim_time': use_sim_time,
284 'robot_name': robot_name,
285 'robot_sdf': robot_sdf,
291 'yaw': pose[
'Y']}.items())
294 ld = LaunchDescription()
297 ld.add_action(declare_namespace_cmd)
298 ld.add_action(declare_slam_cmd)
299 ld.add_action(declare_map_yaml_cmd)
300 ld.add_action(declare_keepout_mask_yaml_cmd)
301 ld.add_action(declare_speed_mask_yaml_cmd)
302 ld.add_action(declare_graph_file_cmd)
303 ld.add_action(declare_use_sim_time_cmd)
304 ld.add_action(declare_params_file_cmd)
305 ld.add_action(declare_autostart_cmd)
306 ld.add_action(declare_use_composition_cmd)
308 ld.add_action(declare_rviz_config_file_cmd)
309 ld.add_action(declare_use_simulator_cmd)
310 ld.add_action(declare_use_robot_state_pub_cmd)
311 ld.add_action(declare_use_rviz_cmd)
312 ld.add_action(declare_simulator_cmd)
313 ld.add_action(declare_world_cmd)
314 ld.add_action(declare_robot_name_cmd)
315 ld.add_action(declare_robot_sdf_cmd)
316 ld.add_action(declare_use_respawn_cmd)
317 ld.add_action(declare_use_keepout_zones_cmd)
318 ld.add_action(declare_use_speed_zones_cmd)
320 ld.add_action(set_env_vars_resources)
321 ld.add_action(world_sdf_xacro)
322 ld.add_action(remove_temp_sdf_file)
323 ld.add_action(gz_robot)
324 ld.add_action(gazebo_server)
325 ld.add_action(gazebo_client)
328 ld.add_action(start_robot_state_publisher_cmd)
329 ld.add_action(rviz_cmd)
330 ld.add_action(bringup_cmd)