17 from ament_index_python.packages
import get_package_share_directory
19 from launch
import LaunchDescription
20 from launch.actions
import (
21 DeclareLaunchArgument,
23 IncludeLaunchDescription,
24 SetEnvironmentVariable,
26 from launch.conditions
import IfCondition
27 from launch.launch_description_sources
import PythonLaunchDescriptionSource
28 from launch.substitutions
import LaunchConfiguration, PythonExpression
29 from launch_ros.actions
import Node
30 from launch_ros.actions
import PushROSNamespace
31 from launch_ros.descriptions
import ParameterFile
35 def generate_launch_description():
37 bringup_dir = get_package_share_directory(
'nav2_bringup')
38 launch_dir = os.path.join(bringup_dir,
'launch')
41 namespace = LaunchConfiguration(
'namespace')
42 use_namespace = LaunchConfiguration(
'use_namespace')
43 slam = LaunchConfiguration(
'slam')
44 map_yaml_file = LaunchConfiguration(
'map')
45 use_sim_time = LaunchConfiguration(
'use_sim_time')
46 params_file = LaunchConfiguration(
'params_file')
47 autostart = LaunchConfiguration(
'autostart')
48 use_composition = LaunchConfiguration(
'use_composition')
49 use_respawn = LaunchConfiguration(
'use_respawn')
50 log_level = LaunchConfiguration(
'log_level')
51 use_localization = LaunchConfiguration(
'use_localization')
59 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
65 params_file = ReplaceString(
66 source_file=params_file,
67 replacements={
'<robot_namespace>': (
'/', namespace)},
68 condition=IfCondition(use_namespace),
71 configured_params = ParameterFile(
73 source_file=params_file,
81 stdout_linebuf_envvar = SetEnvironmentVariable(
82 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
85 declare_namespace_cmd = DeclareLaunchArgument(
86 'namespace', default_value=
'', description=
'Top-level namespace'
89 declare_use_namespace_cmd = DeclareLaunchArgument(
91 default_value=
'false',
92 description=
'Whether to apply a namespace to the navigation stack',
95 declare_slam_cmd = DeclareLaunchArgument(
96 'slam', default_value=
'False', description=
'Whether run a SLAM'
99 declare_map_yaml_cmd = DeclareLaunchArgument(
100 'map', default_value=
'', description=
'Full path to map yaml file to load'
103 declare_use_localization_cmd = DeclareLaunchArgument(
104 'use_localization', default_value=
'True',
105 description=
'Whether to enable localization or not'
108 declare_use_sim_time_cmd = DeclareLaunchArgument(
110 default_value=
'false',
111 description=
'Use simulation (Gazebo) clock if true',
114 declare_params_file_cmd = DeclareLaunchArgument(
116 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
117 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
120 declare_autostart_cmd = DeclareLaunchArgument(
122 default_value=
'true',
123 description=
'Automatically startup the nav2 stack',
126 declare_use_composition_cmd = DeclareLaunchArgument(
128 default_value=
'True',
129 description=
'Whether to use composed bringup',
132 declare_use_respawn_cmd = DeclareLaunchArgument(
134 default_value=
'False',
135 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
138 declare_log_level_cmd = DeclareLaunchArgument(
139 'log_level', default_value=
'info', description=
'log level'
143 bringup_cmd_group = GroupAction(
145 PushROSNamespace(condition=IfCondition(use_namespace), namespace=namespace),
147 condition=IfCondition(use_composition),
148 name=
'nav2_container',
149 package=
'rclcpp_components',
150 executable=
'component_container_isolated',
151 parameters=[configured_params, {
'autostart': autostart}],
152 arguments=[
'--ros-args',
'--log-level', log_level],
153 remappings=remappings,
156 IncludeLaunchDescription(
157 PythonLaunchDescriptionSource(
158 os.path.join(launch_dir,
'slam_launch.py')
160 condition=IfCondition(PythonExpression([slam,
' and ', use_localization])),
162 'namespace': namespace,
163 'use_sim_time': use_sim_time,
164 'autostart': autostart,
165 'use_respawn': use_respawn,
166 'params_file': params_file,
169 IncludeLaunchDescription(
170 PythonLaunchDescriptionSource(
171 os.path.join(launch_dir,
'localization_launch.py')
173 condition=IfCondition(PythonExpression([
'not ', slam,
' and ', use_localization])),
175 'namespace': namespace,
176 'map': map_yaml_file,
177 'use_sim_time': use_sim_time,
178 'autostart': autostart,
179 'params_file': params_file,
180 'use_composition': use_composition,
181 'use_respawn': use_respawn,
182 'container_name':
'nav2_container',
185 IncludeLaunchDescription(
186 PythonLaunchDescriptionSource(
187 os.path.join(launch_dir,
'navigation_launch.py')
190 'namespace': namespace,
191 'use_sim_time': use_sim_time,
192 'autostart': autostart,
193 'params_file': params_file,
194 'use_composition': use_composition,
195 'use_respawn': use_respawn,
196 'container_name':
'nav2_container',
203 ld = LaunchDescription()
206 ld.add_action(stdout_linebuf_envvar)
209 ld.add_action(declare_namespace_cmd)
210 ld.add_action(declare_use_namespace_cmd)
211 ld.add_action(declare_slam_cmd)
212 ld.add_action(declare_map_yaml_cmd)
213 ld.add_action(declare_use_sim_time_cmd)
214 ld.add_action(declare_params_file_cmd)
215 ld.add_action(declare_autostart_cmd)
216 ld.add_action(declare_use_composition_cmd)
217 ld.add_action(declare_use_respawn_cmd)
218 ld.add_action(declare_log_level_cmd)
219 ld.add_action(declare_use_localization_cmd)
222 ld.add_action(bringup_cmd_group)