Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
tb3_loopback_simulation_launch.py
1 # Copyright (C) 2024 Open Navigation LLC
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 """This is all-in-one launch script intended for use by nav2 developers."""
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, IncludeLaunchDescription
22 from launch.conditions import IfCondition
23 from launch.launch_description_sources import PythonLaunchDescriptionSource
24 from launch.substitutions import LaunchConfiguration
25 from launch_ros.actions import Node, SetParameter
26 from launch_ros.descriptions import ParameterFile
27 from nav2_common.launch import LaunchConfigAsBool, RewrittenYaml
28 
29 
30 def generate_launch_description() -> LaunchDescription:
31  # Get the launch directory
32  bringup_dir = get_package_share_directory('nav2_bringup')
33  loopback_sim_dir = get_package_share_directory('nav2_loopback_sim')
34  launch_dir = os.path.join(bringup_dir, 'launch')
35  sim_dir = get_package_share_directory('nav2_minimal_tb3_sim')
36 
37  # Create the launch configuration variables
38  namespace = LaunchConfiguration('namespace')
39  map_yaml_file = LaunchConfiguration('map')
40  graph_filepath = LaunchConfiguration('graph')
41  params_file = LaunchConfiguration('params_file')
42  autostart = LaunchConfigAsBool('autostart')
43  use_composition = LaunchConfigAsBool('use_composition')
44  use_respawn = LaunchConfigAsBool('use_respawn')
45 
46  # Launch configuration variables specific to simulation
47  rviz_config_file = LaunchConfiguration('rviz_config_file')
48  use_robot_state_pub = LaunchConfigAsBool('use_robot_state_pub')
49  use_rviz = LaunchConfigAsBool('use_rviz')
50 
51  remappings = [('/tf', 'tf'), ('/tf_static', 'tf_static')]
52 
53  # Declare the launch arguments
54  declare_namespace_cmd = DeclareLaunchArgument(
55  'namespace', default_value='', description='Top-level namespace'
56  )
57 
58  declare_map_yaml_cmd = DeclareLaunchArgument(
59  'map',
60  default_value=os.path.join(bringup_dir, 'maps', 'tb3_sandbox.yaml'),
61  )
62 
63  declare_graph_file_cmd = DeclareLaunchArgument(
64  'graph',
65  default_value=os.path.join(bringup_dir, 'graphs', 'turtlebot3_graph.geojson'),
66  )
67 
68  declare_params_file_cmd = DeclareLaunchArgument(
69  'params_file',
70  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
71  description='Full path to the ROS2 parameters file to use for all launched nodes',
72  )
73 
74  declare_autostart_cmd = DeclareLaunchArgument(
75  'autostart',
76  default_value='true',
77  description='Automatically startup the nav2 stack',
78  )
79 
80  declare_use_composition_cmd = DeclareLaunchArgument(
81  'use_composition',
82  default_value='True',
83  description='Whether to use composed bringup',
84  )
85 
86  declare_use_respawn_cmd = DeclareLaunchArgument(
87  'use_respawn',
88  default_value='False',
89  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
90  )
91 
92  declare_rviz_config_file_cmd = DeclareLaunchArgument(
93  'rviz_config_file',
94  default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
95  description='Full path to the RVIZ config file to use',
96  )
97 
98  declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
99  'use_robot_state_pub',
100  default_value='True',
101  description='Whether to start the robot state publisher',
102  )
103 
104  declare_use_rviz_cmd = DeclareLaunchArgument(
105  'use_rviz', default_value='True', description='Whether to start RVIZ'
106  )
107 
108  urdf = os.path.join(sim_dir, 'urdf', 'turtlebot3_waffle.urdf')
109  with open(urdf, 'r') as infp:
110  robot_description = infp.read()
111 
112  start_robot_state_publisher_cmd = Node(
113  condition=IfCondition(use_robot_state_pub),
114  package='robot_state_publisher',
115  executable='robot_state_publisher',
116  name='robot_state_publisher',
117  namespace=namespace,
118  output='screen',
119  parameters=[
120  {'use_sim_time': True, 'robot_description': robot_description}
121  ],
122  remappings=remappings,
123  )
124 
125  rviz_cmd = IncludeLaunchDescription(
126  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
127  condition=IfCondition(use_rviz),
128  launch_arguments=[
129  ('namespace', namespace),
130  ('use_sim_time', 'True'),
131  ('rviz_config', rviz_config_file),
132  ],
133  )
134 
135  bringup_cmd = IncludeLaunchDescription(
136  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
137  launch_arguments={
138  'namespace': namespace,
139  'map': map_yaml_file,
140  'graph': graph_filepath,
141  'use_sim_time': 'True',
142  'params_file': params_file,
143  'autostart': autostart,
144  'use_composition': use_composition,
145  'use_respawn': use_respawn,
146  'use_localization': 'False', # Don't use SLAM, AMCL
147  'use_keepout_zones': 'False',
148  'use_speed_zones': 'False',
149  }.items(),
150  )
151 
152  loopback_sim_cmd = IncludeLaunchDescription(
153  PythonLaunchDescriptionSource(
154  os.path.join(loopback_sim_dir, 'loopback_simulation.launch.py')),
155  launch_arguments={
156  'params_file': params_file,
157  }.items(),
158  )
159 
160  configured_params = ParameterFile(
161  RewrittenYaml(
162  source_file=params_file,
163  root_key=namespace,
164  param_rewrites={},
165  convert_types=True,
166  ),
167  allow_substs=True,
168  )
169 
170  start_map_server = GroupAction(
171  actions=[
172  SetParameter('use_sim_time', True),
173  Node(
174  package='nav2_map_server',
175  executable='map_server',
176  name='map_server',
177  output='screen',
178  respawn=use_respawn,
179  respawn_delay=2.0,
180  parameters=[configured_params, {'yaml_filename': map_yaml_file}],
181  remappings=remappings,
182  ),
183  Node(
184  package='nav2_lifecycle_manager',
185  executable='lifecycle_manager',
186  name='lifecycle_manager_map_server',
187  output='screen',
188  parameters=[
189  configured_params,
190  {'autostart': autostart}, {'node_names': ['map_server']}],
191  ),
192  ]
193  )
194 
195  # Create the launch description and populate
196  ld = LaunchDescription()
197 
198  # Declare the launch options
199  ld.add_action(declare_namespace_cmd)
200  ld.add_action(declare_map_yaml_cmd)
201  ld.add_action(declare_graph_file_cmd)
202  ld.add_action(declare_params_file_cmd)
203  ld.add_action(declare_autostart_cmd)
204  ld.add_action(declare_use_composition_cmd)
205 
206  ld.add_action(declare_rviz_config_file_cmd)
207  ld.add_action(declare_use_robot_state_pub_cmd)
208  ld.add_action(declare_use_rviz_cmd)
209  ld.add_action(declare_use_respawn_cmd)
210 
211  # Add the actions to launch all of the navigation nodes
212  ld.add_action(start_robot_state_publisher_cmd)
213  ld.add_action(start_map_server)
214  ld.add_action(loopback_sim_cmd)
215  ld.add_action(rviz_cmd)
216  ld.add_action(bringup_cmd)
217 
218  return ld