16 Example for spawning multiple robots in Gazebo.
18 This is an example on how to create a launch file for spawning multiple robots into Gazebo
19 and launch multiple instances of the navigation stack, each controlling one robot.
20 The robots co-exist on a shared environment and are controlled by independent nav stacks.
24 from pathlib
import Path
27 from ament_index_python.packages
import get_package_share_directory
29 from launch
import LaunchDescription
30 from launch.actions
import (
31 AppendEnvironmentVariable,
32 DeclareLaunchArgument,
35 IncludeLaunchDescription,
40 from launch.conditions
import IfCondition
41 from launch.event_handlers
import OnShutdown
42 from launch.launch_description_sources
import PythonLaunchDescriptionSource
43 from launch.substitutions
import LaunchConfiguration, TextSubstitution
46 def generate_launch_description():
48 bringup_dir = get_package_share_directory(
'nav2_bringup')
49 launch_dir = os.path.join(bringup_dir,
'launch')
50 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
75 world = LaunchConfiguration(
'world')
78 map_yaml_file = LaunchConfiguration(
'map')
80 autostart = LaunchConfiguration(
'autostart')
81 rviz_config_file = LaunchConfiguration(
'rviz_config')
82 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
83 use_rviz = LaunchConfiguration(
'use_rviz')
84 log_settings = LaunchConfiguration(
'log_settings', default=
'true')
87 declare_world_cmd = DeclareLaunchArgument(
89 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
90 description=
'Full path to world file to load',
93 declare_map_yaml_cmd = DeclareLaunchArgument(
95 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
96 description=
'Full path to map file to load',
99 declare_robot1_params_file_cmd = DeclareLaunchArgument(
100 'robot1_params_file',
101 default_value=os.path.join(
102 bringup_dir,
'params',
'nav2_multirobot_params_1.yaml'
104 description=
'Full path to the ROS2 parameters file to use for robot1 launched nodes',
107 declare_robot2_params_file_cmd = DeclareLaunchArgument(
108 'robot2_params_file',
109 default_value=os.path.join(
110 bringup_dir,
'params',
'nav2_multirobot_params_2.yaml'
112 description=
'Full path to the ROS2 parameters file to use for robot2 launched nodes',
115 declare_autostart_cmd = DeclareLaunchArgument(
117 default_value=
'false',
118 description=
'Automatically startup the stacks',
121 declare_rviz_config_file_cmd = DeclareLaunchArgument(
123 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_namespaced_view.rviz'),
124 description=
'Full path to the RVIZ config file to use.',
127 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
128 'use_robot_state_pub',
129 default_value=
'True',
130 description=
'Whether to start the robot state publisher',
133 declare_use_rviz_cmd = DeclareLaunchArgument(
134 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
138 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
139 world_sdf_xacro = ExecuteProcess(
140 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=',
'False'], world])
141 start_gazebo_cmd = ExecuteProcess(
142 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
146 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
148 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
152 nav_instances_cmds = []
154 params_file = LaunchConfiguration(f
"{robot['name']}_params_file")
158 IncludeLaunchDescription(
159 PythonLaunchDescriptionSource(
160 os.path.join(launch_dir,
'rviz_launch.py')
162 condition=IfCondition(use_rviz),
164 'namespace': TextSubstitution(text=robot[
'name']),
165 'use_namespace':
'True',
166 'rviz_config': rviz_config_file,
169 IncludeLaunchDescription(
170 PythonLaunchDescriptionSource(
171 os.path.join(bringup_dir,
'launch',
'tb3_simulation_launch.py')
174 'namespace': robot[
'name'],
175 'use_namespace':
'True',
176 'map': map_yaml_file,
177 'use_sim_time':
'True',
178 'params_file': params_file,
179 'autostart': autostart,
181 'use_simulator':
'False',
183 'use_robot_state_pub': use_robot_state_pub,
184 'x_pose': TextSubstitution(text=str(robot[
'x_pose'])),
185 'y_pose': TextSubstitution(text=str(robot[
'y_pose'])),
186 'z_pose': TextSubstitution(text=str(robot[
'z_pose'])),
187 'roll': TextSubstitution(text=str(robot[
'roll'])),
188 'pitch': TextSubstitution(text=str(robot[
'pitch'])),
189 'yaw': TextSubstitution(text=str(robot[
'yaw'])),
190 'robot_name': TextSubstitution(text=robot[
'name']),
194 condition=IfCondition(log_settings),
195 msg=[
'Launching ', robot[
'name']],
198 condition=IfCondition(log_settings),
199 msg=[robot[
'name'],
' map yaml: ', map_yaml_file],
202 condition=IfCondition(log_settings),
203 msg=[robot[
'name'],
' params yaml: ', params_file],
206 condition=IfCondition(log_settings),
207 msg=[robot[
'name'],
' rviz config file: ', rviz_config_file],
210 condition=IfCondition(log_settings),
213 ' using robot state pub: ',
218 condition=IfCondition(log_settings),
219 msg=[robot[
'name'],
' autostart: ', autostart],
224 nav_instances_cmds.append(group)
226 set_env_vars_resources = AppendEnvironmentVariable(
227 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir,
'models'))
228 set_env_vars_resources2 = AppendEnvironmentVariable(
229 'GZ_SIM_RESOURCE_PATH',
230 str(Path(os.path.join(sim_dir)).parent.resolve()))
233 ld = LaunchDescription()
234 ld.add_action(set_env_vars_resources)
235 ld.add_action(set_env_vars_resources2)
238 ld.add_action(declare_world_cmd)
239 ld.add_action(declare_map_yaml_cmd)
240 ld.add_action(declare_robot1_params_file_cmd)
241 ld.add_action(declare_robot2_params_file_cmd)
242 ld.add_action(declare_use_rviz_cmd)
243 ld.add_action(declare_autostart_cmd)
244 ld.add_action(declare_rviz_config_file_cmd)
245 ld.add_action(declare_use_robot_state_pub_cmd)
248 ld.add_action(world_sdf_xacro)
249 ld.add_action(start_gazebo_cmd)
250 ld.add_action(remove_temp_sdf_file)
252 for simulation_instance_cmd
in nav_instances_cmds:
253 ld.add_action(simulation_instance_cmd)