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
24 def generate_launch_description() -> LaunchDescription:
25 nav2_bringup_dir = get_package_share_directory(
'nav2_bringup')
26 benchmark_dir = os.getcwd()
27 metrics_py = os.path.join(benchmark_dir,
'metrics.py')
28 config = os.path.join(
29 get_package_share_directory(
'nav2_bringup'),
'params',
'nav2_params.yaml'
31 map_file = os.path.join(benchmark_dir,
'maps',
'smoothers_world.yaml')
32 lifecycle_nodes = [
'map_server',
'planner_server',
'smoother_server']
34 static_transform_one = Node(
36 executable=
'static_transform_publisher',
45 '--frame-id',
'base_link',
46 '--child-frame-id',
'map'
50 static_transform_two = Node(
52 executable=
'static_transform_publisher',
61 '--frame-id',
'base_link',
62 '--child-frame-id',
'odom'
66 start_map_server_cmd = Node(
67 package=
'nav2_map_server',
68 executable=
'map_server',
72 {
'use_sim_time':
True},
73 {
'yaml_filename': map_file},
74 {
'topic_name':
'map'},
78 start_planner_server_cmd = Node(
79 package=
'nav2_planner',
80 executable=
'planner_server',
81 name=
'planner_server',
86 start_smoother_server_cmd = Node(
87 package=
'nav2_smoother',
88 executable=
'smoother_server',
89 name=
'smoother_server',
94 start_lifecycle_manager_cmd = Node(
95 package=
'nav2_lifecycle_manager',
96 executable=
'lifecycle_manager',
97 name=
'lifecycle_manager',
100 {
'use_sim_time':
True},
102 {
'node_names': lifecycle_nodes},
106 rviz_cmd = IncludeLaunchDescription(
107 PythonLaunchDescriptionSource(
108 os.path.join(nav2_bringup_dir,
'launch',
'rviz_launch.py')
110 launch_arguments={
'namespace':
''}.items(),
113 metrics_cmd = ExecuteProcess(
114 cmd=[
'python3',
'-u', metrics_py], cwd=[benchmark_dir], output=
'screen'
117 ld = LaunchDescription()
118 ld.add_action(static_transform_one)
119 ld.add_action(static_transform_two)
120 ld.add_action(start_map_server_cmd)
121 ld.add_action(start_planner_server_cmd)
122 ld.add_action(start_smoother_server_cmd)
123 ld.add_action(start_lifecycle_manager_cmd)
124 ld.add_action(rviz_cmd)
125 ld.add_action(metrics_cmd)