19 from ament_index_python.packages
import get_package_share_directory
20 from launch
import LaunchDescription
21 from launch.actions
import DeclareLaunchArgument, GroupAction
22 from launch.conditions
import IfCondition
23 from launch.substitutions
import LaunchConfiguration, NotEqualsSubstitution, PythonExpression
24 from launch_ros.actions
import LoadComposableNodes, Node, PushROSNamespace, SetParameter
25 from launch_ros.descriptions
import ComposableNode, ParameterFile
29 def generate_launch_description() -> LaunchDescription:
31 package_dir = get_package_share_directory(
'nav2_map_server')
34 lifecycle_nodes = [
'vector_object_server',
'costmap_filter_info_server']
35 remappings = [(
'/tf',
'tf'),
36 (
'/tf_static',
'tf_static')]
40 namespace = LaunchConfiguration(
'namespace')
41 use_sim_time = LaunchConfiguration(
'use_sim_time')
42 params_file = LaunchConfiguration(
'params_file')
43 autostart = LaunchConfiguration(
'autostart')
44 use_composition = LaunchConfiguration(
'use_composition')
45 container_name = LaunchConfiguration(
'container_name')
48 declare_namespace_cmd = DeclareLaunchArgument(
51 description=
'Top-level namespace')
53 declare_use_sim_time_cmd = DeclareLaunchArgument(
56 description=
'Use simulation (Gazebo) clock if true')
58 declare_params_file_cmd = DeclareLaunchArgument(
60 default_value=os.path.join(package_dir,
'params',
'vector_object_server_params.yaml'),
61 description=
'Full path to the ROS2 parameters file to use for all launched nodes')
63 declare_autostart_cmd = DeclareLaunchArgument(
64 'autostart', default_value=
'True',
65 description=
'Automatically startup Vector Object server')
67 declare_use_composition_cmd = DeclareLaunchArgument(
68 'use_composition', default_value=
'True',
69 description=
'Use composed bringup if True')
71 declare_container_name_cmd = DeclareLaunchArgument(
72 'container_name', default_value=
'nav2_container',
73 description=
'the name of container that nodes will load in if use composition')
75 configured_params = ParameterFile(
77 source_file=params_file,
86 load_nodes = GroupAction(
87 condition=IfCondition(PythonExpression([
'not ', use_composition])),
89 SetParameter(
'use_sim_time', use_sim_time),
91 condition=IfCondition(NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')),
94 package=
'nav2_map_server',
95 executable=
'vector_object_server',
96 name=
'vector_object_server',
99 parameters=[configured_params],
100 remappings=remappings),
102 package=
'nav2_map_server',
103 executable=
'costmap_filter_info_server',
104 name=
'costmap_filter_info_server',
107 parameters=[configured_params],
108 remappings=remappings),
110 package=
'nav2_lifecycle_manager',
111 executable=
'lifecycle_manager',
112 name=
'lifecycle_manager_vo_server',
115 parameters=[{
'autostart': autostart},
116 {
'node_names': lifecycle_nodes}],
117 remappings=remappings)
121 load_composable_nodes = GroupAction(
122 condition=IfCondition(use_composition),
124 SetParameter(
'use_sim_time', use_sim_time),
126 condition=IfCondition(NotEqualsSubstitution(LaunchConfiguration(
'namespace'),
'')),
127 namespace=namespace),
129 target_container=container_name,
130 composable_node_descriptions=[
132 package=
'nav2_map_server',
133 plugin=
'nav2_map_server::VectorObjectServer',
134 name=
'vector_object_server',
135 parameters=[configured_params],
136 remappings=remappings),
138 package=
'nav2_map_server',
139 plugin=
'nav2_map_server::CostmapFilterInfoServer',
140 name=
'costmap_filter_info_server',
141 parameters=[configured_params],
142 remappings=remappings),
144 package=
'nav2_lifecycle_manager',
145 plugin=
'nav2_lifecycle_manager::LifecycleManager',
146 name=
'lifecycle_manager_vo_server',
147 parameters=[{
'autostart': autostart},
148 {
'node_names': lifecycle_nodes}],
149 remappings=remappings)
155 ld = LaunchDescription()
158 ld.add_action(declare_namespace_cmd)
159 ld.add_action(declare_use_sim_time_cmd)
160 ld.add_action(declare_params_file_cmd)
161 ld.add_action(declare_autostart_cmd)
162 ld.add_action(declare_use_composition_cmd)
163 ld.add_action(declare_container_name_cmd)
166 ld.add_action(load_nodes)
167 ld.add_action(load_composable_nodes)