Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
tb3_simulation_launch.py
1 # Copyright (C) 2023 Open Source Robotics Foundation
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 (DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription,
23  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 LaunchConfiguration, PythonExpression
28 from launch_ros.actions import Node
29 from nav2_common.launch import LaunchConfigAsBool
30 
31 
32 def generate_launch_description() -> LaunchDescription:
33  # Get the launch directory
34  bringup_dir = get_package_share_directory('nav2_bringup')
35  launch_dir = os.path.join(bringup_dir, 'launch')
36  sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
37 
38  # Create the launch configuration variables
39  slam = LaunchConfigAsBool('slam')
40  namespace = LaunchConfiguration('namespace')
41  map_yaml_file = LaunchConfiguration('map')
42  graph_filepath = LaunchConfiguration('graph')
43  use_sim_time = LaunchConfigAsBool('use_sim_time')
44  params_file = LaunchConfiguration('params_file')
45  autostart = LaunchConfiguration('autostart')
46  use_composition = LaunchConfigAsBool('use_composition')
47  use_respawn = LaunchConfigAsBool('use_respawn')
48 
49  # Launch configuration variables specific to simulation
50  rviz_config_file = LaunchConfiguration('rviz_config_file')
51  use_simulator = LaunchConfigAsBool('use_simulator')
52  use_robot_state_pub = LaunchConfigAsBool('use_robot_state_pub')
53  use_rviz = LaunchConfigAsBool('use_rviz')
54  headless = LaunchConfigAsBool('headless')
55  world = LaunchConfiguration('world')
56  pose = {
57  'x': LaunchConfiguration('x_pose', default='-2.00'),
58  'y': LaunchConfiguration('y_pose', default='-0.50'),
59  'z': LaunchConfiguration('z_pose', default='0.01'),
60  'R': LaunchConfiguration('roll', default='0.00'),
61  'P': LaunchConfiguration('pitch', default='0.00'),
62  'Y': LaunchConfiguration('yaw', default='0.00'),
63  }
64  robot_name = LaunchConfiguration('robot_name')
65  robot_sdf = LaunchConfiguration('robot_sdf')
66 
67  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
68 
69  # Declare the launch arguments
70  declare_namespace_cmd = DeclareLaunchArgument(
71  'namespace', default_value='', description='Top-level namespace'
72  )
73 
74  declare_slam_cmd = DeclareLaunchArgument(
75  'slam', default_value='False', description='Whether run a SLAM'
76  )
77 
78  declare_map_yaml_cmd = DeclareLaunchArgument(
79  'map',
80  default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'),
81  )
82 
83  declare_graph_file_cmd = DeclareLaunchArgument(
84  'graph',
85  default_value=os.path.join(bringup_dir, 'graphs', 'turtlebot3_graph.geojson'),
86  )
87 
88  declare_use_sim_time_cmd = DeclareLaunchArgument(
89  'use_sim_time',
90  default_value='true',
91  description='Use simulation (Gazebo) clock if true',
92  )
93 
94  declare_params_file_cmd = DeclareLaunchArgument(
95  'params_file',
96  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
97  description='Full path to the ROS2 parameters file to use for all launched nodes',
98  )
99 
100  declare_autostart_cmd = DeclareLaunchArgument(
101  'autostart',
102  default_value='true',
103  description='Automatically startup the nav2 stack',
104  )
105 
106  declare_use_composition_cmd = DeclareLaunchArgument(
107  'use_composition',
108  default_value='True',
109  description='Whether to use composed bringup',
110  )
111 
112  declare_use_respawn_cmd = DeclareLaunchArgument(
113  'use_respawn',
114  default_value='False',
115  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
116  )
117 
118  declare_rviz_config_file_cmd = DeclareLaunchArgument(
119  'rviz_config_file',
120  default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
121  description='Full path to the RVIZ config file to use',
122  )
123 
124  declare_use_simulator_cmd = DeclareLaunchArgument(
125  'use_simulator',
126  default_value='True',
127  description='Whether to start the simulator',
128  )
129 
130  declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
131  'use_robot_state_pub',
132  default_value='True',
133  description='Whether to start the robot state publisher',
134  )
135 
136  declare_use_rviz_cmd = DeclareLaunchArgument(
137  'use_rviz', default_value='True', description='Whether to start RVIZ'
138  )
139 
140  declare_simulator_cmd = DeclareLaunchArgument(
141  'headless', default_value='True', description='Whether to execute gzclient)'
142  )
143 
144  declare_world_cmd = DeclareLaunchArgument(
145  'world',
146  default_value=os.path.join(sim_dir, 'worlds', 'tb3_sandbox.sdf.xacro'),
147  description='Full path to world model file to load',
148  )
149 
150  declare_robot_name_cmd = DeclareLaunchArgument(
151  'robot_name', default_value='turtlebot3_waffle', description='name of the robot'
152  )
153 
154  declare_robot_sdf_cmd = DeclareLaunchArgument(
155  'robot_sdf',
156  default_value=os.path.join(sim_dir, 'urdf', 'gz_waffle.sdf.xacro'),
157  description='Full path to robot sdf file to spawn the robot in gazebo',
158  )
159 
160  urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
161  with open(urdf, 'r') as infp:
162  robot_description = infp.read()
163 
164  start_robot_state_publisher_cmd = Node(
165  condition=IfCondition(use_robot_state_pub),
166  package='robot_state_publisher',
167  executable='robot_state_publisher',
168  name='robot_state_publisher',
169  namespace=namespace,
170  output='screen',
171  parameters=[
172  {'use_sim_time': use_sim_time, 'robot_description': robot_description}
173  ],
174  remappings=remappings,
175  )
176 
177  rviz_cmd = IncludeLaunchDescription(
178  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
179  condition=IfCondition(use_rviz),
180  launch_arguments={
181  'namespace': namespace,
182  'use_sim_time': use_sim_time,
183  'rviz_config': rviz_config_file,
184  }.items(),
185  )
186 
187  bringup_cmd = IncludeLaunchDescription(
188  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
189  launch_arguments={
190  'namespace': namespace,
191  'slam': slam,
192  'map': map_yaml_file,
193  'graph': graph_filepath,
194  'use_sim_time': use_sim_time,
195  'params_file': params_file,
196  'autostart': autostart,
197  'use_composition': use_composition,
198  'use_respawn': use_respawn,
199  'use_keepout_zones': 'False',
200  'use_speed_zones': 'False',
201  }.items(),
202  )
203  # The SDF file for the world is a xacro file because we wanted to
204  # conditionally load the SceneBroadcaster plugin based on whether we're
205  # running in headless mode. But currently, the Gazebo command line doesn't
206  # take SDF strings for worlds, so the output of xacro needs to be saved into
207  # a temporary file and passed to Gazebo.
208  world_sdf = tempfile.mktemp(prefix='nav2_', suffix='.sdf')
209  world_sdf_xacro = ExecuteProcess(
210  cmd=['xacro', '-o', world_sdf, ['headless:=', headless], world])
211  gazebo_server = ExecuteProcess(
212  cmd=['gz', 'sim', '-r', '-s', world_sdf],
213  output='screen',
214  condition=IfCondition(use_simulator)
215  )
216 
217  remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
218  on_shutdown=[
219  OpaqueFunction(function=lambda _: os.remove(world_sdf))
220  ]))
221 
222  gazebo_client = IncludeLaunchDescription(
223  PythonLaunchDescriptionSource(
224  os.path.join(get_package_share_directory('ros_gz_sim'),
225  'launch',
226  'gz_sim.launch.py')
227  ),
228  condition=IfCondition(PythonExpression(
229  [use_simulator, ' and not ', headless])),
230  launch_arguments={'gz_args': ['-v4 -g ']}.items(),
231  )
232 
233  gz_robot = IncludeLaunchDescription(
234  PythonLaunchDescriptionSource(
235  os.path.join(sim_dir, 'launch', 'spawn_tb3.launch.py')),
236  launch_arguments={'namespace': namespace,
237  'use_sim_time': use_sim_time,
238  'robot_name': robot_name,
239  'robot_sdf': robot_sdf,
240  'x_pose': pose['x'],
241  'y_pose': pose['y'],
242  'z_pose': pose['z'],
243  'roll': pose['R'],
244  'pitch': pose['P'],
245  'yaw': pose['Y']}.items())
246 
247  # Create the launch description and populate
248  ld = LaunchDescription()
249 
250  # Declare the launch options
251  ld.add_action(declare_namespace_cmd)
252  ld.add_action(declare_slam_cmd)
253  ld.add_action(declare_map_yaml_cmd)
254  ld.add_action(declare_graph_file_cmd)
255  ld.add_action(declare_use_sim_time_cmd)
256  ld.add_action(declare_params_file_cmd)
257  ld.add_action(declare_autostart_cmd)
258  ld.add_action(declare_use_composition_cmd)
259 
260  ld.add_action(declare_rviz_config_file_cmd)
261  ld.add_action(declare_use_simulator_cmd)
262  ld.add_action(declare_use_robot_state_pub_cmd)
263  ld.add_action(declare_use_rviz_cmd)
264  ld.add_action(declare_simulator_cmd)
265  ld.add_action(declare_world_cmd)
266  ld.add_action(declare_robot_name_cmd)
267  ld.add_action(declare_robot_sdf_cmd)
268  ld.add_action(declare_use_respawn_cmd)
269 
270  ld.add_action(world_sdf_xacro)
271  ld.add_action(remove_temp_sdf_file)
272  ld.add_action(gz_robot)
273  ld.add_action(gazebo_server)
274  ld.add_action(gazebo_client)
275 
276  # Add the actions to launch all of the navigation nodes
277  ld.add_action(start_robot_state_publisher_cmd)
278  ld.add_action(rviz_cmd)
279  ld.add_action(bringup_cmd)
280 
281  return ld