Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
tb4_simulation_launch.py
1 # Copyright (C) 2024 Open Navigation LLC
2 #
3 # Licensed under the Apache License, Version 2.0 (the "License");
4 # you may not use this file except in compliance with the License.
5 # You may obtain a copy of the License at
6 #
7 # http://www.apache.org/licenses/LICENSE-2.0
8 #
9 # Unless required by applicable law or agreed to in writing, software
10 # distributed under the License is distributed on an "AS IS" BASIS,
11 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 # See the License for the specific language governing permissions and
13 # limitations under the License.
14 
15 """This is all-in-one launch script intended for use by nav2 developers."""
16 
17 import os
18 import tempfile
19 
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
29 
30 # Define local map types
31 MAP_POSES_DICT = {
32  'depot': {
33  'x': -8.00, 'y': 0.00, 'z': 0.01,
34  'R': 0.00, 'P': 0.00, 'Y': 0.00
35  },
36  'warehouse': {
37  'x': 2.00, 'y': -19.65, 'z': 0.01,
38  'R': 0.00, 'P': 0.00, 'Y': 1.57
39  }
40 }
41 MAP_TYPE = 'depot' # Change this to 'warehouse' for warehouse map
42 
43 
44 def generate_launch_description() -> LaunchDescription:
45  # Get the launch directory
46  bringup_dir = get_package_share_directory('nav2_bringup')
47  launch_dir = os.path.join(bringup_dir, 'launch')
48  # This checks that tb4 exists needed for the URDF / simulation files.
49  # If not using TB4, its safe to remove.
50  sim_dir = get_package_share_directory('nav2_minimal_tb4_sim')
51  desc_dir = get_package_share_directory('nav2_minimal_tb4_description')
52 
53  # Create the launch configuration variables
54  slam = LaunchConfiguration('slam')
55  namespace = LaunchConfiguration('namespace')
56  map_yaml_file = LaunchConfiguration('map')
57  keepout_mask_yaml_file = LaunchConfiguration('keepout_mask')
58  speed_mask_yaml_file = LaunchConfiguration('speed_mask')
59  graph_filepath = LaunchConfiguration('graph')
60  use_sim_time = LaunchConfiguration('use_sim_time')
61  params_file = LaunchConfiguration('params_file')
62  autostart = LaunchConfiguration('autostart')
63  use_composition = LaunchConfiguration('use_composition')
64  use_respawn = LaunchConfiguration('use_respawn')
65  use_keepout_zones = LaunchConfiguration('use_keepout_zones')
66  use_speed_zones = LaunchConfiguration('use_speed_zones')
67 
68  # Launch configuration variables specific to simulation
69  rviz_config_file = LaunchConfiguration('rviz_config_file')
70  use_simulator = LaunchConfiguration('use_simulator')
71  use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
72  use_rviz = LaunchConfiguration('use_rviz')
73  headless = LaunchConfiguration('headless')
74  world = LaunchConfiguration('world')
75  pose = {
76  'x': LaunchConfiguration('x_pose', default=MAP_POSES_DICT[MAP_TYPE]['x']),
77  'y': LaunchConfiguration('y_pose', default=MAP_POSES_DICT[MAP_TYPE]['y']),
78  'z': LaunchConfiguration('z_pose', default=MAP_POSES_DICT[MAP_TYPE]['z']),
79  'R': LaunchConfiguration('roll', default=MAP_POSES_DICT[MAP_TYPE]['R']),
80  'P': LaunchConfiguration('pitch', default=MAP_POSES_DICT[MAP_TYPE]['P']),
81  'Y': LaunchConfiguration('yaw', default=MAP_POSES_DICT[MAP_TYPE]['Y']),
82  }
83  robot_name = LaunchConfiguration('robot_name')
84  robot_sdf = LaunchConfiguration('robot_sdf')
85 
86  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
87 
88  # Declare the launch arguments
89  declare_namespace_cmd = DeclareLaunchArgument(
90  'namespace', default_value='', description='Top-level namespace'
91  )
92 
93  declare_slam_cmd = DeclareLaunchArgument(
94  'slam', default_value='False', description='Whether run a SLAM'
95  )
96 
97  declare_map_yaml_cmd = DeclareLaunchArgument(
98  'map',
99  default_value=os.path.join(bringup_dir, 'maps', f'{MAP_TYPE}.yaml'),
100  description='Full path to map file to load',
101  )
102 
103  declare_keepout_mask_yaml_cmd = DeclareLaunchArgument(
104  'keepout_mask',
105  default_value=os.path.join(bringup_dir, 'maps', f'{MAP_TYPE}_keepout.yaml'),
106  description='Full path to keepout mask file to load',
107  )
108 
109  declare_speed_mask_yaml_cmd = DeclareLaunchArgument(
110  'speed_mask',
111  default_value=os.path.join(bringup_dir, 'maps', f'{MAP_TYPE}_speed.yaml'),
112  description='Full path to speed mask file to load',
113  )
114 
115  declare_graph_file_cmd = DeclareLaunchArgument(
116  'graph',
117  default_value=os.path.join(bringup_dir, 'graphs', f'{MAP_TYPE}_graph.geojson'),
118  )
119 
120  declare_use_sim_time_cmd = DeclareLaunchArgument(
121  'use_sim_time',
122  default_value='true',
123  description='Use simulation (Gazebo) clock if true',
124  )
125 
126  declare_params_file_cmd = DeclareLaunchArgument(
127  'params_file',
128  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
129  description='Full path to the ROS2 parameters file to use for all launched nodes',
130  )
131 
132  declare_autostart_cmd = DeclareLaunchArgument(
133  'autostart',
134  default_value='true',
135  description='Automatically startup the nav2 stack',
136  )
137 
138  declare_use_composition_cmd = DeclareLaunchArgument(
139  'use_composition',
140  default_value='True',
141  description='Whether to use composed bringup',
142  )
143 
144  declare_use_respawn_cmd = DeclareLaunchArgument(
145  'use_respawn',
146  default_value='False',
147  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
148  )
149 
150  declare_use_keepout_zones_cmd = DeclareLaunchArgument(
151  'use_keepout_zones', default_value='True',
152  description='Whether to enable keepout zones or not'
153  )
154 
155  declare_use_speed_zones_cmd = DeclareLaunchArgument(
156  'use_speed_zones', default_value='True',
157  description='Whether to enable speed zones or not'
158  )
159 
160  declare_rviz_config_file_cmd = DeclareLaunchArgument(
161  'rviz_config_file',
162  default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
163  description='Full path to the RVIZ config file to use',
164  )
165 
166  declare_use_simulator_cmd = DeclareLaunchArgument(
167  'use_simulator',
168  default_value='True',
169  description='Whether to start the simulator',
170  )
171 
172  declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
173  'use_robot_state_pub',
174  default_value='True',
175  description='Whether to start the robot state publisher',
176  )
177 
178  declare_use_rviz_cmd = DeclareLaunchArgument(
179  'use_rviz', default_value='True', description='Whether to start RVIZ'
180  )
181 
182  declare_simulator_cmd = DeclareLaunchArgument(
183  'headless', default_value='True', description='Whether to execute gzclient)'
184  )
185 
186  declare_world_cmd = DeclareLaunchArgument(
187  'world',
188  default_value=os.path.join(sim_dir, 'worlds', f'{MAP_TYPE}.sdf'),
189  description='Full path to world model file to load',
190  )
191 
192  declare_robot_name_cmd = DeclareLaunchArgument(
193  'robot_name', default_value='nav2_turtlebot4', description='name of the robot'
194  )
195 
196  declare_robot_sdf_cmd = DeclareLaunchArgument(
197  'robot_sdf',
198  default_value=os.path.join(desc_dir, 'urdf', 'standard', 'turtlebot4.urdf.xacro'),
199  description='Full path to robot sdf file to spawn the robot in gazebo',
200  )
201 
202  start_robot_state_publisher_cmd = Node(
203  condition=IfCondition(use_robot_state_pub),
204  package='robot_state_publisher',
205  executable='robot_state_publisher',
206  name='robot_state_publisher',
207  namespace=namespace,
208  output='screen',
209  parameters=[
210  {'use_sim_time': use_sim_time, 'robot_description': Command(['xacro', ' ', robot_sdf])}
211  ],
212  remappings=remappings,
213  )
214 
215  rviz_cmd = IncludeLaunchDescription(
216  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
217  condition=IfCondition(use_rviz),
218  launch_arguments={
219  'namespace': namespace,
220  'use_sim_time': use_sim_time,
221  'rviz_config': rviz_config_file,
222  }.items(),
223  )
224 
225  bringup_cmd = IncludeLaunchDescription(
226  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
227  launch_arguments={
228  'namespace': namespace,
229  'slam': slam,
230  'map': map_yaml_file,
231  'keepout_mask': keepout_mask_yaml_file,
232  'speed_mask': speed_mask_yaml_file,
233  'graph': graph_filepath,
234  'use_sim_time': use_sim_time,
235  'params_file': params_file,
236  'autostart': autostart,
237  'use_composition': use_composition,
238  'use_respawn': use_respawn,
239  'use_keepout_zones': use_keepout_zones,
240  'use_speed_zones': use_speed_zones,
241  }.items(),
242  )
243 
244  # The SDF file for the world is a xacro file because we wanted to
245  # conditionally load the SceneBroadcaster plugin based on whether we're
246  # running in headless mode. But currently, the Gazebo command line doesn't
247  # take SDF strings for worlds, so the output of xacro needs to be saved into
248  # a temporary file and passed to Gazebo.
249  world_sdf = tempfile.mktemp(prefix='nav2_', suffix='.sdf')
250  world_sdf_xacro = ExecuteProcess(
251  cmd=['xacro', '-o', world_sdf, ['headless:=', headless], world])
252  gazebo_server = ExecuteProcess(
253  cmd=['gz', 'sim', '-r', '-s', world_sdf],
254  output='screen',
255  condition=IfCondition(use_simulator)
256  )
257 
258  remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
259  on_shutdown=[
260  OpaqueFunction(function=lambda _: os.remove(world_sdf))
261  ]))
262 
263  set_env_vars_resources = AppendEnvironmentVariable(
264  'GZ_SIM_RESOURCE_PATH',
265  os.path.join(sim_dir, 'worlds'))
266  gazebo_client = IncludeLaunchDescription(
267  PythonLaunchDescriptionSource(
268  os.path.join(get_package_share_directory('ros_gz_sim'),
269  'launch',
270  'gz_sim.launch.py')
271  ),
272  condition=IfCondition(PythonExpression(
273  [use_simulator, ' and not ', headless])),
274  launch_arguments={'gz_args': ['-v4 -g ']}.items(),
275  )
276 
277  gz_robot = IncludeLaunchDescription(
278  PythonLaunchDescriptionSource(
279  os.path.join(sim_dir, 'launch', 'spawn_tb4.launch.py')),
280  launch_arguments={'namespace': namespace,
281  'use_simulator': use_simulator,
282  'use_sim_time': use_sim_time,
283  'robot_name': robot_name,
284  'robot_sdf': robot_sdf,
285  'x_pose': pose['x'],
286  'y_pose': pose['y'],
287  'z_pose': pose['z'],
288  'roll': pose['R'],
289  'pitch': pose['P'],
290  'yaw': pose['Y']}.items())
291 
292  # Create the launch description and populate
293  ld = LaunchDescription()
294 
295  # Declare the launch options
296  ld.add_action(declare_namespace_cmd)
297  ld.add_action(declare_slam_cmd)
298  ld.add_action(declare_map_yaml_cmd)
299  ld.add_action(declare_keepout_mask_yaml_cmd)
300  ld.add_action(declare_speed_mask_yaml_cmd)
301  ld.add_action(declare_graph_file_cmd)
302  ld.add_action(declare_use_sim_time_cmd)
303  ld.add_action(declare_params_file_cmd)
304  ld.add_action(declare_autostart_cmd)
305  ld.add_action(declare_use_composition_cmd)
306 
307  ld.add_action(declare_rviz_config_file_cmd)
308  ld.add_action(declare_use_simulator_cmd)
309  ld.add_action(declare_use_robot_state_pub_cmd)
310  ld.add_action(declare_use_rviz_cmd)
311  ld.add_action(declare_simulator_cmd)
312  ld.add_action(declare_world_cmd)
313  ld.add_action(declare_robot_name_cmd)
314  ld.add_action(declare_robot_sdf_cmd)
315  ld.add_action(declare_use_respawn_cmd)
316  ld.add_action(declare_use_keepout_zones_cmd)
317  ld.add_action(declare_use_speed_zones_cmd)
318 
319  ld.add_action(set_env_vars_resources)
320  ld.add_action(world_sdf_xacro)
321  ld.add_action(remove_temp_sdf_file)
322  ld.add_action(gz_robot)
323  ld.add_action(gazebo_server)
324  ld.add_action(gazebo_client)
325 
326  # Add the actions to launch all of the navigation nodes
327  ld.add_action(start_robot_state_publisher_cmd)
328  ld.add_action(rviz_cmd)
329  ld.add_action(bringup_cmd)
330 
331  return ld