15 """This is all-in-one launch script intended for use by nav2 developers."""
19 from ament_index_python.packages
import get_package_share_directory
21 from launch
import LaunchDescription
22 from launch.actions
import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
23 from launch.conditions
import IfCondition
24 from launch.launch_description_sources
import PythonLaunchDescriptionSource
25 from launch.substitutions
import LaunchConfiguration, PythonExpression
26 from launch_ros.actions
import Node
29 def generate_launch_description():
31 bringup_dir = get_package_share_directory(
'nav2_bringup')
32 launch_dir = os.path.join(bringup_dir,
'launch')
35 slam = LaunchConfiguration(
'slam')
36 namespace = LaunchConfiguration(
'namespace')
37 use_namespace = LaunchConfiguration(
'use_namespace')
38 map_yaml_file = LaunchConfiguration(
'map')
39 use_sim_time = LaunchConfiguration(
'use_sim_time')
40 params_file = LaunchConfiguration(
'params_file')
41 autostart = LaunchConfiguration(
'autostart')
42 use_composition = LaunchConfiguration(
'use_composition')
43 use_respawn = LaunchConfiguration(
'use_respawn')
46 rviz_config_file = LaunchConfiguration(
'rviz_config_file')
47 use_simulator = LaunchConfiguration(
'use_simulator')
48 use_robot_state_pub = LaunchConfiguration(
'use_robot_state_pub')
49 use_rviz = LaunchConfiguration(
'use_rviz')
50 headless = LaunchConfiguration(
'headless')
51 world = LaunchConfiguration(
'world')
52 pose = {
'x': LaunchConfiguration(
'x_pose', default=
'-2.00'),
53 'y': LaunchConfiguration(
'y_pose', default=
'-0.50'),
54 'z': LaunchConfiguration(
'z_pose', default=
'0.01'),
55 'R': LaunchConfiguration(
'roll', default=
'0.00'),
56 'P': LaunchConfiguration(
'pitch', default=
'0.00'),
57 'Y': LaunchConfiguration(
'yaw', default=
'0.00')}
58 robot_name = LaunchConfiguration(
'robot_name')
59 robot_sdf = LaunchConfiguration(
'robot_sdf')
67 remappings = [(
'/tf',
'tf'),
68 (
'/tf_static',
'tf_static')]
71 declare_namespace_cmd = DeclareLaunchArgument(
74 description=
'Top-level namespace')
76 declare_use_namespace_cmd = DeclareLaunchArgument(
78 default_value=
'false',
79 description=
'Whether to apply a namespace to the navigation stack')
81 declare_slam_cmd = DeclareLaunchArgument(
83 default_value=
'False',
84 description=
'Whether run a SLAM')
86 declare_map_yaml_cmd = DeclareLaunchArgument(
88 default_value=os.path.join(
89 bringup_dir,
'maps',
'turtlebot3_world.yaml'),
90 description=
'Full path to map file to load')
92 declare_use_sim_time_cmd = DeclareLaunchArgument(
95 description=
'Use simulation (Gazebo) clock if true')
97 declare_params_file_cmd = DeclareLaunchArgument(
99 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
100 description=
'Full path to the ROS2 parameters file to use for all launched nodes')
102 declare_autostart_cmd = DeclareLaunchArgument(
103 'autostart', default_value=
'true',
104 description=
'Automatically startup the nav2 stack')
106 declare_use_composition_cmd = DeclareLaunchArgument(
107 'use_composition', default_value=
'True',
108 description=
'Whether to use composed bringup')
110 declare_use_respawn_cmd = DeclareLaunchArgument(
111 'use_respawn', default_value=
'False',
112 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.')
114 declare_rviz_config_file_cmd = DeclareLaunchArgument(
116 default_value=os.path.join(
117 bringup_dir,
'rviz',
'nav2_default_view.rviz'),
118 description=
'Full path to the RVIZ config file to use')
120 declare_use_simulator_cmd = DeclareLaunchArgument(
122 default_value=
'True',
123 description=
'Whether to start the simulator')
125 declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
126 'use_robot_state_pub',
127 default_value=
'True',
128 description=
'Whether to start the robot state publisher')
130 declare_use_rviz_cmd = DeclareLaunchArgument(
132 default_value=
'True',
133 description=
'Whether to start RVIZ')
135 declare_simulator_cmd = DeclareLaunchArgument(
137 default_value=
'True',
138 description=
'Whether to execute gzclient)')
140 declare_world_cmd = DeclareLaunchArgument(
146 default_value=os.path.join(bringup_dir,
'worlds',
'world_only.model'),
147 description=
'Full path to world model file to load')
149 declare_robot_name_cmd = DeclareLaunchArgument(
151 default_value=
'turtlebot3_waffle',
152 description=
'name of the robot')
154 declare_robot_sdf_cmd = DeclareLaunchArgument(
156 default_value=os.path.join(bringup_dir,
'worlds',
'waffle.model'),
157 description=
'Full path to robot sdf file to spawn the robot in gazebo')
160 start_gazebo_server_cmd = ExecuteProcess(
161 condition=IfCondition(use_simulator),
162 cmd=[
'gzserver',
'-s',
'libgazebo_ros_init.so',
163 '-s',
'libgazebo_ros_factory.so', world],
164 cwd=[launch_dir], output=
'screen')
166 start_gazebo_client_cmd = ExecuteProcess(
167 condition=IfCondition(PythonExpression(
168 [use_simulator,
' and not ', headless])),
170 cwd=[launch_dir], output=
'screen')
172 urdf = os.path.join(bringup_dir,
'urdf',
'turtlebot3_waffle.urdf')
173 with open(urdf,
'r')
as infp:
174 robot_description = infp.read()
176 start_robot_state_publisher_cmd = Node(
177 condition=IfCondition(use_robot_state_pub),
178 package=
'robot_state_publisher',
179 executable=
'robot_state_publisher',
180 name=
'robot_state_publisher',
183 parameters=[{
'use_sim_time': use_sim_time,
184 'robot_description': robot_description}],
185 remappings=remappings)
187 start_gazebo_spawner_cmd = Node(
188 package=
'gazebo_ros',
189 executable=
'spawn_entity.py',
192 '-entity', robot_name,
194 '-robot_namespace', namespace,
195 '-x', pose[
'x'],
'-y', pose[
'y'],
'-z', pose[
'z'],
196 '-R', pose[
'R'],
'-P', pose[
'P'],
'-Y', pose[
'Y']])
198 rviz_cmd = IncludeLaunchDescription(
199 PythonLaunchDescriptionSource(
200 os.path.join(launch_dir,
'rviz_launch.py')),
201 condition=IfCondition(use_rviz),
202 launch_arguments={
'namespace': namespace,
203 'use_namespace': use_namespace,
204 'rviz_config': rviz_config_file}.items())
206 bringup_cmd = IncludeLaunchDescription(
207 PythonLaunchDescriptionSource(
208 os.path.join(launch_dir,
'bringup_launch.py')),
209 launch_arguments={
'namespace': namespace,
210 'use_namespace': use_namespace,
212 'map': map_yaml_file,
213 'use_sim_time': use_sim_time,
214 'params_file': params_file,
215 'autostart': autostart,
216 'use_composition': use_composition,
217 'use_respawn': use_respawn}.items())
220 ld = LaunchDescription()
223 ld.add_action(declare_namespace_cmd)
224 ld.add_action(declare_use_namespace_cmd)
225 ld.add_action(declare_slam_cmd)
226 ld.add_action(declare_map_yaml_cmd)
227 ld.add_action(declare_use_sim_time_cmd)
228 ld.add_action(declare_params_file_cmd)
229 ld.add_action(declare_autostart_cmd)
230 ld.add_action(declare_use_composition_cmd)
232 ld.add_action(declare_rviz_config_file_cmd)
233 ld.add_action(declare_use_simulator_cmd)
234 ld.add_action(declare_use_robot_state_pub_cmd)
235 ld.add_action(declare_use_rviz_cmd)
236 ld.add_action(declare_simulator_cmd)
237 ld.add_action(declare_world_cmd)
238 ld.add_action(declare_robot_name_cmd)
239 ld.add_action(declare_robot_sdf_cmd)
240 ld.add_action(declare_use_respawn_cmd)
243 ld.add_action(start_gazebo_server_cmd)
244 ld.add_action(start_gazebo_client_cmd)
245 ld.add_action(start_gazebo_spawner_cmd)
248 ld.add_action(start_robot_state_publisher_cmd)
249 ld.add_action(rviz_cmd)
250 ld.add_action(bringup_cmd)