Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
vector_object_server.launch.py
1 #!/usr/bin/env python3
2 
3 # Copyright (c) 2023 Samsung R&D Institute Russia
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 import os
18 
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
26 from nav2_common.launch import RewrittenYaml
27 
28 
29 def generate_launch_description() -> LaunchDescription:
30  # Environment
31  package_dir = get_package_share_directory('nav2_map_server')
32 
33  # Constant parameters
34  lifecycle_nodes = ['vector_object_server', 'costmap_filter_info_server']
35  remappings = [('/tf', 'tf'),
36  ('/tf_static', 'tf_static')]
37 
38  # Launch arguments
39  # 1. Create the launch configuration variables
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')
46 
47  # 2. Declare the launch arguments
48  declare_namespace_cmd = DeclareLaunchArgument(
49  'namespace',
50  default_value='',
51  description='Top-level namespace')
52 
53  declare_use_sim_time_cmd = DeclareLaunchArgument(
54  'use_sim_time',
55  default_value='True',
56  description='Use simulation (Gazebo) clock if true')
57 
58  declare_params_file_cmd = DeclareLaunchArgument(
59  'params_file',
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')
62 
63  declare_autostart_cmd = DeclareLaunchArgument(
64  'autostart', default_value='True',
65  description='Automatically startup Vector Object server')
66 
67  declare_use_composition_cmd = DeclareLaunchArgument(
68  'use_composition', default_value='True',
69  description='Use composed bringup if True')
70 
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')
74 
75  configured_params = ParameterFile(
76  RewrittenYaml(
77  source_file=params_file,
78  root_key=namespace,
79  param_rewrites={},
80  convert_types=True,
81  ),
82  allow_substs=True,
83  )
84 
85  # Declare node launching commands
86  load_nodes = GroupAction(
87  condition=IfCondition(PythonExpression(['not ', use_composition])),
88  actions=[
89  SetParameter('use_sim_time', use_sim_time),
90  PushROSNamespace(
91  condition=IfCondition(NotEqualsSubstitution(LaunchConfiguration('namespace'), '')),
92  namespace=namespace),
93  Node(
94  package='nav2_map_server',
95  executable='vector_object_server',
96  name='vector_object_server',
97  output='screen',
98  emulate_tty=True, # https://github.com/ros2/launch/issues/188
99  parameters=[configured_params],
100  remappings=remappings),
101  Node(
102  package='nav2_map_server',
103  executable='costmap_filter_info_server',
104  name='costmap_filter_info_server',
105  output='screen',
106  emulate_tty=True, # https://github.com/ros2/launch/issues/188
107  parameters=[configured_params],
108  remappings=remappings),
109  Node(
110  package='nav2_lifecycle_manager',
111  executable='lifecycle_manager',
112  name='lifecycle_manager_vo_server',
113  output='screen',
114  emulate_tty=True, # https://github.com/ros2/launch/issues/188
115  parameters=[{'autostart': autostart},
116  {'node_names': lifecycle_nodes}],
117  remappings=remappings)
118  ]
119  )
120 
121  load_composable_nodes = GroupAction(
122  condition=IfCondition(use_composition),
123  actions=[
124  SetParameter('use_sim_time', use_sim_time),
125  PushROSNamespace(
126  condition=IfCondition(NotEqualsSubstitution(LaunchConfiguration('namespace'), '')),
127  namespace=namespace),
128  LoadComposableNodes(
129  target_container=container_name,
130  composable_node_descriptions=[
131  ComposableNode(
132  package='nav2_map_server',
133  plugin='nav2_map_server::VectorObjectServer',
134  name='vector_object_server',
135  parameters=[configured_params],
136  remappings=remappings),
137  ComposableNode(
138  package='nav2_map_server',
139  plugin='nav2_map_server::CostmapFilterInfoServer',
140  name='costmap_filter_info_server',
141  parameters=[configured_params],
142  remappings=remappings),
143  ComposableNode(
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)
150  ],
151  )
152  ]
153  )
154 
155  ld = LaunchDescription()
156 
157  # Launch arguments
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)
164 
165  # Node launching commands
166  ld.add_action(load_nodes)
167  ld.add_action(load_composable_nodes)
168 
169  return ld