Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
tb4_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 Command, 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  desc_dir = get_package_share_directory('nav2_minimal_tb4_description')
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', 'depot.yaml'), # Try warehouse.yaml!
61  description='Full path to map file to load',
62  )
63 
64  declare_graph_file_cmd = DeclareLaunchArgument(
65  'graph',
66  default_value=os.path.join(bringup_dir, 'graphs', 'depot_graph.geojson'),
67  )
68 
69  declare_params_file_cmd = DeclareLaunchArgument(
70  'params_file',
71  default_value=os.path.join(bringup_dir, 'params', 'nav2_params.yaml'),
72  description='Full path to the ROS2 parameters file to use for all launched nodes',
73  )
74 
75  declare_autostart_cmd = DeclareLaunchArgument(
76  'autostart',
77  default_value='true',
78  description='Automatically startup the nav2 stack',
79  )
80 
81  declare_use_composition_cmd = DeclareLaunchArgument(
82  'use_composition',
83  default_value='True',
84  description='Whether to use composed bringup',
85  )
86 
87  declare_use_respawn_cmd = DeclareLaunchArgument(
88  'use_respawn',
89  default_value='False',
90  description='Whether to respawn if a node crashes. Applied when composition is disabled.',
91  )
92 
93  declare_rviz_config_file_cmd = DeclareLaunchArgument(
94  'rviz_config_file',
95  default_value=os.path.join(bringup_dir, 'rviz', 'nav2_default_view.rviz'),
96  description='Full path to the RVIZ config file to use',
97  )
98 
99  declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
100  'use_robot_state_pub',
101  default_value='True',
102  description='Whether to start the robot state publisher',
103  )
104 
105  declare_use_rviz_cmd = DeclareLaunchArgument(
106  'use_rviz', default_value='True', description='Whether to start RVIZ'
107  )
108 
109  sdf = os.path.join(desc_dir, 'urdf', 'standard', 'turtlebot4.urdf.xacro')
110  start_robot_state_publisher_cmd = Node(
111  condition=IfCondition(use_robot_state_pub),
112  package='robot_state_publisher',
113  executable='robot_state_publisher',
114  name='robot_state_publisher',
115  namespace=namespace,
116  output='screen',
117  parameters=[
118  {'use_sim_time': True, 'robot_description': Command(['xacro', ' ', sdf])}
119  ],
120  remappings=remappings,
121  )
122 
123  rviz_cmd = IncludeLaunchDescription(
124  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'rviz_launch.py')),
125  condition=IfCondition(use_rviz),
126  launch_arguments=[
127  ('namespace', namespace),
128  ('use_sim_time', 'True'),
129  ('rviz_config', rviz_config_file),
130  ],
131  )
132 
133  bringup_cmd = IncludeLaunchDescription(
134  PythonLaunchDescriptionSource(os.path.join(launch_dir, 'bringup_launch.py')),
135  launch_arguments={
136  'namespace': namespace,
137  'map': map_yaml_file,
138  'graph': graph_filepath,
139  'use_sim_time': 'True',
140  'params_file': params_file,
141  'autostart': autostart,
142  'use_composition': use_composition,
143  'use_respawn': use_respawn,
144  'use_keepout_zones': 'False', # Keepout zones not used in loopback simulation
145  'use_speed_zones': 'False', # Speed zones not used in loopback simulation
146  'use_localization': 'False', # Don't use SLAM, AMCL
147  }.items(),
148  )
149 
150  loopback_sim_cmd = IncludeLaunchDescription(
151  PythonLaunchDescriptionSource(
152  os.path.join(loopback_sim_dir, 'loopback_simulation.launch.py')),
153  launch_arguments=[
154  ('params_file', params_file),
155  ('scan_frame_id', 'rplidar_link'),
156  ],
157  )
158 
159  static_publisher_cmd = Node(
160  package='tf2_ros',
161  executable='static_transform_publisher',
162  arguments=[
163  '--x', '0.0', '--y', '0.0', '--z', '0.0',
164  '--roll', '0', '--pitch', '0', '--yaw', '0',
165  '--frame-id', 'base_footprint', '--child-frame-id', 'base_link']
166  )
167 
168  configured_params = ParameterFile(
169  RewrittenYaml(
170  source_file=params_file,
171  root_key=namespace,
172  param_rewrites={},
173  convert_types=True,
174  ),
175  allow_substs=True,
176  )
177 
178  start_map_server = GroupAction(
179  actions=[
180  SetParameter('use_sim_time', True),
181  Node(
182  package='nav2_map_server',
183  executable='map_server',
184  name='map_server',
185  output='screen',
186  respawn=use_respawn,
187  respawn_delay=2.0,
188  parameters=[configured_params, {'yaml_filename': map_yaml_file}],
189  remappings=remappings,
190  ),
191  Node(
192  package='nav2_lifecycle_manager',
193  executable='lifecycle_manager',
194  name='lifecycle_manager_map_server',
195  output='screen',
196  parameters=[
197  configured_params,
198  {'autostart': autostart}, {'node_names': ['map_server']}],
199  ),
200  ]
201  )
202 
203  # Create the launch description and populate
204  ld = LaunchDescription()
205 
206  # Declare the launch options
207  ld.add_action(declare_namespace_cmd)
208  ld.add_action(declare_map_yaml_cmd)
209  ld.add_action(declare_graph_file_cmd)
210  ld.add_action(declare_params_file_cmd)
211  ld.add_action(declare_autostart_cmd)
212  ld.add_action(declare_use_composition_cmd)
213 
214  ld.add_action(declare_rviz_config_file_cmd)
215  ld.add_action(declare_use_robot_state_pub_cmd)
216  ld.add_action(declare_use_rviz_cmd)
217  ld.add_action(declare_use_respawn_cmd)
218 
219  # Add the actions to launch all of the navigation nodes
220  ld.add_action(start_robot_state_publisher_cmd)
221  ld.add_action(static_publisher_cmd)
222  ld.add_action(start_map_server)
223  ld.add_action(loopback_sim_cmd)
224  ld.add_action(rviz_cmd)
225  ld.add_action(bringup_cmd)
226 
227  return ld