17 from ament_index_python.packages
import get_package_share_directory
18 from launch
import LaunchDescription
19 from launch.actions
import (DeclareLaunchArgument, GroupAction, IncludeLaunchDescription,
20 SetEnvironmentVariable)
21 from launch.conditions
import IfCondition
22 from launch.launch_description_sources
import PythonLaunchDescriptionSource
23 from launch.substitutions
import LaunchConfiguration, PythonExpression
24 from launch_ros.actions
import Node
25 from launch_ros.descriptions
import ParameterFile
29 def generate_launch_description() -> LaunchDescription:
31 bringup_dir = get_package_share_directory(
'nav2_bringup')
32 launch_dir = os.path.join(bringup_dir,
'launch')
35 namespace = LaunchConfiguration(
'namespace')
36 slam = LaunchConfigAsBool(
'slam')
37 map_yaml_file = LaunchConfiguration(
'map')
38 keepout_mask_yaml_file = LaunchConfiguration(
'keepout_mask')
39 speed_mask_yaml_file = LaunchConfiguration(
'speed_mask')
40 graph_filepath = LaunchConfiguration(
'graph')
41 use_sim_time = LaunchConfigAsBool(
'use_sim_time')
42 params_file = LaunchConfiguration(
'params_file')
43 autostart = LaunchConfigAsBool(
'autostart')
44 use_composition = LaunchConfigAsBool(
'use_composition')
45 use_respawn = LaunchConfigAsBool(
'use_respawn')
46 log_level = LaunchConfiguration(
'log_level')
47 use_localization = LaunchConfigAsBool(
'use_localization')
48 use_keepout_zones = LaunchConfigAsBool(
'use_keepout_zones')
49 use_speed_zones = LaunchConfigAsBool(
'use_speed_zones')
52 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
54 yaml_substitutions = {
55 'KEEPOUT_ZONE_ENABLED': use_keepout_zones,
56 'SPEED_ZONE_ENABLED': use_speed_zones,
59 configured_params = ParameterFile(
61 source_file=params_file,
64 value_rewrites=yaml_substitutions,
70 stdout_linebuf_envvar = SetEnvironmentVariable(
71 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
74 declare_namespace_cmd = DeclareLaunchArgument(
75 'namespace', default_value=
'', description=
'Top-level namespace'
78 declare_slam_cmd = DeclareLaunchArgument(
79 'slam', default_value=
'False', description=
'Whether run a SLAM'
82 declare_map_yaml_cmd = DeclareLaunchArgument(
83 'map', default_value=
'', description=
'Full path to map yaml file to load'
86 declare_keepout_mask_yaml_cmd = DeclareLaunchArgument(
87 'keepout_mask', default_value=
'',
88 description=
'Full path to keepout mask yaml file to load'
91 declare_speed_mask_yaml_cmd = DeclareLaunchArgument(
92 'speed_mask', default_value=
'',
93 description=
'Full path to speed mask yaml file to load'
96 declare_graph_file_cmd = DeclareLaunchArgument(
98 default_value=
'', description=
'Path to the graph file to load'
101 declare_use_localization_cmd = DeclareLaunchArgument(
102 'use_localization', default_value=
'True',
103 description=
'Whether to enable localization or not'
106 declare_use_keepout_zones_cmd = DeclareLaunchArgument(
107 'use_keepout_zones', default_value=
'True',
108 description=
'Whether to enable keepout zones or not'
111 declare_use_speed_zones_cmd = DeclareLaunchArgument(
112 'use_speed_zones', default_value=
'True',
113 description=
'Whether to enable speed zones or not'
116 declare_use_sim_time_cmd = DeclareLaunchArgument(
118 default_value=
'false',
119 description=
'Use simulation (Gazebo) clock if true',
122 declare_params_file_cmd = DeclareLaunchArgument(
124 default_value=os.path.join(bringup_dir,
'params',
'nav2_params.yaml'),
125 description=
'Full path to the ROS2 parameters file to use for all launched nodes',
128 declare_autostart_cmd = DeclareLaunchArgument(
130 default_value=
'true',
131 description=
'Automatically startup the nav2 stack',
134 declare_use_composition_cmd = DeclareLaunchArgument(
136 default_value=
'True',
137 description=
'Whether to use composed bringup',
140 declare_use_respawn_cmd = DeclareLaunchArgument(
142 default_value=
'False',
143 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
146 declare_log_level_cmd = DeclareLaunchArgument(
147 'log_level', default_value=
'info', description=
'log level'
151 bringup_cmd_group = GroupAction(
154 condition=IfCondition(use_composition),
155 name=
'nav2_container',
157 package=
'rclcpp_components',
158 executable=
'component_container_isolated',
159 parameters=[configured_params, {
'autostart': autostart}],
160 arguments=[
'--ros-args',
'--log-level', log_level],
161 remappings=remappings,
164 IncludeLaunchDescription(
165 PythonLaunchDescriptionSource(
166 os.path.join(launch_dir,
'slam_launch.py')
168 condition=IfCondition(PythonExpression([slam,
' and ', use_localization])),
170 'namespace': namespace,
171 'use_sim_time': use_sim_time,
172 'autostart': autostart,
173 'use_respawn': use_respawn,
174 'params_file': params_file,
177 IncludeLaunchDescription(
178 PythonLaunchDescriptionSource(
179 os.path.join(launch_dir,
'localization_launch.py')
181 condition=IfCondition(PythonExpression([
'not ', slam,
' and ', use_localization])),
183 'namespace': namespace,
184 'map': map_yaml_file,
185 'use_sim_time': use_sim_time,
186 'autostart': autostart,
187 'params_file': params_file,
188 'use_composition': use_composition,
189 'use_respawn': use_respawn,
190 'container_name':
'nav2_container',
194 IncludeLaunchDescription(
195 PythonLaunchDescriptionSource(
196 os.path.join(launch_dir,
'keepout_zone_launch.py')
198 condition=IfCondition(use_keepout_zones),
200 'namespace': namespace,
201 'keepout_mask': keepout_mask_yaml_file,
202 'use_sim_time': use_sim_time,
203 'params_file': params_file,
204 'use_composition': use_composition,
205 'use_respawn': use_respawn,
206 'container_name':
'nav2_container',
210 IncludeLaunchDescription(
211 PythonLaunchDescriptionSource(
212 os.path.join(launch_dir,
'speed_zone_launch.py')
214 condition=IfCondition(use_speed_zones),
216 'namespace': namespace,
217 'speed_mask': speed_mask_yaml_file,
218 'use_sim_time': use_sim_time,
219 'params_file': params_file,
220 'use_composition': use_composition,
221 'use_respawn': use_respawn,
222 'container_name':
'nav2_container',
226 IncludeLaunchDescription(
227 PythonLaunchDescriptionSource(
228 os.path.join(launch_dir,
'navigation_launch.py')
231 'namespace': namespace,
232 'use_sim_time': use_sim_time,
233 'autostart': autostart,
234 'graph': graph_filepath,
235 'params_file': params_file,
236 'use_composition': use_composition,
237 'use_respawn': use_respawn,
238 'use_keepout_zones': use_keepout_zones,
239 'use_speed_zones': use_speed_zones,
240 'container_name':
'nav2_container',
247 ld = LaunchDescription()
250 ld.add_action(stdout_linebuf_envvar)
253 ld.add_action(declare_namespace_cmd)
254 ld.add_action(declare_slam_cmd)
255 ld.add_action(declare_map_yaml_cmd)
256 ld.add_action(declare_keepout_mask_yaml_cmd)
257 ld.add_action(declare_speed_mask_yaml_cmd)
258 ld.add_action(declare_graph_file_cmd)
259 ld.add_action(declare_use_sim_time_cmd)
260 ld.add_action(declare_params_file_cmd)
261 ld.add_action(declare_autostart_cmd)
262 ld.add_action(declare_use_composition_cmd)
263 ld.add_action(declare_use_respawn_cmd)
264 ld.add_action(declare_log_level_cmd)
265 ld.add_action(declare_use_localization_cmd)
266 ld.add_action(declare_use_keepout_zones_cmd)
267 ld.add_action(declare_use_speed_zones_cmd)
270 ld.add_action(bringup_cmd_group)