|
@@ -0,0 +1,256 @@
|
|
|
+# Copyright (c) 2018 Intel Corporation
|
|
|
+# Copyright (c) Contributors to the Open 3D Engine Project.
|
|
|
+#
|
|
|
+# Licensed under the Apache License, Version 2.0 (the "License");
|
|
|
+# you may not use this file except in compliance with the License.
|
|
|
+# You may obtain a copy of the License at
|
|
|
+#
|
|
|
+# http://www.apache.org/licenses/LICENSE-2.0
|
|
|
+#
|
|
|
+# Unless required by applicable law or agreed to in writing, software
|
|
|
+# distributed under the License is distributed on an "AS IS" BASIS,
|
|
|
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
|
|
+# See the License for the specific language governing permissions and
|
|
|
+# limitations under the License.
|
|
|
+
|
|
|
+import os
|
|
|
+
|
|
|
+from ament_index_python.packages import get_package_share_directory
|
|
|
+
|
|
|
+from launch import LaunchDescription
|
|
|
+from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, GroupAction
|
|
|
+from launch.conditions import IfCondition
|
|
|
+from launch.substitutions import LaunchConfiguration
|
|
|
+from launch_ros.actions import Node, PushRosNamespace
|
|
|
+
|
|
|
+from nav2_common.launch import RewrittenYaml
|
|
|
+
|
|
|
+def generate_launch_description():
|
|
|
+ # Get the launch directory
|
|
|
+ o3de_fleet_nav_dir = get_package_share_directory('o3de_fleet_nav')
|
|
|
+
|
|
|
+ # Create the launch configuration variables
|
|
|
+ namespace = LaunchConfiguration('namespace')
|
|
|
+ use_namespace = LaunchConfiguration('use_namespace')
|
|
|
+ use_sim_time = LaunchConfiguration('use_sim_time')
|
|
|
+ map_yaml_file = LaunchConfiguration('map')
|
|
|
+ params_file = LaunchConfiguration('params_file')
|
|
|
+ autostart = LaunchConfiguration('autostart')
|
|
|
+ use_respawn = LaunchConfiguration('use_respawn')
|
|
|
+ log_level = LaunchConfiguration('log_level')
|
|
|
+
|
|
|
+ distro = os.getenv('ROS_DISTRO')
|
|
|
+
|
|
|
+ # Declare the launch arguments
|
|
|
+ declare_namespace_cmd = DeclareLaunchArgument(
|
|
|
+ 'namespace',
|
|
|
+ default_value='',
|
|
|
+ description='Top-level namespace')
|
|
|
+
|
|
|
+ declare_use_namespace_cmd = DeclareLaunchArgument(
|
|
|
+ 'use_namespace',
|
|
|
+ default_value='false',
|
|
|
+ description='Whether to apply a namespace to the navigation stack')
|
|
|
+
|
|
|
+ declare_map_yaml_cmd = DeclareLaunchArgument(
|
|
|
+ 'map',
|
|
|
+ default_value=os.path.join(
|
|
|
+ o3de_fleet_nav_dir, 'maps', 'map_warehouse.yaml'),
|
|
|
+ description='Full path to map file to load')
|
|
|
+
|
|
|
+ declare_use_sim_time_cmd = DeclareLaunchArgument(
|
|
|
+ 'use_sim_time',
|
|
|
+ default_value='true',
|
|
|
+ description='Use simulation clock if true')
|
|
|
+
|
|
|
+ declare_params_file_cmd = DeclareLaunchArgument(
|
|
|
+ 'params_file',
|
|
|
+ default_value=os.path.join(o3de_fleet_nav_dir, 'params', distro, 'nav2_params.yaml'),
|
|
|
+ description='Full path to the ROS2 parameters file to use for all launched nodes')
|
|
|
+
|
|
|
+ declare_autostart_cmd = DeclareLaunchArgument(
|
|
|
+ 'autostart', default_value='True',
|
|
|
+ description='Automatically startup the nav2 stack')
|
|
|
+
|
|
|
+ declare_use_respawn_cmd = DeclareLaunchArgument(
|
|
|
+ 'use_respawn', default_value='False',
|
|
|
+ description='Whether to respawn if a node crashes. Applied when composition is disabled.')
|
|
|
+
|
|
|
+ declare_log_level_cmd = DeclareLaunchArgument(
|
|
|
+ 'log_level', default_value='info',
|
|
|
+ description='log level')
|
|
|
+
|
|
|
+ # Set up lifecycle configuration
|
|
|
+ localization_lifecycle_nodes = ['map_server', 'amcl']
|
|
|
+
|
|
|
+ navigation_lifecycle_nodes = ['controller_server',
|
|
|
+ 'smoother_server',
|
|
|
+ 'planner_server',
|
|
|
+ 'behavior_server',
|
|
|
+ 'bt_navigator',
|
|
|
+ 'waypoint_follower',
|
|
|
+ 'velocity_smoother']
|
|
|
+
|
|
|
+ # Set up parameters
|
|
|
+ param_substitutions = {
|
|
|
+ 'use_sim_time': use_sim_time,
|
|
|
+ 'yaml_filename': map_yaml_file,
|
|
|
+ 'autostart': autostart}
|
|
|
+
|
|
|
+ configured_params = RewrittenYaml(
|
|
|
+ source_file=params_file,
|
|
|
+ root_key=namespace,
|
|
|
+ param_rewrites=param_substitutions,
|
|
|
+ convert_types=True)
|
|
|
+
|
|
|
+ # Main navigation action
|
|
|
+ fleet_nav = GroupAction([
|
|
|
+ PushRosNamespace(
|
|
|
+ condition=IfCondition(use_namespace),
|
|
|
+ namespace=namespace),
|
|
|
+ # Localization actions
|
|
|
+ GroupAction(
|
|
|
+ actions=[
|
|
|
+ Node(
|
|
|
+ package='nav2_map_server',
|
|
|
+ executable='map_server',
|
|
|
+ name='map_server',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_amcl',
|
|
|
+ executable='amcl',
|
|
|
+ name='amcl',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_lifecycle_manager',
|
|
|
+ executable='lifecycle_manager',
|
|
|
+ name='lifecycle_manager_localization',
|
|
|
+ output='screen',
|
|
|
+ arguments=['--ros-args', '--log-level', log_level],
|
|
|
+ parameters=[{'use_sim_time': use_sim_time},
|
|
|
+ {'autostart': autostart},
|
|
|
+ {'node_names': localization_lifecycle_nodes}])
|
|
|
+ ]
|
|
|
+ ),
|
|
|
+ # Navigation actions
|
|
|
+ GroupAction(
|
|
|
+ actions=[
|
|
|
+ Node(
|
|
|
+ package='nav2_controller',
|
|
|
+ executable='controller_server',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level],
|
|
|
+ remappings=[('cmd_vel', 'cmd_vel_nav')]),
|
|
|
+ Node(
|
|
|
+ package='nav2_smoother',
|
|
|
+ executable='smoother_server',
|
|
|
+ name='smoother_server',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_planner',
|
|
|
+ executable='planner_server',
|
|
|
+ name='planner_server',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_behaviors',
|
|
|
+ executable='behavior_server',
|
|
|
+ name='behavior_server',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_bt_navigator',
|
|
|
+ executable='bt_navigator',
|
|
|
+ name='bt_navigator',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_waypoint_follower',
|
|
|
+ executable='waypoint_follower',
|
|
|
+ name='waypoint_follower',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level]),
|
|
|
+ Node(
|
|
|
+ package='nav2_velocity_smoother',
|
|
|
+ executable='velocity_smoother',
|
|
|
+ name='velocity_smoother',
|
|
|
+ output='screen',
|
|
|
+ respawn=use_respawn,
|
|
|
+ respawn_delay=2.0,
|
|
|
+ parameters=[configured_params],
|
|
|
+ arguments=['--ros-args', '--log-level', log_level],
|
|
|
+ remappings=[('cmd_vel', 'cmd_vel_nav'), ('cmd_vel_smoothed', 'cmd_vel')]),
|
|
|
+ Node(
|
|
|
+ package='nav2_lifecycle_manager',
|
|
|
+ executable='lifecycle_manager',
|
|
|
+ name='lifecycle_manager_navigation',
|
|
|
+ output='screen',
|
|
|
+ arguments=['--ros-args', '--log-level', log_level],
|
|
|
+ parameters=[{'use_sim_time': use_sim_time},
|
|
|
+ {'autostart': autostart},
|
|
|
+ {'node_names': navigation_lifecycle_nodes}]),
|
|
|
+ ]
|
|
|
+ )
|
|
|
+ ])
|
|
|
+
|
|
|
+ # Robot spawning in the simulation (via the spawn service)
|
|
|
+ spawner = Node(
|
|
|
+ package='o3de_fleet_nav',
|
|
|
+ executable='robot_spawner',
|
|
|
+ output='screen',
|
|
|
+ parameters=[params_file]
|
|
|
+ )
|
|
|
+
|
|
|
+ stdout_linebuf_envvar = SetEnvironmentVariable(
|
|
|
+ 'RCUTILS_LOGGING_BUFFERED_STREAM', '1')
|
|
|
+
|
|
|
+ # Create the launch description and populate
|
|
|
+ ld = LaunchDescription()
|
|
|
+
|
|
|
+ # Declare the launch options
|
|
|
+ ld.add_action(declare_namespace_cmd)
|
|
|
+ ld.add_action(declare_use_namespace_cmd)
|
|
|
+ ld.add_action(declare_map_yaml_cmd)
|
|
|
+ ld.add_action(declare_use_sim_time_cmd)
|
|
|
+ ld.add_action(declare_params_file_cmd)
|
|
|
+ ld.add_action(declare_autostart_cmd)
|
|
|
+ ld.add_action(declare_use_respawn_cmd)
|
|
|
+ ld.add_action(declare_log_level_cmd)
|
|
|
+
|
|
|
+ # Navigation
|
|
|
+ ld.add_action(fleet_nav)
|
|
|
+
|
|
|
+ # Spawning
|
|
|
+ ld.add_action(spawner)
|
|
|
+
|
|
|
+ # Other
|
|
|
+ ld.add_action(stdout_linebuf_envvar)
|
|
|
+
|
|
|
+ return ld
|