18 from pathlib
import Path
20 from typing
import Optional
22 from ament_index_python.packages
import get_package_share_directory
23 from launch
import LaunchDescription, LaunchDescriptionEntity
24 from launch.actions
import (AppendEnvironmentVariable, DeclareLaunchArgument, ExecuteProcess,
25 ForEach, GroupAction, IncludeLaunchDescription, LogInfo,
26 OpaqueFunction, RegisterEventHandler)
27 from launch.conditions
import IfCondition
28 from launch.event_handlers
import OnShutdown
29 from launch.launch_context
import LaunchContext
30 from launch.launch_description_sources
import PythonLaunchDescriptionSource
31 from launch.substitutions
import LaunchConfiguration, TextSubstitution
36 def count_robots(context: LaunchContext) -> list[LogInfo]:
37 """Count the number of robots from the 'robots' launch argument."""
38 robots_str = LaunchConfiguration(
'robots').perform(context).strip()
42 log_msg =
'No robots provided in the launch argument.'
45 robots_list = [yaml.safe_load(robot.strip())
for robot
in
46 robots_str.split(
';')
if robot.strip()]
47 log_msg = f
'number_of_robots={len(robots_list)}'
48 except yaml.YAMLError
as e:
49 log_msg = f
'Error parsing the robots launch argument: {e}'
51 return [LogInfo(msg=[log_msg])]
54 def generate_robot_actions(
55 name: str =
'', pose: dict[str, float] = {}) -> \
56 Optional[list[LaunchDescriptionEntity]]:
57 """Generate the actions to launch a robot with the given name and pose."""
58 bringup_dir = get_package_share_directory(
'nav2_bringup')
59 launch_dir = os.path.join(bringup_dir,
'launch')
60 use_rviz = LaunchConfigAsBool(
'use_rviz')
61 params_file = LaunchConfiguration(
'params_file')
62 autostart = LaunchConfigAsBool(
'autostart')
63 rviz_config_file = LaunchConfiguration(
'rviz_config')
64 map_yaml_file = LaunchConfiguration(
'map')
65 graph_filepath = LaunchConfiguration(
'graph')
66 use_robot_state_pub = LaunchConfigAsBool(
'use_robot_state_pub')
72 msg=[
'Launching namespace=', name,
' init_pose=', str(pose),]
74 IncludeLaunchDescription(
75 PythonLaunchDescriptionSource(
76 os.path.join(launch_dir,
'rviz_launch.py')
78 condition=IfCondition(use_rviz),
80 'namespace': TextSubstitution(text=name),
81 'rviz_config': rviz_config_file,
84 IncludeLaunchDescription(
85 PythonLaunchDescriptionSource(
86 os.path.join(bringup_dir,
'launch',
'tb3_simulation_launch.py')
91 'graph': graph_filepath,
92 'use_sim_time':
'True',
93 'params_file': params_file,
94 'autostart': autostart,
96 'use_simulator':
'False',
98 'use_robot_state_pub': use_robot_state_pub,
99 'x_pose': TextSubstitution(text=str(pose.get(
'x', 0.0))),
100 'y_pose': TextSubstitution(text=str(pose.get(
'y', 0.0))),
101 'z_pose': TextSubstitution(text=str(pose.get(
'z', 0.0))),
102 'roll': TextSubstitution(text=str(pose.get(
'roll', 0.0))),
103 'pitch': TextSubstitution(text=str(pose.get(
'pitch', 0.0))),
104 'yaw': TextSubstitution(text=str(pose.get(
'yaw', 0.0))),
105 'robot_name': TextSubstitution(text=name),
113 def generate_launch_description() -> LaunchDescription:
115 Bring up the multi-robots with given launch arguments.
117 Launch arguments consist of robot name(which is namespace) and pose for initialization.
118 Keep general yaml format for pose information.
120 ex) robots:='{name: 'robot1', pose: {x: 1.0, y: 1.0, yaw: 1.5707}};
121 {name: 'robot2', pose: {x: 1.0, y: 1.0, yaw: 1.5707}}'
122 ex) robots:='{name: 'robot3', pose: {x: 1.0, y: 1.0, z: 1.0,
123 roll: 0.0, pitch: 1.5707, yaw: 1.5707}};
124 {name: 'robot4', pose: {x: 1.0, y: 1.0, z: 1.0,
125 roll: 0.0, pitch: 1.5707, yaw: 1.5707}}'
128 bringup_dir = get_package_share_directory(
'nav2_bringup')
129 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
132 world = LaunchConfiguration(
'world')
135 map_yaml_file = LaunchConfiguration(
'map')
136 params_file = LaunchConfiguration(
'params_file')
137 autostart = LaunchConfigAsBool(
'autostart')
138 rviz_config_file = LaunchConfiguration(
'rviz_config')
139 use_robot_state_pub = LaunchConfigAsBool(
'use_robot_state_pub')
140 log_settings = LaunchConfiguration(
'log_settings', default=
'true')
143 declare_world_cmd = DeclareLaunchArgument(
145 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
146 description=
'Full path to world file to load',
149 declare_robots_cmd = DeclareLaunchArgument(
152 "{name: 'robot1', pose: {x: 0.5, y: 0.5, yaw: 0}};"
153 "{name: 'robot2', pose: {x: -0.5, y: -0.5, z: 0, roll: 0, pitch: 0, yaw: 1.5707}}"
155 description=
'Robots and their initialization poses in YAML format',
158 declare_map_yaml_cmd = DeclareLaunchArgument(
160 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
161 description=
'Full path to map file to load',
164 declare_graph_file_cmd = DeclareLaunchArgument(
166 default_value=os.path.join(bringup_dir,
'graphs',
'turtlebot3_graph.geojson'),
169 declare_params_file_cmd = DeclareLaunchArgument(
171 default_value=os.path.join(
172 bringup_dir,
'params',
'nav2_params.yaml'
174 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
177 declare_autostart_cmd = DeclareLaunchArgument(
179 default_value=
'false',
180 description=
'Automatically startup the stacks',
183 declare_rviz_config_file_cmd = DeclareLaunchArgument(
185 default_value=os.path.join(
186 bringup_dir,
'rviz',
'nav2_default_view.rviz'),
187 description=
'Full path to the RVIZ config file to use.',
190 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
191 'use_robot_state_pub',
192 default_value=
'True',
193 description=
'Whether to start the robot state publisher',
196 declare_use_rviz_cmd = DeclareLaunchArgument(
197 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
201 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
202 world_sdf_xacro = ExecuteProcess(
203 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=',
'False'], world])
204 start_gazebo_cmd = ExecuteProcess(
205 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
209 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
211 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
214 set_env_vars_resources = AppendEnvironmentVariable(
215 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir,
'models'))
216 set_env_vars_resources2 = AppendEnvironmentVariable(
217 'GZ_SIM_RESOURCE_PATH',
218 str(Path(os.path.join(sim_dir)).parent.resolve()))
221 ld = LaunchDescription()
222 ld.add_action(set_env_vars_resources)
223 ld.add_action(set_env_vars_resources2)
226 ld.add_action(declare_world_cmd)
227 ld.add_action(declare_robots_cmd)
228 ld.add_action(declare_map_yaml_cmd)
229 ld.add_action(declare_graph_file_cmd)
230 ld.add_action(declare_params_file_cmd)
231 ld.add_action(declare_use_rviz_cmd)
232 ld.add_action(declare_autostart_cmd)
233 ld.add_action(declare_rviz_config_file_cmd)
234 ld.add_action(declare_use_robot_state_pub_cmd)
237 ld.add_action(world_sdf_xacro)
238 ld.add_action(start_gazebo_cmd)
239 ld.add_action(remove_temp_sdf_file)
242 LogInfo(condition=IfCondition(log_settings), msg=[
'map yaml: ', map_yaml_file])
245 LogInfo(condition=IfCondition(log_settings), msg=[
'params yaml: ', params_file])
249 condition=IfCondition(log_settings),
250 msg=[
'rviz config file: ', rviz_config_file],
255 condition=IfCondition(log_settings),
256 msg=[
'using robot state pub: ', use_robot_state_pub],
260 LogInfo(condition=IfCondition(log_settings), msg=[
'autostart: ', autostart])
263 ld.add_action(OpaqueFunction(function=count_robots))
264 ld.add_action(ForEach(LaunchConfiguration(
'robots'), function=generate_robot_actions))