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
27 def generate_launch_description() -> LaunchDescription:
29 bringup_dir = get_package_share_directory(
'nav2_bringup')
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')
43 lifecycle_nodes = [
'speed_filter_mask_server',
'speed_costmap_filter_info_server']
46 remappings = [(
'/tf',
'tf'), (
'/tf_static',
'tf_static')]
48 yaml_substitutions = {
49 'SPEED_ZONE_ENABLED': use_speed_zones,
52 configured_params = ParameterFile(
54 source_file=params_file,
57 value_rewrites=yaml_substitutions,
63 stdout_linebuf_envvar = SetEnvironmentVariable(
64 'RCUTILS_LOGGING_BUFFERED_STREAM',
'1'
67 declare_namespace_cmd = DeclareLaunchArgument(
68 'namespace', default_value=
'', description=
'Top-level namespace'
71 declare_speed_mask_yaml_cmd = DeclareLaunchArgument(
74 description=
'Full path to speed mask yaml file to load',
77 declare_use_sim_time_cmd = DeclareLaunchArgument(
79 default_value=
'false',
80 description=
'Use simulation (Gazebo) clock if true',
83 declare_params_file_cmd = DeclareLaunchArgument(
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',
89 declare_use_composition_cmd = DeclareLaunchArgument(
91 default_value=
'False',
92 description=
'Use composed bringup if True',
95 declare_container_name_cmd = DeclareLaunchArgument(
97 default_value=
'nav2_container',
98 description=
'the name of container that nodes will load in if use composition',
101 declare_use_respawn_cmd = DeclareLaunchArgument(
103 default_value=
'False',
104 description=
'Whether to respawn if a node crashes. Applied when composition is disabled.',
107 declare_use_speed_zones_cmd = DeclareLaunchArgument(
108 'use_speed_zones', default_value=
'True',
109 description=
'Whether to enable speed zones or not'
112 declare_log_level_cmd = DeclareLaunchArgument(
113 'log_level', default_value=
'info', description=
'log level'
116 load_nodes = GroupAction(
117 condition=IfCondition(PythonExpression([
'not ', use_composition])),
119 PushROSNamespace(namespace),
120 SetParameter(
'use_sim_time', use_sim_time),
122 condition=IfCondition(use_speed_zones),
123 package=
'nav2_map_server',
124 executable=
'map_server',
125 name=
'speed_filter_mask_server',
129 parameters=[configured_params, {
'yaml_filename': speed_mask_yaml_file}],
130 arguments=[
'--ros-args',
'--log-level', log_level],
131 remappings=remappings,
134 condition=IfCondition(use_speed_zones),
135 package=
'nav2_map_server',
136 executable=
'costmap_filter_info_server',
137 name=
'speed_costmap_filter_info_server',
141 parameters=[configured_params],
142 arguments=[
'--ros-args',
'--log-level', log_level],
143 remappings=remappings,
146 package=
'nav2_lifecycle_manager',
147 executable=
'lifecycle_manager',
148 name=
'lifecycle_manager_speed_zone',
150 arguments=[
'--ros-args',
'--log-level', log_level],
151 parameters=[{
'autostart': autostart}, {
'node_names': lifecycle_nodes}],
160 load_composable_nodes = GroupAction(
161 condition=IfCondition(use_composition),
163 PushROSNamespace(namespace),
164 SetParameter(
'use_sim_time', use_sim_time),
166 target_container=container_name_full,
167 condition=IfCondition(use_speed_zones),
168 composable_node_descriptions=[
170 package=
'nav2_map_server',
171 plugin=
'nav2_map_server::MapServer',
172 name=
'speed_filter_mask_server',
175 {
'yaml_filename': speed_mask_yaml_file}
177 remappings=remappings,
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,
190 target_container=container_name_full,
191 composable_node_descriptions=[
193 package=
'nav2_lifecycle_manager',
194 plugin=
'nav2_lifecycle_manager::LifecycleManager',
195 name=
'lifecycle_manager_speed_zone',
197 {
'autostart': autostart,
'node_names': lifecycle_nodes}
206 ld = LaunchDescription()
209 ld.add_action(stdout_linebuf_envvar)
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)
223 ld.add_action(load_nodes)
224 ld.add_action(load_composable_nodes)