Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
smoother_benchmark_bringup.py
1 # Copyright (c) 2022 Samsung Research America
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 ExecuteProcess, IncludeLaunchDescription
20 from launch.launch_description_sources import PythonLaunchDescriptionSource
21 from launch_ros.actions import Node
22 from nav2_common.launch import RewrittenYaml
23 
24 
25 def generate_launch_description() -> LaunchDescription:
26  nav2_bringup_dir = get_package_share_directory('nav2_bringup')
27  benchmark_dir = os.getcwd()
28  metrics_py = os.path.join(benchmark_dir, 'metrics.py')
29  config = os.path.join(
30  get_package_share_directory('nav2_bringup'), 'params', 'nav2_params.yaml'
31  )
32  map_file = os.path.join(benchmark_dir, 'maps', 'smoothers_world.yaml')
33  lifecycle_nodes = ['map_server', 'planner_server', 'smoother_server']
34  config = RewrittenYaml(
35  source_file=config, root_key='', param_rewrites={},
36  value_rewrites={
37  'KEEPOUT_ZONE_ENABLED': 'False',
38  'SPEED_ZONE_ENABLED': 'False',
39  },
40  convert_types=True
41  )
42 
43  static_transform_one = Node(
44  package='tf2_ros',
45  executable='static_transform_publisher',
46  output='screen',
47  arguments=[
48  '--x', '0',
49  '--y', '0',
50  '--z', '0',
51  '--roll', '0',
52  '--pitch', '0',
53  '--yaw', '0',
54  '--frame-id', 'base_link',
55  '--child-frame-id', 'map'
56  ],
57  )
58 
59  static_transform_two = Node(
60  package='tf2_ros',
61  executable='static_transform_publisher',
62  output='screen',
63  arguments=[
64  '--x', '0',
65  '--y', '0',
66  '--z', '0',
67  '--roll', '0',
68  '--pitch', '0',
69  '--yaw', '0',
70  '--frame-id', 'base_link',
71  '--child-frame-id', 'odom'
72  ],
73  )
74 
75  start_map_server_cmd = Node(
76  package='nav2_map_server',
77  executable='map_server',
78  name='map_server',
79  output='screen',
80  parameters=[
81  {'use_sim_time': True},
82  {'yaml_filename': map_file},
83  {'topic_name': 'map'},
84  ],
85  )
86 
87  start_planner_server_cmd = Node(
88  package='nav2_planner',
89  executable='planner_server',
90  name='planner_server',
91  output='screen',
92  parameters=[config],
93  )
94 
95  start_smoother_server_cmd = Node(
96  package='nav2_smoother',
97  executable='smoother_server',
98  name='smoother_server',
99  output='screen',
100  parameters=[config],
101  )
102 
103  start_lifecycle_manager_cmd = Node(
104  package='nav2_lifecycle_manager',
105  executable='lifecycle_manager',
106  name='lifecycle_manager',
107  output='screen',
108  parameters=[
109  {'use_sim_time': True},
110  {'autostart': True},
111  {'node_names': lifecycle_nodes},
112  ],
113  )
114 
115  rviz_cmd = IncludeLaunchDescription(
116  PythonLaunchDescriptionSource(
117  os.path.join(nav2_bringup_dir, 'launch', 'rviz_launch.py')
118  ),
119  launch_arguments={'namespace': ''}.items(),
120  )
121 
122  metrics_cmd = ExecuteProcess(
123  cmd=['python3', '-u', metrics_py], cwd=[benchmark_dir], output='screen'
124  )
125 
126  ld = LaunchDescription()
127  ld.add_action(static_transform_one)
128  ld.add_action(static_transform_two)
129  ld.add_action(start_map_server_cmd)
130  ld.add_action(start_planner_server_cmd)
131  ld.add_action(start_smoother_server_cmd)
132  ld.add_action(start_lifecycle_manager_cmd)
133  ld.add_action(rviz_cmd)
134  ld.add_action(metrics_cmd)
135  return ld