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
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'
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={},
37 'KEEPOUT_ZONE_ENABLED':
'False',
38 'SPEED_ZONE_ENABLED':
'False',
43 static_transform_one = Node(
45 executable=
'static_transform_publisher',
54 '--frame-id',
'base_link',
55 '--child-frame-id',
'map'
59 static_transform_two = Node(
61 executable=
'static_transform_publisher',
70 '--frame-id',
'base_link',
71 '--child-frame-id',
'odom'
75 start_map_server_cmd = Node(
76 package=
'nav2_map_server',
77 executable=
'map_server',
81 {
'use_sim_time':
True},
82 {
'yaml_filename': map_file},
83 {
'topic_name':
'map'},
87 start_planner_server_cmd = Node(
88 package=
'nav2_planner',
89 executable=
'planner_server',
90 name=
'planner_server',
95 start_smoother_server_cmd = Node(
96 package=
'nav2_smoother',
97 executable=
'smoother_server',
98 name=
'smoother_server',
103 start_lifecycle_manager_cmd = Node(
104 package=
'nav2_lifecycle_manager',
105 executable=
'lifecycle_manager',
106 name=
'lifecycle_manager',
109 {
'use_sim_time':
True},
111 {
'node_names': lifecycle_nodes},
115 rviz_cmd = IncludeLaunchDescription(
116 PythonLaunchDescriptionSource(
117 os.path.join(nav2_bringup_dir,
'launch',
'rviz_launch.py')
119 launch_arguments={
'namespace':
''}.items(),
122 metrics_cmd = ExecuteProcess(
123 cmd=[
'python3',
'-u', metrics_py], cwd=[benchmark_dir], output=
'screen'
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)