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
22 from launch
import LaunchDescription
23 from launch.actions
import (
24 DeclareLaunchArgument,
26 IncludeLaunchDescription,
30 from launch.conditions
import IfCondition
31 from launch.event_handlers
import OnShutdown
32 from launch.launch_description_sources
import PythonLaunchDescriptionSource
33 from launch.substitutions
import LaunchConfiguration, PythonExpression
35 from launch_ros.actions
import Node
38 def generate_launch_description():
40 bringup_dir = get_package_share_directory(
'nav2_bringup')
41 launch_dir = os.path.join(bringup_dir,
'launch')
42 sim_dir = get_package_share_directory(
'nav2_minimal_tb3_sim')
45 slam = LaunchConfiguration(
'slam')
46 namespace = LaunchConfiguration(
'namespace')
47 use_namespace = LaunchConfiguration(
'use_namespace')
48 map_yaml_file = LaunchConfiguration(
'map')
49 use_sim_time = LaunchConfiguration(
'use_sim_time')
50 params_file = LaunchConfiguration(
'params_file')
51 autostart = LaunchConfiguration(
'autostart')
52 use_composition = LaunchConfiguration(
'use_composition')
53 use_respawn = LaunchConfiguration(
'use_respawn')
56 rviz_config_file = LaunchConfiguration(
'rviz_config_file')
57 use_simulator = LaunchConfiguration(
'use_simulator')
58 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
59 use_rviz = LaunchConfiguration(
'use_rviz')
60 headless = LaunchConfiguration(
'headless')
61 world = LaunchConfiguration(
'world')
63 'x': LaunchConfiguration(
'x_pose', default=
'-2.00'),
64 'y': LaunchConfiguration(
'y_pose', default=
'-0.50'),
65 'z': LaunchConfiguration(
'z_pose', default=
'0.01'),
66 'R': LaunchConfiguration(
'roll', default=
'0.00'),
67 'P': LaunchConfiguration(
'pitch', default=
'0.00'),
68 'Y': LaunchConfiguration(
'yaw', default=
'0.00'),
70 robot_name = LaunchConfiguration(
'robot_name')
71 robot_sdf = LaunchConfiguration(
'robot_sdf')
73 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
76 declare_namespace_cmd = DeclareLaunchArgument(
77 'namespace', default_value=
'', description=
'Top-level namespace'
80 declare_use_namespace_cmd = DeclareLaunchArgument(
82 default_value=
'false',
83 description=
'Whether to apply a namespace to the navigation stack',
86 declare_slam_cmd = DeclareLaunchArgument(
87 'slam', default_value=
'False', description=
'Whether run a SLAM'
90 declare_map_yaml_cmd = DeclareLaunchArgument(
92 default_value=os.path.join(bringup_dir,
'maps',
'tb3_sandbox.yaml'),
95 declare_use_sim_time_cmd = DeclareLaunchArgument(
98 description=
'Use simulation (Gazebo) clock if true',
101 declare_params_file_cmd = DeclareLaunchArgument(
103 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
104 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
107 declare_autostart_cmd = DeclareLaunchArgument(
109 default_value=
'true',
110 description=
'Automatically startup the nav2 stack',
113 declare_use_composition_cmd = DeclareLaunchArgument(
115 default_value=
'True',
116 description=
'Whether to use composed bringup',
119 declare_use_respawn_cmd = DeclareLaunchArgument(
121 default_value=
'False',
122 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
125 declare_rviz_config_file_cmd = DeclareLaunchArgument(
127 default_value=os.path.join(bringup_dir,
'rviz',
'nav2_default_view.rviz'),
128 description=
'Full path to the RVIZ config file to use',
131 declare_use_simulator_cmd = DeclareLaunchArgument(
133 default_value=
'True',
134 description=
'Whether to start the simulator',
137 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
138 'use_robot_state_pub',
139 default_value=
'True',
140 description=
'Whether to start the robot state publisher',
143 declare_use_rviz_cmd = DeclareLaunchArgument(
144 'use_rviz', default_value=
'True', description=
'Whether to start RVIZ'
147 declare_simulator_cmd = DeclareLaunchArgument(
148 'headless', default_value=
'True', description=
'Whether to execute gzclient)'
151 declare_world_cmd = DeclareLaunchArgument(
153 default_value=os.path.join(sim_dir,
'worlds',
'tb3_sandbox.sdf.xacro'),
154 description=
'Full path to world model file to load',
157 declare_robot_name_cmd = DeclareLaunchArgument(
158 'robot_name', default_value=
'turtlebot3_waffle', description=
'name of the robot'
161 declare_robot_sdf_cmd = DeclareLaunchArgument(
163 default_value=os.path.join(sim_dir,
'urdf',
'gz_waffle.sdf.xacro'),
164 description=
'Full path to robot sdf file to spawn the robot in gazebo',
167 urdf = os.path.join(sim_dir,
'urdf',
'turtlebot3_waffle.urdf')
168 with open(urdf,
'r')
as infp:
169 robot_description = infp.read()
171 start_robot_state_publisher_cmd = Node(
172 condition=IfCondition(use_robot_state_pub),
173 package=
'robot_state_publisher',
174 executable=
'robot_state_publisher',
175 name=
'robot_state_publisher',
179 {
'use_sim_time': use_sim_time,
'robot_description': robot_description}
181 remappings=remappings,
184 rviz_cmd = IncludeLaunchDescription(
185 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'rviz_launch.py')),
186 condition=IfCondition(use_rviz),
188 'namespace': namespace,
189 'use_namespace': use_namespace,
190 'use_sim_time': use_sim_time,
191 'rviz_config': rviz_config_file,
195 bringup_cmd = IncludeLaunchDescription(
196 PythonLaunchDescriptionSource(os.path.join(launch_dir,
'bringup_launch.py')),
198 'namespace': namespace,
199 'use_namespace': use_namespace,
201 'map': map_yaml_file,
202 'use_sim_time': use_sim_time,
203 'params_file': params_file,
204 'autostart': autostart,
205 'use_composition': use_composition,
206 'use_respawn': use_respawn,
214 world_sdf = tempfile.mktemp(prefix=
'nav2_', suffix=
'.sdf')
215 world_sdf_xacro = ExecuteProcess(
216 cmd=[
'xacro',
'-o', world_sdf, [
'headless:=', headless], world])
217 gazebo_server = ExecuteProcess(
218 cmd=[
'gz',
'sim',
'-r',
'-s', world_sdf],
220 condition=IfCondition(use_simulator)
223 remove_temp_sdf_file = RegisterEventHandler(event_handler=OnShutdown(
225 OpaqueFunction(function=
lambda _: os.remove(world_sdf))
228 gazebo_client = IncludeLaunchDescription(
229 PythonLaunchDescriptionSource(
230 os.path.join(get_package_share_directory(
'ros_gz_sim'),
234 condition=IfCondition(PythonExpression(
235 [use_simulator,
' and not ', headless])),
236 launch_arguments={
'gz_args': [
'-v4 -g ']}.items(),
239 gz_robot = IncludeLaunchDescription(
240 PythonLaunchDescriptionSource(
241 os.path.join(sim_dir,
'launch',
'spawn_tb3.launch.py')),
242 launch_arguments={
'namespace': namespace,
243 'use_sim_time': use_sim_time,
244 'robot_name': robot_name,
245 'robot_sdf': robot_sdf,
251 'yaw': pose[
'Y']}.items())
254 ld = LaunchDescription()
257 ld.add_action(declare_namespace_cmd)
258 ld.add_action(declare_use_namespace_cmd)
259 ld.add_action(declare_slam_cmd)
260 ld.add_action(declare_map_yaml_cmd)
261 ld.add_action(declare_use_sim_time_cmd)
262 ld.add_action(declare_params_file_cmd)
263 ld.add_action(declare_autostart_cmd)
264 ld.add_action(declare_use_composition_cmd)
266 ld.add_action(declare_rviz_config_file_cmd)
267 ld.add_action(declare_use_simulator_cmd)
268 ld.add_action(declare_use_robot_state_pub_cmd)
269 ld.add_action(declare_use_rviz_cmd)
270 ld.add_action(declare_simulator_cmd)
271 ld.add_action(declare_world_cmd)
272 ld.add_action(declare_robot_name_cmd)
273 ld.add_action(declare_robot_sdf_cmd)
274 ld.add_action(declare_use_respawn_cmd)
276 ld.add_action(world_sdf_xacro)
277 ld.add_action(remove_temp_sdf_file)
278 ld.add_action(gz_robot)
279 ld.add_action(gazebo_server)
280 ld.add_action(gazebo_client)
283 ld.add_action(start_robot_state_publisher_cmd)
284 ld.add_action(rviz_cmd)
285 ld.add_action(bringup_cmd)