Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
speed_zone_launch.py
1 # Copyright (c) 2025 Leander Stephen Desouza
2 #
3 # Licensed under the Apache License, Version 2.0 (the "License");
4 # you may not use this file except in compliance with the License.
5 # You may obtain a copy of the License at
6 #
7 # http://www.apache.org/licenses/LICENSE-2.0
8 #
9 # Unless required by applicable law or agreed to in writing, software
10 # distributed under the License is distributed on an "AS IS" BASIS,
11 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 # See the License for the specific language governing permissions and
13 # limitations under the License.
14 
15 import os
16 
17 from ament_index_python.packages import get_package_share_directory
18 from launch import LaunchDescription
19 from launch.actions import DeclareLaunchArgument, GroupAction, SetEnvironmentVariable
20 from launch.conditions import IfCondition
21 from launch.substitutions import LaunchConfiguration, PythonExpression
22 from launch_ros.actions import LoadComposableNodes, Node, PushROSNamespace, SetParameter
23 from launch_ros.descriptions import ComposableNode, ParameterFile
24 from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml
25 
26 
27 def generate_launch_description() -> LaunchDescription:
28  # Get the launch directory
29  bringup_dir = get_package_share_directory('nav2_bringup')
30 
31  namespace = LaunchConfiguration('namespace')
32  speed_mask_yaml_file = LaunchConfiguration('speed_mask')
33  use_sim_time = LaunchConfigAsBool('use_sim_time')
34  autostart = LaunchConfigAsBool('autostart')
35  params_file = LaunchConfiguration('params_file')
36  use_composition = LaunchConfigAsBool('use_composition')
37  container_name = LaunchConfiguration('container_name')
38  container_name_full = (namespace, '/', container_name)
39  use_respawn = LaunchConfigAsBool('use_respawn')
40  use_speed_zones = LaunchConfigAsBool('use_speed_zones')
41  log_level = LaunchConfiguration('log_level')
42 
43  lifecycle_nodes = ['speed_filter_mask_server', 'speed_costmap_filter_info_server']
44 
45  # Map fully qualified names to relative ones so the node's namespace can be prepended.
46  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
47 
48  yaml_substitutions = {
49  'SPEED_ZONE_ENABLED': use_speed_zones,
50  }
51 
52  configured_params = ParameterFile(
53  RewrittenYaml(
54  source_file=params_file,
55  root_key=namespace,
56  param_rewrites={},
57  value_rewrites=yaml_substitutions,
58  convert_types=True,
59  ),
60  allow_substs=True,
61  )
62 
63  stdout_linebuf_envvar = SetEnvironmentVariable(
64  'RCUTILS_LOGGING_BUFFERED_STREAM', '1'
65  )
66 
67  declare_namespace_cmd = DeclareLaunchArgument(
68  'namespace', default_value='', description='Top-level namespace'
69  )
70 
71  declare_speed_mask_yaml_cmd = DeclareLaunchArgument(
72  'speed_mask',
73  default_value='',
74  description='Full path to speed mask yaml file to load',
75  )
76 
77  declare_use_sim_time_cmd = DeclareLaunchArgument(
78  'use_sim_time',
79  default_value='false',
80  description='Use simulation (Gazebo) clock if true',
81  )
82 
83  declare_params_file_cmd = DeclareLaunchArgument(
84  'params_file',
85  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
86  description='Full path to the ROS2 parameters file to use for all launched nodes',
87  )
88 
89  declare_use_composition_cmd = DeclareLaunchArgument(
90  'use_composition',
91  default_value='False',
92  description='Use composed bringup if True',
93  )
94 
95  declare_container_name_cmd = DeclareLaunchArgument(
96  'container_name',
97  default_value='nav2_container',
98  description='the name of container that nodes will load in if use composition',
99  )
100 
101  declare_use_respawn_cmd = DeclareLaunchArgument(
102  'use_respawn',
103  default_value='False',
104  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
105  )
106 
107  declare_use_speed_zones_cmd = DeclareLaunchArgument(
108  'use_speed_zones', default_value='True',
109  description='Whether to enable speed zones or not'
110  )
111 
112  declare_log_level_cmd = DeclareLaunchArgument(
113  'log_level', default_value='info', description='log level'
114  )
115 
116  load_nodes = GroupAction(
117  condition=IfCondition(PythonExpression(['not ', use_composition])),
118  actions=[
119  PushROSNamespace(namespace),
120  SetParameter('use_sim_time', use_sim_time),
121  Node(
122  condition=IfCondition(use_speed_zones),
123  package='nav2_map_server',
124  executable='map_server',
125  name='speed_filter_mask_server',
126  output='screen',
127  respawn=use_respawn,
128  respawn_delay=2.0,
129  parameters=[configured_params, {'yaml_filename': speed_mask_yaml_file}],
130  arguments=['--ros-args', '--log-level', log_level],
131  remappings=remappings,
132  ),
133  Node(
134  condition=IfCondition(use_speed_zones),
135  package='nav2_map_server',
136  executable='costmap_filter_info_server',
137  name='speed_costmap_filter_info_server',
138  output='screen',
139  respawn=use_respawn,
140  respawn_delay=2.0,
141  parameters=[configured_params],
142  arguments=['--ros-args', '--log-level', log_level],
143  remappings=remappings,
144  ),
145  Node(
146  package='nav2_lifecycle_manager',
147  executable='lifecycle_manager',
148  name='lifecycle_manager_speed_zone',
149  output='screen',
150  arguments=['--ros-args', '--log-level', log_level],
151  parameters=[{'autostart': autostart}, {'node_names': lifecycle_nodes}],
152  ),
153  ],
154  )
155  # LoadComposableNode for map server twice depending if we should use the
156  # value of map from a CLI or launch default or user defined value in the
157  # yaml configuration file. They are separated since the conditions
158  # currently only work on the LoadComposableNodes commands and not on the
159  # ComposableNode node function itself
160  load_composable_nodes = GroupAction(
161  condition=IfCondition(use_composition),
162  actions=[
163  PushROSNamespace(namespace),
164  SetParameter('use_sim_time', use_sim_time),
165  LoadComposableNodes(
166  target_container=container_name_full,
167  condition=IfCondition(use_speed_zones),
168  composable_node_descriptions=[
169  ComposableNode(
170  package='nav2_map_server',
171  plugin='nav2_map_server::MapServer',
172  name='speed_filter_mask_server',
173  parameters=[
174  configured_params,
175  {'yaml_filename': speed_mask_yaml_file}
176  ],
177  remappings=remappings,
178  ),
179  ComposableNode(
180  package='nav2_map_server',
181  plugin='nav2_map_server::CostmapFilterInfoServer',
182  name='speed_costmap_filter_info_server',
183  parameters=[configured_params],
184  remappings=remappings,
185  ),
186  ],
187  ),
188 
189  LoadComposableNodes(
190  target_container=container_name_full,
191  composable_node_descriptions=[
192  ComposableNode(
193  package='nav2_lifecycle_manager',
194  plugin='nav2_lifecycle_manager::LifecycleManager',
195  name='lifecycle_manager_speed_zone',
196  parameters=[
197  {'autostart': autostart, 'node_names': lifecycle_nodes}
198  ],
199  ),
200  ],
201  ),
202  ],
203  )
204 
205  # Create the launch description and populate
206  ld = LaunchDescription()
207 
208  # Set environment variables
209  ld.add_action(stdout_linebuf_envvar)
210 
211  # Declare the launch options
212  ld.add_action(declare_namespace_cmd)
213  ld.add_action(declare_speed_mask_yaml_cmd)
214  ld.add_action(declare_use_sim_time_cmd)
215  ld.add_action(declare_params_file_cmd)
216  ld.add_action(declare_use_composition_cmd)
217  ld.add_action(declare_container_name_cmd)
218  ld.add_action(declare_use_respawn_cmd)
219  ld.add_action(declare_use_speed_zones_cmd)
220  ld.add_action(declare_log_level_cmd)
221 
222  # Add the actions to launch all of the map modifier nodes
223  ld.add_action(load_nodes)
224  ld.add_action(load_composable_nodes)
225 
226  return ld