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
26 from typing
import TypedDict
28 from ament_index_python.packages
import get_package_share_directory
29 from launch
import LaunchDescription
30 from launch.actions
import (AppendEnvironmentVariable, DeclareLaunchArgument, ExecuteProcess,
31 GroupAction, IncludeLaunchDescription, LogInfo, OpaqueFunction,
33 from launch.conditions
import IfCondition
34 from launch.event_handlers
import OnShutdown
35 from launch.launch_description_sources
import PythonLaunchDescriptionSource
36 from launch.substitutions
import LaunchConfiguration, TextSubstitution
41 """TypedDict for robot configuration."""
52 def generate_launch_description() -> LaunchDescription:
54 bringup_dir = get_package_share_directory(
'nav2_bringup')
55 launch_dir = os.path.join(bringup_dir,
'launch')
56 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
59 robots: list[RobotConfig] = [
81 world = LaunchConfiguration(
'world')
84 map_yaml_file = LaunchConfiguration(
'map')
85 graph_filepath = LaunchConfiguration(
'graph')
87 autostart = LaunchConfigAsBool(
'autostart')
88 rviz_config_file = LaunchConfiguration(
'rviz_config')
89 use_robot_state_pub = LaunchConfigAsBool(
'use_robot_state_pub')
90 use_rviz = LaunchConfigAsBool(
'use_rviz')
91 log_settings = LaunchConfiguration(
'log_settings', default=
'true')
94 declare_world_cmd = DeclareLaunchArgument(
96 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
97 description=
'Full path to world file to load',
100 declare_map_yaml_cmd = DeclareLaunchArgument(
102 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
103 description=
'Full path to map file to load',
106 declare_graph_file_cmd = DeclareLaunchArgument(
108 default_value=os.path.join(bringup_dir,
'graphs',
'turtlebot3_graph.geojson'),
111 declare_robot1_params_file_cmd = DeclareLaunchArgument(
112 'robot1_params_file',
113 default_value=os.path.join(
114 bringup_dir,
'params',
'nav2_params.yaml'
116 description=
'Full path to the ROS2 parameters file to use for robot1 launched nodes',
119 declare_robot2_params_file_cmd = DeclareLaunchArgument(
120 'robot2_params_file',
121 default_value=os.path.join(
122 bringup_dir,
'params',
'nav2_params.yaml'
124 description=
'Full path to the ROS2 parameters file to use for robot2 launched nodes',
127 declare_autostart_cmd = DeclareLaunchArgument(
129 default_value=
'false',
130 description=
'Automatically startup the stacks',
133 declare_rviz_config_file_cmd = DeclareLaunchArgument(
135 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
136 description=
'Full path to the RVIZ config file to use.',
139 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
140 'use_robot_state_pub',
141 default_value=
'True',
142 description=
'Whether to start the robot state publisher',
145 declare_use_rviz_cmd = DeclareLaunchArgument(
146 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
150 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
151 world_sdf_xacro = ExecuteProcess(
152 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=',
'False'], world])
153 start_gazebo_cmd = ExecuteProcess(
154 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
158 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
160 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
164 nav_instances_cmds = []
166 params_file = LaunchConfiguration(f
"{robot['name']}_params_file")
170 IncludeLaunchDescription(
171 PythonLaunchDescriptionSource(
172 os.path.join(launch_dir,
'rviz_launch.py')
174 condition=IfCondition(use_rviz),
176 'namespace': TextSubstitution(text=robot[
'name']),
177 'rviz_config': rviz_config_file,
180 IncludeLaunchDescription(
181 PythonLaunchDescriptionSource(
182 os.path.join(bringup_dir,
'launch',
'tb3_simulation_launch.py')
185 'namespace': robot[
'name'],
186 'map': map_yaml_file,
187 'graph': graph_filepath,
188 'use_sim_time':
'True',
189 'params_file': params_file,
190 'autostart': autostart,
192 'use_simulator':
'False',
194 'use_robot_state_pub': use_robot_state_pub,
195 'x_pose': TextSubstitution(text=str(robot[
'x_pose'])),
196 'y_pose': TextSubstitution(text=str(robot[
'y_pose'])),
197 'z_pose': TextSubstitution(text=str(robot[
'z_pose'])),
198 'roll': TextSubstitution(text=str(robot[
'roll'])),
199 'pitch': TextSubstitution(text=str(robot[
'pitch'])),
200 'yaw': TextSubstitution(text=str(robot[
'yaw'])),
201 'robot_name': TextSubstitution(text=robot[
'name']),
205 condition=IfCondition(log_settings),
206 msg=[
'Launching ', robot[
'name']],
209 condition=IfCondition(log_settings),
210 msg=[robot[
'name'],
' map yaml: ', map_yaml_file],
213 condition=IfCondition(log_settings),
214 msg=[robot[
'name'],
' params yaml: ', params_file],
217 condition=IfCondition(log_settings),
218 msg=[robot[
'name'],
' rviz config file: ', rviz_config_file],
221 condition=IfCondition(log_settings),
224 ' using robot state pub: ',
229 condition=IfCondition(log_settings),
230 msg=[robot[
'name'],
' autostart: ', autostart],
235 nav_instances_cmds.append(group)
237 set_env_vars_resources = AppendEnvironmentVariable(
238 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir,
'models'))
239 set_env_vars_resources2 = AppendEnvironmentVariable(
240 'GZ_SIM_RESOURCE_PATH',
241 str(Path(os.path.join(sim_dir)).parent.resolve()))
244 ld = LaunchDescription()
245 ld.add_action(set_env_vars_resources)
246 ld.add_action(set_env_vars_resources2)
249 ld.add_action(declare_world_cmd)
250 ld.add_action(declare_map_yaml_cmd)
251 ld.add_action(declare_graph_file_cmd)
252 ld.add_action(declare_robot1_params_file_cmd)
253 ld.add_action(declare_robot2_params_file_cmd)
254 ld.add_action(declare_use_rviz_cmd)
255 ld.add_action(declare_autostart_cmd)
256 ld.add_action(declare_rviz_config_file_cmd)
257 ld.add_action(declare_use_robot_state_pub_cmd)
260 ld.add_action(world_sdf_xacro)
261 ld.add_action(start_gazebo_cmd)
262 ld.add_action(remove_temp_sdf_file)
264 for simulation_instance_cmd
in nav_instances_cmds:
265 ld.add_action(simulation_instance_cmd)