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 (AppendEnvironmentVariable, DeclareLaunchArgument, ExecuteProcess,
24 ForEach, GroupAction, IncludeLaunchDescription, LogInfo,
25 OpaqueFunction, RegisterEventHandler)
26 from launch.conditions
import IfCondition
27 from launch.event_handlers
import OnShutdown
28 from launch.launch_context
import LaunchContext
29 from launch.launch_description_sources
import PythonLaunchDescriptionSource
30 from launch.substitutions
import LaunchConfiguration, TextSubstitution
34 def count_robots(context: LaunchContext) -> list[LogInfo]:
35 """Count the number of robots from the 'robots' launch argument."""
36 robots_str = LaunchConfiguration(
'robots').perform(context).strip()
40 log_msg =
'No robots provided in the launch argument.'
43 robots_list = [yaml.safe_load(robot.strip())
for robot
in
44 robots_str.split(
';')
if robot.strip()]
45 log_msg = f
'number_of_robots={len(robots_list)}'
46 except yaml.YAMLError
as e:
47 log_msg = f
'Error parsing the robots launch argument: {e}'
49 return [LogInfo(msg=[log_msg])]
52 def generate_robot_actions(name: str =
'', pose: dict[str, float] = {}) -> list[GroupAction]:
53 """Generate the actions to launch a robot with the given name and pose."""
54 bringup_dir = get_package_share_directory(
'nav2_bringup')
55 launch_dir = os.path.join(bringup_dir,
'launch')
56 use_rviz = LaunchConfiguration(
'use_rviz')
57 params_file = LaunchConfiguration(
'params_file')
58 autostart = LaunchConfiguration(
'autostart')
59 rviz_config_file = LaunchConfiguration(
'rviz_config')
60 map_yaml_file = LaunchConfiguration(
'map')
61 graph_filepath = LaunchConfiguration(
'graph')
62 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
68 msg=[
'Launching namespace=', name,
' init_pose=', str(pose),]
70 IncludeLaunchDescription(
71 PythonLaunchDescriptionSource(
72 os.path.join(launch_dir,
'rviz_launch.py')
74 condition=IfCondition(use_rviz),
76 'namespace': TextSubstitution(text=name),
77 'rviz_config': rviz_config_file,
80 IncludeLaunchDescription(
81 PythonLaunchDescriptionSource(
82 os.path.join(bringup_dir,
'launch',
'tb3_simulation_launch.py')
87 'graph': graph_filepath,
88 'use_sim_time':
'True',
89 'params_file': params_file,
90 'autostart': autostart,
92 'use_simulator':
'False',
94 'use_robot_state_pub': use_robot_state_pub,
95 'x_pose': TextSubstitution(text=str(pose.get(
'x', 0.0))),
96 'y_pose': TextSubstitution(text=str(pose.get(
'y', 0.0))),
97 'z_pose': TextSubstitution(text=str(pose.get(
'z', 0.0))),
98 'roll': TextSubstitution(text=str(pose.get(
'roll', 0.0))),
99 'pitch': TextSubstitution(text=str(pose.get(
'pitch', 0.0))),
100 'yaw': TextSubstitution(text=str(pose.get(
'yaw', 0.0))),
101 'robot_name': TextSubstitution(text=name),
109 def generate_launch_description() -> LaunchDescription:
111 Bring up the multi-robots with given launch arguments.
113 Launch arguments consist of robot name(which is namespace) and pose for initialization.
114 Keep general yaml format for pose information.
116 ex) robots:='{name: 'robot1', pose: {x: 1.0, y: 1.0, yaw: 1.5707}};
117 {name: 'robot2', pose: {x: 1.0, y: 1.0, yaw: 1.5707}}'
118 ex) robots:='{name: 'robot3', pose: {x: 1.0, y: 1.0, z: 1.0,
119 roll: 0.0, pitch: 1.5707, yaw: 1.5707}};
120 {name: 'robot4', pose: {x: 1.0, y: 1.0, z: 1.0,
121 roll: 0.0, pitch: 1.5707, yaw: 1.5707}}'
124 bringup_dir = get_package_share_directory(
'nav2_bringup')
125 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
128 world = LaunchConfiguration(
'world')
131 map_yaml_file = LaunchConfiguration(
'map')
132 params_file = LaunchConfiguration(
'params_file')
133 autostart = LaunchConfiguration(
'autostart')
134 rviz_config_file = LaunchConfiguration(
'rviz_config')
135 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
136 log_settings = LaunchConfiguration(
'log_settings', default=
'true')
139 declare_world_cmd = DeclareLaunchArgument(
141 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
142 description=
'Full path to world file to load',
145 declare_robots_cmd = DeclareLaunchArgument(
148 "{name: 'robot1', pose: {x: 0.5, y: 0.5, yaw: 0}};"
149 "{name: 'robot2', pose: {x: -0.5, y: -0.5, z: 0, roll: 0, pitch: 0, yaw: 1.5707}}"
151 description=
'Robots and their initialization poses in YAML format',
154 declare_map_yaml_cmd = DeclareLaunchArgument(
156 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
157 description=
'Full path to map file to load',
160 declare_graph_file_cmd = DeclareLaunchArgument(
162 default_value=os.path.join(bringup_dir,
'graphs',
'turtlebot3_graph.geojson'),
165 declare_params_file_cmd = DeclareLaunchArgument(
167 default_value=os.path.join(
168 bringup_dir,
'params',
'nav2_params.yaml'
170 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
173 declare_autostart_cmd = DeclareLaunchArgument(
175 default_value=
'false',
176 description=
'Automatically startup the stacks',
179 declare_rviz_config_file_cmd = DeclareLaunchArgument(
181 default_value=os.path.join(
182 bringup_dir,
'rviz',
'nav2_default_view.rviz'),
183 description=
'Full path to the RVIZ config file to use.',
186 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
187 'use_robot_state_pub',
188 default_value=
'True',
189 description=
'Whether to start the robot state publisher',
192 declare_use_rviz_cmd = DeclareLaunchArgument(
193 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
197 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
198 world_sdf_xacro = ExecuteProcess(
199 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=',
'False'], world])
200 start_gazebo_cmd = ExecuteProcess(
201 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
205 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
207 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
210 set_env_vars_resources = AppendEnvironmentVariable(
211 'GZ_SIM_RESOURCE_PATH', os.path.join(sim_dir,
'models'))
212 set_env_vars_resources2 = AppendEnvironmentVariable(
213 'GZ_SIM_RESOURCE_PATH',
214 str(Path(os.path.join(sim_dir)).parent.resolve()))
217 ld = LaunchDescription()
218 ld.add_action(set_env_vars_resources)
219 ld.add_action(set_env_vars_resources2)
222 ld.add_action(declare_world_cmd)
223 ld.add_action(declare_robots_cmd)
224 ld.add_action(declare_map_yaml_cmd)
225 ld.add_action(declare_graph_file_cmd)
226 ld.add_action(declare_params_file_cmd)
227 ld.add_action(declare_use_rviz_cmd)
228 ld.add_action(declare_autostart_cmd)
229 ld.add_action(declare_rviz_config_file_cmd)
230 ld.add_action(declare_use_robot_state_pub_cmd)
233 ld.add_action(world_sdf_xacro)
234 ld.add_action(start_gazebo_cmd)
235 ld.add_action(remove_temp_sdf_file)
238 LogInfo(condition=IfCondition(log_settings), msg=[
'map yaml: ', map_yaml_file])
241 LogInfo(condition=IfCondition(log_settings), msg=[
'params yaml: ', params_file])
245 condition=IfCondition(log_settings),
246 msg=[
'rviz config file: ', rviz_config_file],
251 condition=IfCondition(log_settings),
252 msg=[
'using robot state pub: ', use_robot_state_pub],
256 LogInfo(condition=IfCondition(log_settings), msg=[
'autostart: ', autostart])
259 ld.add_action(OpaqueFunction(function=count_robots))
260 ld.add_action(ForEach(LaunchConfiguration(
'robots'), function=generate_robot_actions))