18 from pathlib
import Path
21 from ament_index_python.packages
import get_package_share_directory
22 from launch
import LaunchDescription
23 from launch.actions
import (
24 AppendEnvironmentVariable,
25 DeclareLaunchArgument,
28 IncludeLaunchDescription,
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
40 def generate_launch_description():
42 Bring up the multi-robots with given launch arguments.
44 Launch arguments consist of robot name(which is namespace) and pose for initialization.
45 Keep general yaml format for pose information.
46 ex) robots:='robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}'
47 ex) robots:='robot3={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707};
48 robot4={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}'
51 bringup_dir = get_package_share_directory(
'nav2_bringup')
52 launch_dir = os.path.join(bringup_dir,
'launch')
53 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
56 world = LaunchConfiguration(
'world')
59 map_yaml_file = LaunchConfiguration(
'map')
60 params_file = LaunchConfiguration(
'params_file')
61 autostart = LaunchConfiguration(
'autostart')
62 rviz_config_file = LaunchConfiguration(
'rviz_config')
63 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
64 use_rviz = LaunchConfiguration(
'use_rviz')
65 log_settings = LaunchConfiguration(
'log_settings', default=
'true')
68 declare_world_cmd = DeclareLaunchArgument(
70 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
71 description=
'Full path to world file to load',
74 declare_map_yaml_cmd = DeclareLaunchArgument(
76 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
77 description=
'Full path to map file to load',
80 declare_params_file_cmd = DeclareLaunchArgument(
82 default_value=os.path.join(
83 bringup_dir,
'params',
'nav2_multirobot_params_all.yaml'
85 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
88 declare_autostart_cmd = DeclareLaunchArgument(
90 default_value=
'false',
91 description=
'Automatically startup the stacks',
94 declare_rviz_config_file_cmd = DeclareLaunchArgument(
96 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_namespaced_view.rviz'),
97 description=
'Full path to the RVIZ config file to use.',
100 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
101 'use_robot_state_pub',
102 default_value=
'True',
103 description=
'Whether to start the robot state publisher',
106 declare_use_rviz_cmd = DeclareLaunchArgument(
107 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
111 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
112 world_sdf_xacro = ExecuteProcess(
113 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=',
'False'], world])
114 start_gazebo_cmd = ExecuteProcess(
115 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
119 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
121 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
124 robots_list = ParseMultiRobotPose(
'robots').value()
127 bringup_cmd_group = []
128 for robot_name
in robots_list:
129 init_pose = robots_list[robot_name]
134 'Launching namespace=',
140 IncludeLaunchDescription(
141 PythonLaunchDescriptionSource(
142 os.path.join(launch_dir,
'rviz_launch.py')
144 condition=IfCondition(use_rviz),
146 'namespace': TextSubstitution(text=robot_name),
147 'use_namespace':
'True',
148 'rviz_config': rviz_config_file,
151 IncludeLaunchDescription(
152 PythonLaunchDescriptionSource(
153 os.path.join(bringup_dir,
'launch',
'tb3_simulation_launch.py')
156 'namespace': robot_name,
157 'use_namespace':
'True',
158 'map': map_yaml_file,
159 'use_sim_time':
'True',
160 'params_file': params_file,
161 'autostart': autostart,
163 'use_simulator':
'False',
165 'use_robot_state_pub': use_robot_state_pub,
166 'x_pose': TextSubstitution(text=str(init_pose[
'x'])),
167 'y_pose': TextSubstitution(text=str(init_pose[
'y'])),
168 'z_pose': TextSubstitution(text=str(init_pose[
'z'])),
169 'roll': TextSubstitution(text=str(init_pose[
'roll'])),
170 'pitch': TextSubstitution(text=str(init_pose[
'pitch'])),
171 'yaw': TextSubstitution(text=str(init_pose[
'yaw'])),
172 'robot_name': TextSubstitution(text=robot_name),
178 bringup_cmd_group.append(group)
180 set_env_vars_resources = AppendEnvironmentVariable(
181 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir,
'models'))
182 set_env_vars_resources2 = AppendEnvironmentVariable(
183 'GZ_SIM_RESOURCE_PATH',
184 str(Path(os.path.join(sim_dir)).parent.resolve()))
187 ld = LaunchDescription()
188 ld.add_action(set_env_vars_resources)
189 ld.add_action(set_env_vars_resources2)
192 ld.add_action(declare_world_cmd)
193 ld.add_action(declare_map_yaml_cmd)
194 ld.add_action(declare_params_file_cmd)
195 ld.add_action(declare_use_rviz_cmd)
196 ld.add_action(declare_autostart_cmd)
197 ld.add_action(declare_rviz_config_file_cmd)
198 ld.add_action(declare_use_robot_state_pub_cmd)
201 ld.add_action(world_sdf_xacro)
202 ld.add_action(start_gazebo_cmd)
203 ld.add_action(remove_temp_sdf_file)
205 ld.add_action(LogInfo(msg=[
'number_of_robots=', str(len(robots_list))]))
208 LogInfo(condition=IfCondition(log_settings), msg=[
'map yaml: ', map_yaml_file])
211 LogInfo(condition=IfCondition(log_settings), msg=[
'params yaml: ', params_file])
215 condition=IfCondition(log_settings),
216 msg=[
'rviz config file: ', rviz_config_file],
221 condition=IfCondition(log_settings),
222 msg=[
'using robot state pub: ', use_robot_state_pub],
226 LogInfo(condition=IfCondition(log_settings), msg=[
'autostart: ', autostart])
229 for cmd
in bringup_cmd_group: