15 """This is all-in-one launch script intended for use by nav2 developers."""
20 from ament_index_python.packages
import get_package_share_directory
21 from launch
import LaunchDescription
22 from launch.actions
import (DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription,
23 OpaqueFunction, RegisterEventHandler)
24 from launch.conditions
import IfCondition
25 from launch.event_handlers
import OnShutdown
26 from launch.launch_description_sources
import PythonLaunchDescriptionSource
27 from launch.substitutions
import LaunchConfiguration, PythonExpression
28 from launch_ros.actions
import Node
32 def generate_launch_description() -> LaunchDescription:
34 bringup_dir = get_package_share_directory(
'nav2_bringup')
35 launch_dir = os.path.join(bringup_dir,
'launch')
36 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
39 slam = LaunchConfigAsBool(
'slam')
40 namespace = LaunchConfiguration(
'namespace')
41 map_yaml_file = LaunchConfiguration(
'map')
42 graph_filepath = LaunchConfiguration(
'graph')
43 use_sim_time = LaunchConfigAsBool(
'use_sim_time')
44 params_file = LaunchConfiguration(
'params_file')
45 autostart = LaunchConfiguration(
'autostart')
46 use_composition = LaunchConfigAsBool(
'use_composition')
47 use_respawn = LaunchConfigAsBool(
'use_respawn')
50 rviz_config_file = LaunchConfiguration(
'rviz_config_file')
51 use_simulator = LaunchConfigAsBool(
'use_simulator')
52 use_robot_state_pub = LaunchConfigAsBool(
'use_robot_state_pub')
53 use_rviz = LaunchConfigAsBool(
'use_rviz')
54 headless = LaunchConfigAsBool(
'headless')
55 world = LaunchConfiguration(
'world')
57 'x': LaunchConfiguration(
'x_pose', default=
'-2.00'),
58 'y': LaunchConfiguration(
'y_pose', default=
'-0.50'),
59 'z': LaunchConfiguration(
'z_pose', default=
'0.01'),
60 'R': LaunchConfiguration(
'roll', default=
'0.00'),
61 'P': LaunchConfiguration(
'pitch', default=
'0.00'),
62 'Y': LaunchConfiguration(
'yaw', default=
'0.00'),
64 robot_name = LaunchConfiguration(
'robot_name')
65 robot_sdf = LaunchConfiguration(
'robot_sdf')
67 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
70 declare_namespace_cmd = DeclareLaunchArgument(
71 'namespace', default_value=
'', description=
'Top-level namespace'
74 declare_slam_cmd = DeclareLaunchArgument(
75 'slam', default_value=
'False', description=
'Whether run a SLAM'
78 declare_map_yaml_cmd = DeclareLaunchArgument(
80 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
83 declare_graph_file_cmd = DeclareLaunchArgument(
85 default_value=os.path.join(bringup_dir,
'graphs',
'turtlebot3_graph.geojson'),
88 declare_use_sim_time_cmd = DeclareLaunchArgument(
91 description=
'Use simulation (Gazebo) clock if true',
94 declare_params_file_cmd = DeclareLaunchArgument(
96 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
97 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
100 declare_autostart_cmd = DeclareLaunchArgument(
102 default_value=
'true',
103 description=
'Automatically startup the nav2 stack',
106 declare_use_composition_cmd = DeclareLaunchArgument(
108 default_value=
'True',
109 description=
'Whether to use composed bringup',
112 declare_use_respawn_cmd = DeclareLaunchArgument(
114 default_value=
'False',
115 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
118 declare_rviz_config_file_cmd = DeclareLaunchArgument(
120 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
121 description=
'Full path to the RVIZ config file to use',
124 declare_use_simulator_cmd = DeclareLaunchArgument(
126 default_value=
'True',
127 description=
'Whether to start the simulator',
130 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
131 'use_robot_state_pub',
132 default_value=
'True',
133 description=
'Whether to start the robot state publisher',
136 declare_use_rviz_cmd = DeclareLaunchArgument(
137 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
140 declare_simulator_cmd = DeclareLaunchArgument(
141 'headless', default_value=
'True', description=
'Whether to execute gzclient)'
144 declare_world_cmd = DeclareLaunchArgument(
146 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
147 description=
'Full path to world model file to load',
150 declare_robot_name_cmd = DeclareLaunchArgument(
151 'robot_name', default_value=
'turtlebot3_waffle', description=
'name of the robot'
154 declare_robot_sdf_cmd = DeclareLaunchArgument(
156 default_value=os.path.join(sim_dir,
'urdf',
'gz_waffle.sdf.xacro'),
157 description=
'Full path to robot sdf file to spawn the robot in gazebo',
160 urdf = os.path.join(sim_dir,
'urdf',
'turtlebot3_waffle.urdf')
161 with open(urdf,
'r')
as infp:
162 robot_description = infp.read()
164 start_robot_state_publisher_cmd = Node(
165 condition=IfCondition(use_robot_state_pub),
166 package=
'robot_state_publisher',
167 executable=
'robot_state_publisher',
168 name=
'robot_state_publisher',
172 {
'use_sim_time': use_sim_time,
'robot_description': robot_description}
174 remappings=remappings,
177 rviz_cmd = IncludeLaunchDescription(
178 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'rviz_launch.py')),
179 condition=IfCondition(use_rviz),
181 'namespace': namespace,
182 'use_sim_time': use_sim_time,
183 'rviz_config': rviz_config_file,
187 bringup_cmd = IncludeLaunchDescription(
188 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'bringup_launch.py')),
190 'namespace': namespace,
192 'map': map_yaml_file,
193 'graph': graph_filepath,
194 'use_sim_time': use_sim_time,
195 'params_file': params_file,
196 'autostart': autostart,
197 'use_composition': use_composition,
198 'use_respawn': use_respawn,
199 'use_keepout_zones':
'False',
200 'use_speed_zones':
'False',
208 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
209 world_sdf_xacro = ExecuteProcess(
210 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=', headless], world])
211 gazebo_server = ExecuteProcess(
212 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
214 condition=IfCondition(use_simulator)
217 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
219 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
222 gazebo_client = IncludeLaunchDescription(
223 PythonLaunchDescriptionSource(
224 os.path.join(get_package_share_directory(
'ros_gz_sim'),
228 condition=IfCondition(PythonExpression(
229 [use_simulator,
' and not ', headless])),
230 launch_arguments={
'gz_args': [
'-v4 -g ']}.items(),
233 gz_robot = IncludeLaunchDescription(
234 PythonLaunchDescriptionSource(
235 os.path.join(sim_dir,
'launch',
'spawn_tb3.launch.py')),
236 launch_arguments={
'namespace': namespace,
237 'use_sim_time': use_sim_time,
238 'robot_name': robot_name,
239 'robot_sdf': robot_sdf,
245 'yaw': pose[
'Y']}.items())
248 ld = LaunchDescription()
251 ld.add_action(declare_namespace_cmd)
252 ld.add_action(declare_slam_cmd)
253 ld.add_action(declare_map_yaml_cmd)
254 ld.add_action(declare_graph_file_cmd)
255 ld.add_action(declare_use_sim_time_cmd)
256 ld.add_action(declare_params_file_cmd)
257 ld.add_action(declare_autostart_cmd)
258 ld.add_action(declare_use_composition_cmd)
260 ld.add_action(declare_rviz_config_file_cmd)
261 ld.add_action(declare_use_simulator_cmd)
262 ld.add_action(declare_use_robot_state_pub_cmd)
263 ld.add_action(declare_use_rviz_cmd)
264 ld.add_action(declare_simulator_cmd)
265 ld.add_action(declare_world_cmd)
266 ld.add_action(declare_robot_name_cmd)
267 ld.add_action(declare_robot_sdf_cmd)
268 ld.add_action(declare_use_respawn_cmd)
270 ld.add_action(world_sdf_xacro)
271 ld.add_action(remove_temp_sdf_file)
272 ld.add_action(gz_robot)
273 ld.add_action(gazebo_server)
274 ld.add_action(gazebo_client)
277 ld.add_action(start_robot_state_publisher_cmd)
278 ld.add_action(rviz_cmd)
279 ld.add_action(bringup_cmd)