Explorar o código

Fleet navigation ROS 2 package and assets (#450)

Fleet navigation ROS2 package and assets

---------

Signed-off-by: Piotr Jaroszek <[email protected]>
Piotr Jaroszek hai 1 ano
pai
achega
02ff6f8530
Modificáronse 27 ficheiros con 2693 adicións e 35 borrados
  1. 1 1
      .gitattributes
  2. 126 7
      Templates/Ros2FleetRobotTemplate/README.md
  3. BIN=BIN
      Templates/Ros2FleetRobotTemplate/Screenshots/fleet_rviz.png
  4. 1 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/NOTICE
  5. 19 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/config/fleet_config.yaml
  6. 153 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_fleet_nav_launch.py
  7. 256 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_nav_launch.py
  8. 107 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_rviz_launch.py
  9. 3 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/maps/map_warehouse.pgm
  10. 7 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/maps/map_warehouse.yaml
  11. 0 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav/__init__.py
  12. 81 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav/robot_spawner.py
  13. 24 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/package.xml
  14. 310 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/humble/nav2_multirobot_params.yaml
  15. 300 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/humble/nav2_params.yaml
  16. 313 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/iron/nav2_multirobot_params.yaml
  17. 303 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/iron/nav2_params.yaml
  18. 0 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/resource/o3de_fleet_nav
  19. 322 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/rviz/nav2_namespaced_view.rviz
  20. 4 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/setup.cfg
  21. 35 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/setup.py
  22. 25 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/test/test_copyright.py
  23. 25 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/test/test_flake8.py
  24. 23 0
      Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/test/test_pep257.py
  25. 14 15
      Templates/Ros2FleetRobotTemplate/Template/Levels/Warehouse/Warehouse.prefab
  26. 131 0
      Templates/Ros2FleetRobotTemplate/Template/Prefabs/ProteusLaserScanner.prefab
  27. 110 12
      Templates/Ros2FleetRobotTemplate/template.json

+ 1 - 1
.gitattributes

@@ -1,4 +1,3 @@
-
 #
 # Git LFS (see https://git-lfs.github.com/)
 #
@@ -130,3 +129,4 @@ Templates/Ros2FleetRobotTemplate/docs/images/*.png filter= diff= merge= -text
 Gems/ROS2/docs/**/*.png -filter -diff -merge
 Templates/Ros2ProjectTemplate/Screenshots/*.png filter= diff= merge= -text
 Templates/Ros2FleetRobotTemplate/Screenshots/*.png filter= diff= merge= -text
+*.pgm filter=lfs diff=lfs merge=lfs -text

+ 126 - 7
Templates/Ros2FleetRobotTemplate/README.md

@@ -18,6 +18,7 @@ to install all required dependencies and create your project with a template (ma
 ## Spawning robots
 
 The level contains spawn points configured to easily add more Proteus robots through ROS 2 calls.
+
 This is done with the [Spawner Component](https://development--o3deorg.netlify.app/docs/user-guide/interactivity/robotics/concepts-and-components-overview/#spawner).
 There are 4 spawn points already added in the level. You can use them all with the following service calls:
 
@@ -28,17 +29,135 @@ ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity '{name: 'proteus', x
 ros2 service call /spawn_entity gazebo_msgs/srv/SpawnEntity '{name: 'proteus', xml: 'spawnPoint4'}'
 ```
 
-## Topics and frames
+## Fleet navigation
+
+This template comes with the example fleet navigation ROS 2 package called `o3de_fleet_nav`. You can find a prepared ROS 2 workspace in the `Examples` directory.
+
+This package contains a modified code from `nav2_bringup` package (https://github.com/ros-planning/navigation2).
+
+In this example, a fleet of robots is automatically spawned and each individual robot can be controlled via the Rviz2. An AMCL localization is used for robot localization.
+
+> Notice: Before running an automated fleet example, please make sure your level doesn't contain any robots in it (they will be spawned).
+
+### Fleet configuration
+
+You can configure the fleet by modifying `Example/ros2_ws/src/o3de_fleet_nav/config/fleet_config.yaml` file:
+
+```
+fleet:
+  - robot_name: proteus
+    robot_namespace: robot1
+    position: 
+      x: -6.0
+      y: 0.5
+      z: 0.2
+  - robot_name: proteus
+    robot_namespace: robot2
+    position: 
+      x: -6.0
+      y: 7.5
+      z: 0.2
+  - robot_name: proteus
+    robot_namespace: robot3
+    position: 
+      x: -6.0
+      y: -6.0
+      z: 0.2
+```
+
+This configuration file contains the data about each robot in a fleet:
+- name (a type of the robot to spawn), 
+- namespace (must be unique per spawned robot),
+- spawning position (spawn position is also used as an AMCL initial estimation). 
+
+In this example, only the `proteus` robot is supported.
+
+You can modify contents of this file to add/remove robots or change their initial positions.
 
-Every spawned robot will have its own namespace for all topics. For the first robot, these will be:
+> Notice: You have to rebuild the ROS 2 workspace for changes to update.
 
-- `/proteus_1/cmd_vel`: The topic to [control the robot](https://development--o3deorg.netlify.app/docs/user-guide/interactivity/robotics/concepts-and-components-overview/#robot-control).
-- `/proteus_1/pc` - The topic of simulated LIDAR point cloud.
+### Navigation configuration
+
+You can configure navigation parameters by modifying `Examples/ros2_ws/src/o3de_fleet_nav/params/<ROS_DISTRO>/nav2_*.yaml` files.
+
+Please visit the [nav2 configuration guide](https://navigation.ros.org/configuration/index.html) for a detailed description of the navigation parameters.
+
+> Notice: You have to rebuild the ROS 2 workspace for changes to update.
+
+### Topics and frames
+
+Every spawned robot will have its own namespace for all topics. For the first robot ('robot1' namespace), these will be:
+
+- `/robot1/cmd_vel`: The topic to [control the robot](https://development--o3deorg.netlify.app/docs/user-guide/interactivity/robotics/concepts-and-components-overview/#robot-control).
+- `/robot1/scan` - The topic of simulated 2D laser scanner sensor.
 
 The first spawned robot also provides the following transformations:
 
-- `/proteus_1/odom`
-- `/proteus_1/base_link`
-- `/proteus_1/lidar`
+- `/robot1/odom`
+- `/robot1/base_link`
+- `/robot1/lidar`
 
 To understand more about transformations, see ROS 2 navigation [documentation](https://navigation.ros.org/setup_guides/transformation/setup_transforms.html).
+
+## Using your robots in the simulation
+
+You can also use your robots in the simulation. To do so, you need to:
+- [import a robot](https://docs.o3de.org/docs/user-guide/interactivity/robotics/importing-robot/) from existing URDF file,
+  - or create a robot from scratch in a O3DE editor using ROS 2 gem components (see [Frames](https://docs.o3de.org/docs/user-guide/interactivity/robotics/concepts-and-components-overview)),
+- make sure that your robot has a 2D scanner attached 
+  - and publishes scans on `scan` topic (see [Sensors](https://docs.o3de.org/docs/user-guide/interactivity/robotics/concepts-and-components-overview/#robot-control)),
+- is controlled via the `cmd_vel` topic (see [Robot Control](https://docs.o3de.org/docs/user-guide/interactivity/robotics/concepts-and-components-overview/#robot-control)).
+
+When you have your robot set up:
+- create a prefab out of it (skip if URDF importer did that for you),
+- load the `Warehouse` level,
+- assign the prefab to the `RobotSpawner` entity inside `ROS2 Spawner Component` with a preferred name.
+
+Then you can alter `fleet_config.yaml` file to change the robot name to the assigned one, and start the fleet simulation with your robot!
+
+### Building
+
+- Source ROS 2:
+```
+. /opt/ros/humble/setup.bash
+```
+
+- Go to the ROS 2 workspace:
+```
+cd Examples/ros2_ws
+```
+
+- Install ROS 2 dependencies:
+```
+rosdep update
+rosdep install --from-paths src -y --ignore-src
+```
+
+- Build workspace:
+```
+colcon build --symlink-install
+```
+
+### Running
+
+- Run the `Warehouse` level in O3DE editor.
+
+- Source ROS 2 and the `o3de_fleet_nav` workspace:
+```
+. /opt/ros/humble/setup.bash
+```
+
+- Source the `o3de_fleet_nav` workspace:
+```
+cd Examples/ros2_ws
+. ./install/setup.bash
+```
+
+- Run the fleet example:
+```
+ros2 launch o3de_fleet_nav o3de_fleet_nav_launch.py
+```
+
+Few RViz2 windows should appear. You can use the "Nav2 Goal" button to send goal to the robot.
+
+![RViz2](Screenshots/fleet_rviz.png)

BIN=BIN
Templates/Ros2FleetRobotTemplate/Screenshots/fleet_rviz.png


+ 1 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/NOTICE

@@ -0,0 +1 @@
+This package contains a modified code from "nav2_bringup" package (https://github.com/ros-planning/navigation2).

+ 19 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/config/fleet_config.yaml

@@ -0,0 +1,19 @@
+fleet:
+  - robot_name: proteus
+    robot_namespace: robot1
+    position: 
+      x: -6.0
+      y: 0.5
+      z: 0.2
+  - robot_name: proteus
+    robot_namespace: robot2
+    position: 
+      x: -6.0
+      y: 7.5
+      z: 0.2
+  - robot_name: proteus
+    robot_namespace: robot3
+    position: 
+      x: -6.0
+      y: -6.0
+      z: 0.2

+ 153 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_fleet_nav_launch.py

@@ -0,0 +1,153 @@
+# 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
+import yaml
+
+from ament_index_python.packages import get_package_share_directory
+
+from launch import LaunchDescription
+from launch.actions import (DeclareLaunchArgument, ExecuteProcess, GroupAction,
+                            IncludeLaunchDescription, LogInfo)
+from launch.conditions import IfCondition
+from launch.launch_description_sources import PythonLaunchDescriptionSource
+from launch.substitutions import LaunchConfiguration, TextSubstitution
+from nav2_common.launch import ReplaceString
+
+
+def generate_launch_description():
+    # Get the launch directory
+    o3de_fleet_nav_dir = get_package_share_directory('o3de_fleet_nav')
+    o3de_launch_dir = os.path.join(o3de_fleet_nav_dir, 'launch')
+
+    # Load fleet configuration
+    fleet_config_file = os.path.join(o3de_fleet_nav_dir, 'config', 'fleet_config.yaml')
+    robots = []
+    with open(fleet_config_file, 'r') as f:
+        configuration = yaml.safe_load(f)
+        for robot in configuration["fleet"]:
+            robots.append(
+                {
+                    "name": robot["robot_name"],
+                    "namespace": robot["robot_namespace"],
+                    "x_pose": robot["position"]["x"],
+                    "y_pose": robot["position"]["y"],
+                    "z_pose": robot["position"]["z"]
+                }
+            )
+
+    map_yaml_file = LaunchConfiguration('map')
+    autostart = LaunchConfiguration('autostart')
+    rviz_config_file = LaunchConfiguration('rviz_config')
+    use_rviz = LaunchConfiguration('use_rviz')
+    log_settings = LaunchConfiguration('log_settings', default='true')
+
+    distro = os.getenv('ROS_DISTRO')
+
+    # Declare the launch arguments
+    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_robot_params_file_cmd = DeclareLaunchArgument(
+        'robot_params_file',
+        default_value=os.path.join(o3de_fleet_nav_dir, 'params', distro, 'nav2_multirobot_params.yaml'),
+        description='Full path to the ROS2 parameters file to use for all robot launched nodes')
+
+    declare_autostart_cmd = DeclareLaunchArgument(
+        'autostart', default_value='True',
+        description='Automatically startup the stacks')
+
+    declare_rviz_config_file_cmd = DeclareLaunchArgument(
+        'rviz_config',
+        default_value=os.path.join(o3de_fleet_nav_dir, 'rviz', 'nav2_namespaced_view.rviz'),
+        description='Full path to the RVIZ config file to use.')
+
+    declare_use_rviz_cmd = DeclareLaunchArgument(
+        'use_rviz',
+        default_value='True',
+        description='Whether to start RVIZ')
+
+    # Launch navigation for each robot in fleet configuration
+    nav_instances_cmds = []
+    for robot in robots:
+        params_file = LaunchConfiguration("robot_params_file")
+        
+        configured_params = ReplaceString(
+            source_file=params_file,
+            replacements={
+                '<robot_name>': robot['name'],
+                '<robot_namespace>': robot['namespace'],
+                '<robot_initial_pose_x>': str(robot['x_pose']),
+                '<robot_initial_pose_y>': str(robot['y_pose']),
+                '<robot_initial_pose_z>': str(robot['z_pose'])
+            })
+        
+
+        group = GroupAction([
+            IncludeLaunchDescription(
+                PythonLaunchDescriptionSource(
+                        os.path.join(o3de_launch_dir, 'o3de_rviz_launch.py')),
+                condition=IfCondition(use_rviz),
+                launch_arguments={
+                                  'namespace': TextSubstitution(text=robot['namespace']),
+                                  'use_namespace': 'True',
+                                  'rviz_config': rviz_config_file}.items()),
+
+            IncludeLaunchDescription(
+                PythonLaunchDescriptionSource(os.path.join(o3de_launch_dir,
+                                                           'o3de_nav_launch.py')),
+                launch_arguments={'namespace': robot['namespace'],
+                                  'use_namespace': 'True',
+                                  'map': map_yaml_file,
+                                  'use_sim_time': 'True',
+                                  'params_file': configured_params,
+                                  'autostart': autostart}.items()),
+
+            LogInfo(
+                condition=IfCondition(log_settings),
+                msg=['Launching ', robot['namespace']]),
+            LogInfo(
+                condition=IfCondition(log_settings),
+                msg=[robot['namespace'], ' map yaml: ', map_yaml_file]),
+            LogInfo(
+                condition=IfCondition(log_settings),
+                msg=[robot['namespace'], ' params yaml: ', params_file]),
+            LogInfo(
+                condition=IfCondition(log_settings),
+                msg=[robot['namespace'], ' rviz config file: ', rviz_config_file]),
+            LogInfo(
+                condition=IfCondition(log_settings),
+                msg=[robot['namespace'], ' autostart: ', autostart])
+        ])
+
+        nav_instances_cmds.append(group)
+
+    # Create the launch description and populate
+    ld = LaunchDescription()
+
+    # Declare the launch options
+    ld.add_action(declare_map_yaml_cmd)
+    ld.add_action(declare_robot_params_file_cmd)
+    ld.add_action(declare_use_rviz_cmd)
+    ld.add_action(declare_autostart_cmd)
+    ld.add_action(declare_rviz_config_file_cmd)
+
+    # Launch robots
+    for simulation_instance_cmd in nav_instances_cmds:
+        ld.add_action(simulation_instance_cmd)
+
+    return ld

+ 256 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_nav_launch.py

@@ -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

+ 107 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_rviz_launch.py

@@ -0,0 +1,107 @@
+# 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, EmitEvent, RegisterEventHandler
+from launch.conditions import IfCondition, UnlessCondition
+from launch.event_handlers import OnProcessExit
+from launch.events import Shutdown
+from launch.substitutions import LaunchConfiguration
+from launch_ros.actions import Node
+from nav2_common.launch import ReplaceString
+
+
+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')
+    rviz_config_file = LaunchConfiguration('rviz_config')
+
+    # Declare the launch arguments
+    declare_namespace_cmd = DeclareLaunchArgument(
+        'namespace',
+        default_value='navigation',
+        description=('Top-level namespace. The value will be used to replace the '
+                     '<robot_namespace> keyword on the rviz config file.'))
+
+    declare_use_namespace_cmd = DeclareLaunchArgument(
+        'use_namespace',
+        default_value='false',
+        description='Whether to apply a namespace to the navigation stack')
+
+    declare_rviz_config_file_cmd = DeclareLaunchArgument(
+        'rviz_config',
+        default_value=os.path.join(o3de_fleet_nav_dir, 'rviz', 'nav2_default_view.rviz'),
+        description='Full path to the RVIZ config file to use')
+
+    # Launch rviz
+    start_rviz_cmd = Node(
+        condition=UnlessCondition(use_namespace),
+        package='rviz2',
+        executable='rviz2',
+        arguments=['-d', rviz_config_file],
+        output='screen')
+
+    namespaced_rviz_config_file = ReplaceString(
+            source_file=rviz_config_file,
+            replacements={'<robot_namespace>': ('/', namespace)})
+
+    start_namespaced_rviz_cmd = Node(
+        condition=IfCondition(use_namespace),
+        package='rviz2',
+        executable='rviz2',
+        namespace=namespace,
+        arguments=['-d', namespaced_rviz_config_file, "--ros-args", "-p", "use_sim_time:=True"],
+        output='screen',
+        remappings=[('/goal_pose', 'goal_pose'),
+                    ('/clicked_point', 'clicked_point'),
+                    ('/initialpose', 'initialpose')])
+
+    exit_event_handler = RegisterEventHandler(
+        condition=UnlessCondition(use_namespace),
+        event_handler=OnProcessExit(
+            target_action=start_rviz_cmd,
+            on_exit=EmitEvent(event=Shutdown(reason='rviz exited'))))
+
+    exit_event_handler_namespaced = RegisterEventHandler(
+        condition=IfCondition(use_namespace),
+        event_handler=OnProcessExit(
+            target_action=start_namespaced_rviz_cmd,
+            on_exit=EmitEvent(event=Shutdown(reason='rviz exited'))))
+
+    # 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_rviz_config_file_cmd)
+
+    # Add any conditioned actions
+    ld.add_action(start_rviz_cmd)
+    ld.add_action(start_namespaced_rviz_cmd)
+
+    # Add other nodes and processes we need
+    ld.add_action(exit_event_handler)
+    ld.add_action(exit_event_handler_namespaced)
+
+    return ld

+ 3 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/maps/map_warehouse.pgm

@@ -0,0 +1,3 @@
+version https://git-lfs.github.com/spec/v1
+oid sha256:f526ada8248be73c1a9ef3240149b892226c9a6e1edd27a549e9a6675111129f
+size 508885

+ 7 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/maps/map_warehouse.yaml

@@ -0,0 +1,7 @@
+image: map_warehouse.pgm
+mode: trinary
+resolution: 0.05
+origin: [-10.2, -10, 0]
+negate: 0
+occupied_thresh: 0.65
+free_thresh: 0.25

+ 0 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav/__init__.py


+ 81 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav/robot_spawner.py

@@ -0,0 +1,81 @@
+# 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.
+
+from gazebo_msgs.srv import SpawnEntity
+
+import rclpy
+from rclpy.exceptions import ParameterUninitializedException
+from rclpy.node import Node
+
+
+class RobotSpawner(Node):
+
+    def __init__(self):
+        super().__init__('robot_spawner_client')
+
+        self.declare_parameter('robot_name', rclpy.Parameter.Type.STRING)
+        self.declare_parameter('robot_namespace', '')
+        self.declare_parameter('robot_initial_position', [0.0, 0.0, 0.0])
+
+        try:
+            self.robot_name = self.get_parameter('robot_name').get_parameter_value().string_value
+        except ParameterUninitializedException as e:
+            self.get_logger().warn("Nothing to spawn. 'robot_name' parameter not set.")
+            return
+        
+        self.robot_namespace = self.get_parameter('robot_namespace').get_parameter_value().string_value
+        self.robot_initial_position = self.get_parameter('robot_initial_position').get_parameter_value().double_array_value
+
+
+        self.cli = self.create_client(SpawnEntity, 'spawn_entity')
+        
+        while not self.cli.wait_for_service(timeout_sec=1.0):
+            self.get_logger().info('Spawning service not available, waiting...')
+
+        self.req = SpawnEntity.Request()
+        result = self.send_request()
+
+        if result.success:
+            self.get_logger().info(f'{self.robot_namespace} spawned.')
+        else:
+            self.get_logger().error(f'Failed to spawn {self.robot_namespace}: {result.status_message}')
+
+    def send_request(self):
+        self.get_logger().info(f"Spawning robot: {self.robot_namespace}/{self.robot_name} on ("
+                            f"{self.robot_initial_position[0]}, "
+                            f"{self.robot_initial_position[1]}, "
+                            f"{self.robot_initial_position[2]})")
+        
+        self.req.name = self.robot_name
+        self.req.robot_namespace = self.robot_namespace
+        self.req.initial_pose.position.x = self.robot_initial_position[0]
+        self.req.initial_pose.position.y = self.robot_initial_position[1]
+        self.req.initial_pose.position.z = self.robot_initial_position[2]
+
+        self.future = self.cli.call_async(self.req)
+        rclpy.spin_until_future_complete(self, self.future)
+
+        return self.future.result()
+
+
+def main(args=None):
+    rclpy.init(args=args)
+
+    robot_spawner = RobotSpawner()
+    robot_spawner.destroy_node()
+
+    rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()

+ 24 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/package.xml

@@ -0,0 +1,24 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>o3de_fleet_nav</name>
+  <version>1.0.0</version>
+  <description>Navigation package for O3DE Ros2FleetRobotTemplate</description>
+  <maintainer email="[email protected]">pjaroszek</maintainer>
+  <license>Apache 2.0</license>
+
+  <exec_depend>launch_ros</exec_depend>
+  <exec_depend>nav2_bringup</exec_depend>
+  <exec_depend>nav2_common</exec_depend>
+  <exec_depend>slam_toolbox</exec_depend>
+  <exec_depend>gazebo_msgs</exec_depend>
+
+  <test_depend>ament_copyright</test_depend>
+  <test_depend>ament_flake8</test_depend>
+  <test_depend>ament_pep257</test_depend>
+  <test_depend>python3-pytest</test_depend>
+
+  <export>
+    <build_type>ament_python</build_type>
+  </export>
+</package>

+ 310 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/humble/nav2_multirobot_params.yaml

@@ -0,0 +1,310 @@
+robot_spawner_client:
+  ros__parameters:
+    robot_name: <robot_name>
+    robot_namespace: <robot_namespace>
+    robot_initial_position: [<robot_initial_pose_x>, <robot_initial_pose_y>, <robot_initial_pose_z>]
+
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    alpha1: 0.2
+    alpha2: 0.2
+    alpha3: 0.2
+    alpha4: 0.2
+    alpha5: 0.2
+    base_frame_id: "<robot_namespace>/base_link"
+    beam_skip_distance: 0.5
+    beam_skip_error_threshold: 0.9
+    beam_skip_threshold: 0.3
+    do_beamskip: false
+    global_frame_id: "map"
+    map_topic: "map"
+    lambda_short: 0.1
+    laser_likelihood_max_dist: 2.0
+    laser_max_range: 100.0
+    laser_min_range: -1.0
+    laser_model_type: "<robot_namespace>/likelihood_field"
+    max_beams: 60
+    max_particles: 2000
+    min_particles: 500
+    odom_frame_id: "<robot_namespace>/odom"
+    pf_err: 0.05
+    pf_z: 0.99
+    recovery_alpha_fast: 0.0
+    recovery_alpha_slow: 0.0
+    resample_interval: 1
+    robot_model_type: "nav2_amcl::DifferentialMotionModel"
+    save_pose_rate: 0.5
+    sigma_hit: 0.2
+    tf_broadcast: true
+    transform_tolerance: 1.0
+    update_min_a: 0.2
+    update_min_d: 0.25
+    z_hit: 0.5
+    z_max: 0.05
+    z_rand: 0.5
+    z_short: 0.05
+    scan_topic: scan
+    set_initial_pose: True
+    initial_pose:
+      x: <robot_initial_pose_x>
+      y: <robot_initial_pose_y>
+      z: <robot_initial_pose_z>
+
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    global_frame: map
+    robot_base_frame: <robot_namespace>/base_link
+    odom_topic: odom
+    bt_loop_duration: 10
+    default_server_timeout: 20
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
+    # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
+    plugin_lib_names:
+      - nav2_compute_path_to_pose_action_bt_node
+      - nav2_compute_path_through_poses_action_bt_node
+      - nav2_smooth_path_action_bt_node
+      - nav2_follow_path_action_bt_node
+      - nav2_spin_action_bt_node
+      - nav2_wait_action_bt_node
+      - nav2_assisted_teleop_action_bt_node
+      - nav2_back_up_action_bt_node
+      - nav2_drive_on_heading_bt_node
+      - nav2_clear_costmap_service_bt_node
+      - nav2_is_stuck_condition_bt_node
+      - nav2_goal_reached_condition_bt_node
+      - nav2_goal_updated_condition_bt_node
+      - nav2_globally_updated_goal_condition_bt_node
+      - nav2_is_path_valid_condition_bt_node
+      - nav2_initial_pose_received_condition_bt_node
+      - nav2_reinitialize_global_localization_service_bt_node
+      - nav2_rate_controller_bt_node
+      - nav2_distance_controller_bt_node
+      - nav2_speed_controller_bt_node
+      - nav2_truncate_path_action_bt_node
+      - nav2_truncate_path_local_action_bt_node
+      - nav2_goal_updater_node_bt_node
+      - nav2_recovery_node_bt_node
+      - nav2_pipeline_sequence_bt_node
+      - nav2_round_robin_node_bt_node
+      - nav2_transform_available_condition_bt_node
+      - nav2_time_expired_condition_bt_node
+      - nav2_path_expiring_timer_condition
+      - nav2_distance_traveled_condition_bt_node
+      - nav2_single_trigger_bt_node
+      - nav2_goal_updated_controller_bt_node
+      - nav2_is_battery_low_condition_bt_node
+      - nav2_navigate_through_poses_action_bt_node
+      - nav2_navigate_to_pose_action_bt_node
+      - nav2_remove_passed_goals_action_bt_node
+      - nav2_planner_selector_bt_node
+      - nav2_controller_selector_bt_node
+      - nav2_goal_checker_selector_bt_node
+      - nav2_controller_cancel_bt_node
+      - nav2_path_longer_on_approach_bt_node
+      - nav2_wait_cancel_bt_node
+      - nav2_spin_cancel_bt_node
+      - nav2_back_up_cancel_bt_node
+      - nav2_assisted_teleop_cancel_bt_node
+      - nav2_drive_on_heading_cancel_bt_node
+
+bt_navigator_navigate_through_poses_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+bt_navigator_navigate_to_pose_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    controller_frequency: 20.0
+    min_x_velocity_threshold: 0.001
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    progress_checker_plugin: "progress_checker"
+    goal_checker_plugins: ["goal_checker"]
+    controller_plugins: ["FollowPath"]
+
+    # Progress checker parameters
+    progress_checker:
+      plugin: "nav2_controller::SimpleProgressChecker"
+      required_movement_radius: 0.5
+      movement_time_allowance: 10.0
+    # Goal checker parameters
+    goal_checker:
+      plugin: "nav2_controller::SimpleGoalChecker"
+      xy_goal_tolerance: 0.25
+      yaw_goal_tolerance: 0.25
+      stateful: True
+    # DWB parameters
+    FollowPath:
+      plugin: "dwb_core::DWBLocalPlanner"
+      debug_trajectory_details: True
+      min_vel_x: 0.0
+      min_vel_y: 0.0
+      max_vel_x: 0.26
+      max_vel_y: 0.0
+      max_vel_theta: 1.0
+      min_speed_xy: 0.0
+      max_speed_xy: 0.26
+      min_speed_theta: 0.0
+      acc_lim_x: 2.5
+      acc_lim_y: 0.0
+      acc_lim_theta: 3.2
+      decel_lim_x: -2.5
+      decel_lim_y: 0.0
+      decel_lim_theta: -3.2
+      vx_samples: 20
+      vy_samples: 5
+      vtheta_samples: 20
+      sim_time: 1.7
+      linear_granularity: 0.05
+      angular_granularity: 0.025
+      transform_tolerance: 0.2
+      trans_stopped_velocity: 0.25
+      short_circuit_trajectory_evaluation: True
+      stateful: True
+      critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+      BaseObstacle.scale: 0.02
+      PathAlign.scale: 0.0
+      GoalAlign.scale: 0.0
+      PathDist.scale: 32.0
+      GoalDist.scale: 24.0
+      RotateToGoal.scale: 32.0
+      RotateToGoal.slowing_factor: 5.0
+      RotateToGoal.lookahead_time: -1.0
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      robot_base_frame: "<robot_namespace>/base_link"
+      use_sim_time: True
+      global_frame: <robot_namespace>/odom
+      rolling_window: true
+      width: 3
+      height: 3
+      resolution: 0.05
+      robot_radius: 0.22
+      plugins: ["voxel_layer", "inflation_layer"]
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      voxel_layer:
+        plugin: "nav2_costmap_2d::VoxelLayer"
+        enabled: True
+        publish_voxel_map: False
+        origin_z: 0.0
+        z_resolution: 0.05
+        z_voxels: 16
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: scan
+        scan:
+          topic: /<robot_namespace>/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      robot_base_frame: "<robot_namespace>/base_link"
+      global_frame: "map"
+      use_sim_time: True
+      robot_radius: 0.22
+      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
+      obstacle_layer:
+        plugin: "nav2_costmap_2d::ObstacleLayer"
+        enabled: True
+        observation_sources: scan
+        scan:
+          topic: /<robot_namespace>/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        plugin: "nav2_costmap_2d::StaticLayer"
+        map_subscribe_transient_local: True
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      always_send_full_costmap: True
+
+map_server:
+  ros__parameters:
+    use_sim_time: True
+    yaml_filename: "map_warehouse.yaml"
+    save_map_timeout: 5.0
+    frame_id: "map"
+
+planner_server:
+  ros__parameters:
+    use_sim_time: True
+    planner_plugins: ["GridBased"]
+    GridBased:
+      plugin: "nav2_navfn_planner/NavfnPlanner"
+      tolerance: 0.5
+      use_astar: false
+      allow_unknown: true
+
+smoother_server:
+  ros__parameters:
+    use_sim_time: True
+    robot_base_frame: "<robot_namespace>/base_link"
+
+behavior_server:
+  ros__parameters:
+    costmap_topic: local_costmap/costmap_raw
+    footprint_topic: local_costmap/published_footprint
+    cycle_frequency: 10.0
+    behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"]
+    spin:
+      plugin: "nav2_behaviors/Spin"
+    backup:
+      plugin: "nav2_behaviors/BackUp"
+    drive_on_heading:
+      plugin: "nav2_behaviors/DriveOnHeading"
+    wait:
+      plugin: "nav2_behaviors/Wait"
+    global_frame: <robot_namespace>/odom
+    robot_base_frame: <robot_namespace>/base_link
+    transform_tolerance: 0.1
+    use_sim_time: true
+    simulate_ahead_time: 2.0
+    max_rotational_vel: 1.0
+    min_rotational_vel: 0.4
+    rotational_acc_lim: 3.2
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
+
+waypoint_follower:
+  ros__parameters:
+    loop_rate: 20
+    stop_on_failure: false
+    waypoint_task_executor_plugin: "wait_at_waypoint"
+    wait_at_waypoint:
+      plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+      enabled: True
+      waypoint_pause_duration: 200

+ 300 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/humble/nav2_params.yaml

@@ -0,0 +1,300 @@
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    alpha1: 0.2
+    alpha2: 0.2
+    alpha3: 0.2
+    alpha4: 0.2
+    alpha5: 0.2
+    base_frame_id: "base_link"
+    beam_skip_distance: 0.5
+    beam_skip_error_threshold: 0.9
+    beam_skip_threshold: 0.3
+    do_beamskip: false
+    global_frame_id: "map"
+    map_topic: "map"
+    lambda_short: 0.1
+    laser_likelihood_max_dist: 2.0
+    laser_max_range: 100.0
+    laser_min_range: -1.0
+    laser_model_type: "likelihood_field"
+    max_beams: 60
+    max_particles: 2000
+    min_particles: 500
+    odom_frame_id: "odom"
+    pf_err: 0.05
+    pf_z: 0.99
+    recovery_alpha_fast: 0.0
+    recovery_alpha_slow: 0.0
+    resample_interval: 1
+    robot_model_type: "nav2_amcl::DifferentialMotionModel"
+    save_pose_rate: 0.5
+    sigma_hit: 0.2
+    tf_broadcast: true
+    transform_tolerance: 1.0
+    update_min_a: 0.2
+    update_min_d: 0.25
+    z_hit: 0.5
+    z_max: 0.05
+    z_rand: 0.5
+    z_short: 0.05
+    scan_topic: scan
+    set_initial_pose: False
+
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    global_frame: map
+    robot_base_frame: base_link
+    odom_topic: odom
+    bt_loop_duration: 10
+    default_server_timeout: 20
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
+    # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
+    plugin_lib_names:
+      - nav2_compute_path_to_pose_action_bt_node
+      - nav2_compute_path_through_poses_action_bt_node
+      - nav2_smooth_path_action_bt_node
+      - nav2_follow_path_action_bt_node
+      - nav2_spin_action_bt_node
+      - nav2_wait_action_bt_node
+      - nav2_assisted_teleop_action_bt_node
+      - nav2_back_up_action_bt_node
+      - nav2_drive_on_heading_bt_node
+      - nav2_clear_costmap_service_bt_node
+      - nav2_is_stuck_condition_bt_node
+      - nav2_goal_reached_condition_bt_node
+      - nav2_goal_updated_condition_bt_node
+      - nav2_globally_updated_goal_condition_bt_node
+      - nav2_is_path_valid_condition_bt_node
+      - nav2_initial_pose_received_condition_bt_node
+      - nav2_reinitialize_global_localization_service_bt_node
+      - nav2_rate_controller_bt_node
+      - nav2_distance_controller_bt_node
+      - nav2_speed_controller_bt_node
+      - nav2_truncate_path_action_bt_node
+      - nav2_truncate_path_local_action_bt_node
+      - nav2_goal_updater_node_bt_node
+      - nav2_recovery_node_bt_node
+      - nav2_pipeline_sequence_bt_node
+      - nav2_round_robin_node_bt_node
+      - nav2_transform_available_condition_bt_node
+      - nav2_time_expired_condition_bt_node
+      - nav2_path_expiring_timer_condition
+      - nav2_distance_traveled_condition_bt_node
+      - nav2_single_trigger_bt_node
+      - nav2_goal_updated_controller_bt_node
+      - nav2_is_battery_low_condition_bt_node
+      - nav2_navigate_through_poses_action_bt_node
+      - nav2_navigate_to_pose_action_bt_node
+      - nav2_remove_passed_goals_action_bt_node
+      - nav2_planner_selector_bt_node
+      - nav2_controller_selector_bt_node
+      - nav2_goal_checker_selector_bt_node
+      - nav2_controller_cancel_bt_node
+      - nav2_path_longer_on_approach_bt_node
+      - nav2_wait_cancel_bt_node
+      - nav2_spin_cancel_bt_node
+      - nav2_back_up_cancel_bt_node
+      - nav2_assisted_teleop_cancel_bt_node
+      - nav2_drive_on_heading_cancel_bt_node
+
+bt_navigator_navigate_through_poses_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+bt_navigator_navigate_to_pose_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    controller_frequency: 20.0
+    min_x_velocity_threshold: 0.001
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    progress_checker_plugin: "progress_checker"
+    goal_checker_plugins: ["goal_checker"]
+    controller_plugins: ["FollowPath"]
+
+    # Progress checker parameters
+    progress_checker:
+      plugin: "nav2_controller::SimpleProgressChecker"
+      required_movement_radius: 0.5
+      movement_time_allowance: 10.0
+    # Goal checker parameters
+    goal_checker:
+      plugin: "nav2_controller::SimpleGoalChecker"
+      xy_goal_tolerance: 0.25
+      yaw_goal_tolerance: 0.25
+      stateful: True
+    # DWB parameters
+    FollowPath:
+      plugin: "dwb_core::DWBLocalPlanner"
+      debug_trajectory_details: True
+      min_vel_x: 0.0
+      min_vel_y: 0.0
+      max_vel_x: 0.26
+      max_vel_y: 0.0
+      max_vel_theta: 1.0
+      min_speed_xy: 0.0
+      max_speed_xy: 0.26
+      min_speed_theta: 0.0
+      acc_lim_x: 2.5
+      acc_lim_y: 0.0
+      acc_lim_theta: 3.2
+      decel_lim_x: -2.5
+      decel_lim_y: 0.0
+      decel_lim_theta: -3.2
+      vx_samples: 20
+      vy_samples: 5
+      vtheta_samples: 20
+      sim_time: 1.7
+      linear_granularity: 0.05
+      angular_granularity: 0.025
+      transform_tolerance: 0.2
+      trans_stopped_velocity: 0.25
+      short_circuit_trajectory_evaluation: True
+      stateful: True
+      critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+      BaseObstacle.scale: 0.02
+      PathAlign.scale: 0.0
+      GoalAlign.scale: 0.0
+      PathDist.scale: 32.0
+      GoalDist.scale: 24.0
+      RotateToGoal.scale: 32.0
+      RotateToGoal.slowing_factor: 5.0
+      RotateToGoal.lookahead_time: -1.0
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      robot_base_frame: "base_link"
+      use_sim_time: True
+      global_frame: odom
+      rolling_window: true
+      width: 3
+      height: 3
+      resolution: 0.05
+      robot_radius: 0.22
+      plugins: ["voxel_layer", "inflation_layer"]
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      voxel_layer:
+        plugin: "nav2_costmap_2d::VoxelLayer"
+        enabled: True
+        publish_voxel_map: False
+        origin_z: 0.0
+        z_resolution: 0.05
+        z_voxels: 16
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      robot_base_frame: "base_link"
+      global_frame: "map"
+      use_sim_time: True
+      robot_radius: 0.22
+      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
+      obstacle_layer:
+        plugin: "nav2_costmap_2d::ObstacleLayer"
+        enabled: True
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        plugin: "nav2_costmap_2d::StaticLayer"
+        map_subscribe_transient_local: True
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      always_send_full_costmap: True
+
+map_server:
+  ros__parameters:
+    use_sim_time: True
+    yaml_filename: "map_warehouse.yaml"
+    save_map_timeout: 5.0
+    frame_id: "map"
+
+planner_server:
+  ros__parameters:
+    use_sim_time: True
+    planner_plugins: ["GridBased"]
+    GridBased:
+      plugin: "nav2_navfn_planner/NavfnPlanner"
+      tolerance: 0.5
+      use_astar: false
+      allow_unknown: true
+
+smoother_server:
+  ros__parameters:
+    use_sim_time: True
+    robot_base_frame: "base_link"
+
+behavior_server:
+  ros__parameters:
+    costmap_topic: local_costmap/costmap_raw
+    footprint_topic: local_costmap/published_footprint
+    cycle_frequency: 10.0
+    behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"]
+    spin:
+      plugin: "nav2_behaviors/Spin"
+    backup:
+      plugin: "nav2_behaviors/BackUp"
+    drive_on_heading:
+      plugin: "nav2_behaviors/DriveOnHeading"
+    wait:
+      plugin: "nav2_behaviors/Wait"
+    global_frame: odom
+    robot_base_frame: base_link
+    transform_tolerance: 0.1
+    use_sim_time: true
+    simulate_ahead_time: 2.0
+    max_rotational_vel: 1.0
+    min_rotational_vel: 0.4
+    rotational_acc_lim: 3.2
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
+
+waypoint_follower:
+  ros__parameters:
+    loop_rate: 20
+    stop_on_failure: false
+    waypoint_task_executor_plugin: "wait_at_waypoint"
+    wait_at_waypoint:
+      plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+      enabled: True
+      waypoint_pause_duration: 200

+ 313 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/iron/nav2_multirobot_params.yaml

@@ -0,0 +1,313 @@
+robot_spawner_client:
+  ros__parameters:
+    robot_name: <robot_name>
+    robot_namespace: <robot_namespace>
+    robot_initial_position: [<robot_initial_pose_x>, <robot_initial_pose_y>, <robot_initial_pose_z>]
+
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    alpha1: 0.2
+    alpha2: 0.2
+    alpha3: 0.2
+    alpha4: 0.2
+    alpha5: 0.2
+    base_frame_id: "<robot_namespace>/base_link"
+    beam_skip_distance: 0.5
+    beam_skip_error_threshold: 0.9
+    beam_skip_threshold: 0.3
+    do_beamskip: false
+    global_frame_id: "map"
+    map_topic: "map"
+    lambda_short: 0.1
+    laser_likelihood_max_dist: 2.0
+    laser_max_range: 100.0
+    laser_min_range: -1.0
+    laser_model_type: "<robot_namespace>/likelihood_field"
+    max_beams: 60
+    max_particles: 2000
+    min_particles: 500
+    odom_frame_id: "<robot_namespace>/odom"
+    pf_err: 0.05
+    pf_z: 0.99
+    recovery_alpha_fast: 0.0
+    recovery_alpha_slow: 0.0
+    resample_interval: 1
+    robot_model_type: "nav2_amcl::DifferentialMotionModel"
+    save_pose_rate: 0.5
+    sigma_hit: 0.2
+    tf_broadcast: true
+    transform_tolerance: 1.0
+    update_min_a: 0.2
+    update_min_d: 0.25
+    z_hit: 0.5
+    z_max: 0.05
+    z_rand: 0.5
+    z_short: 0.05
+    scan_topic: scan
+    set_initial_pose: True
+    initial_pose:
+      x: <robot_initial_pose_x>
+      y: <robot_initial_pose_y>
+      z: <robot_initial_pose_z>
+
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    global_frame: map
+    robot_base_frame: <robot_namespace>/base_link
+    odom_topic: odom
+    bt_loop_duration: 10
+    default_server_timeout: 20
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
+    # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
+    plugin_lib_names:
+      - nav2_compute_path_to_pose_action_bt_node
+      - nav2_compute_path_through_poses_action_bt_node
+      - nav2_smooth_path_action_bt_node
+      - nav2_follow_path_action_bt_node
+      - nav2_spin_action_bt_node
+      - nav2_wait_action_bt_node
+      - nav2_assisted_teleop_action_bt_node
+      - nav2_back_up_action_bt_node
+      - nav2_drive_on_heading_bt_node
+      - nav2_clear_costmap_service_bt_node
+      - nav2_is_stuck_condition_bt_node
+      - nav2_goal_reached_condition_bt_node
+      - nav2_goal_updated_condition_bt_node
+      - nav2_globally_updated_goal_condition_bt_node
+      - nav2_is_path_valid_condition_bt_node
+      - nav2_initial_pose_received_condition_bt_node
+      - nav2_reinitialize_global_localization_service_bt_node
+      - nav2_rate_controller_bt_node
+      - nav2_distance_controller_bt_node
+      - nav2_speed_controller_bt_node
+      - nav2_truncate_path_action_bt_node
+      - nav2_truncate_path_local_action_bt_node
+      - nav2_goal_updater_node_bt_node
+      - nav2_recovery_node_bt_node
+      - nav2_pipeline_sequence_bt_node
+      - nav2_round_robin_node_bt_node
+      - nav2_transform_available_condition_bt_node
+      - nav2_time_expired_condition_bt_node
+      - nav2_path_expiring_timer_condition
+      - nav2_distance_traveled_condition_bt_node
+      - nav2_single_trigger_bt_node
+      - nav2_goal_updated_controller_bt_node
+      - nav2_is_battery_low_condition_bt_node
+      - nav2_navigate_through_poses_action_bt_node
+      - nav2_navigate_to_pose_action_bt_node
+      - nav2_remove_passed_goals_action_bt_node
+      - nav2_planner_selector_bt_node
+      - nav2_controller_selector_bt_node
+      - nav2_goal_checker_selector_bt_node
+      - nav2_controller_cancel_bt_node
+      - nav2_path_longer_on_approach_bt_node
+      - nav2_wait_cancel_bt_node
+      - nav2_spin_cancel_bt_node
+      - nav2_back_up_cancel_bt_node
+      - nav2_assisted_teleop_cancel_bt_node
+      - nav2_drive_on_heading_cancel_bt_node
+      - nav2_would_a_controller_recovery_help_condition_bt_node
+      - nav2_would_a_planner_recovery_help_condition_bt_node
+      - nav2_would_a_smoother_recovery_help_condition_bt_node
+
+bt_navigator_navigate_through_poses_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+bt_navigator_navigate_to_pose_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    controller_frequency: 20.0
+    min_x_velocity_threshold: 0.001
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    progress_checker_plugin: "progress_checker"
+    goal_checker_plugins: ["goal_checker"]
+    controller_plugins: ["FollowPath"]
+
+    # Progress checker parameters
+    progress_checker:
+      plugin: "nav2_controller::SimpleProgressChecker"
+      required_movement_radius: 0.5
+      movement_time_allowance: 10.0
+    # Goal checker parameters
+    goal_checker:
+      plugin: "nav2_controller::SimpleGoalChecker"
+      xy_goal_tolerance: 0.25
+      yaw_goal_tolerance: 0.25
+      stateful: True
+    # DWB parameters
+    FollowPath:
+      plugin: "dwb_core::DWBLocalPlanner"
+      debug_trajectory_details: True
+      min_vel_x: 0.0
+      min_vel_y: 0.0
+      max_vel_x: 0.26
+      max_vel_y: 0.0
+      max_vel_theta: 1.0
+      min_speed_xy: 0.0
+      max_speed_xy: 0.26
+      min_speed_theta: 0.0
+      acc_lim_x: 2.5
+      acc_lim_y: 0.0
+      acc_lim_theta: 3.2
+      decel_lim_x: -2.5
+      decel_lim_y: 0.0
+      decel_lim_theta: -3.2
+      vx_samples: 20
+      vy_samples: 5
+      vtheta_samples: 20
+      sim_time: 1.7
+      linear_granularity: 0.05
+      angular_granularity: 0.025
+      transform_tolerance: 0.2
+      trans_stopped_velocity: 0.25
+      short_circuit_trajectory_evaluation: True
+      stateful: True
+      critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+      BaseObstacle.scale: 0.02
+      PathAlign.scale: 0.0
+      GoalAlign.scale: 0.0
+      PathDist.scale: 32.0
+      GoalDist.scale: 24.0
+      RotateToGoal.scale: 32.0
+      RotateToGoal.slowing_factor: 5.0
+      RotateToGoal.lookahead_time: -1.0
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      robot_base_frame: "<robot_namespace>/base_link"
+      use_sim_time: True
+      global_frame: <robot_namespace>/odom
+      rolling_window: true
+      width: 3
+      height: 3
+      resolution: 0.05
+      robot_radius: 0.22
+      plugins: ["voxel_layer", "inflation_layer"]
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      voxel_layer:
+        plugin: "nav2_costmap_2d::VoxelLayer"
+        enabled: True
+        publish_voxel_map: False
+        origin_z: 0.0
+        z_resolution: 0.05
+        z_voxels: 16
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: scan
+        scan:
+          topic: /<robot_namespace>/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      robot_base_frame: "<robot_namespace>/base_link"
+      global_frame: "map"
+      use_sim_time: True
+      robot_radius: 0.22
+      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
+      obstacle_layer:
+        plugin: "nav2_costmap_2d::ObstacleLayer"
+        enabled: True
+        observation_sources: scan
+        scan:
+          topic: /<robot_namespace>/scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        plugin: "nav2_costmap_2d::StaticLayer"
+        map_subscribe_transient_local: True
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      always_send_full_costmap: True
+
+map_server:
+  ros__parameters:
+    use_sim_time: True
+    yaml_filename: "map_warehouse.yaml"
+    save_map_timeout: 5.0
+    frame_id: "map"
+
+planner_server:
+  ros__parameters:
+    use_sim_time: True
+    planner_plugins: ["GridBased"]
+    GridBased:
+      plugin: "nav2_navfn_planner/NavfnPlanner"
+      tolerance: 0.5
+      use_astar: false
+      allow_unknown: true
+
+smoother_server:
+  ros__parameters:
+    use_sim_time: True
+    robot_base_frame: "<robot_namespace>/base_link"
+
+behavior_server:
+  ros__parameters:
+    costmap_topic: local_costmap/costmap_raw
+    footprint_topic: local_costmap/published_footprint
+    cycle_frequency: 10.0
+    behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"]
+    spin:
+      plugin: "nav2_behaviors/Spin"
+    backup:
+      plugin: "nav2_behaviors/BackUp"
+    drive_on_heading:
+      plugin: "nav2_behaviors/DriveOnHeading"
+    wait:
+      plugin: "nav2_behaviors/Wait"
+    global_frame: <robot_namespace>/odom
+    robot_base_frame: <robot_namespace>/base_link
+    transform_tolerance: 0.1
+    use_sim_time: true
+    simulate_ahead_time: 2.0
+    max_rotational_vel: 1.0
+    min_rotational_vel: 0.4
+    rotational_acc_lim: 3.2
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
+
+waypoint_follower:
+  ros__parameters:
+    loop_rate: 20
+    stop_on_failure: false
+    waypoint_task_executor_plugin: "wait_at_waypoint"
+    wait_at_waypoint:
+      plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+      enabled: True
+      waypoint_pause_duration: 200

+ 303 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/params/iron/nav2_params.yaml

@@ -0,0 +1,303 @@
+amcl:
+  ros__parameters:
+    use_sim_time: True
+    alpha1: 0.2
+    alpha2: 0.2
+    alpha3: 0.2
+    alpha4: 0.2
+    alpha5: 0.2
+    base_frame_id: "base_link"
+    beam_skip_distance: 0.5
+    beam_skip_error_threshold: 0.9
+    beam_skip_threshold: 0.3
+    do_beamskip: false
+    global_frame_id: "map"
+    map_topic: "map"
+    lambda_short: 0.1
+    laser_likelihood_max_dist: 2.0
+    laser_max_range: 100.0
+    laser_min_range: -1.0
+    laser_model_type: "likelihood_field"
+    max_beams: 60
+    max_particles: 2000
+    min_particles: 500
+    odom_frame_id: "odom"
+    pf_err: 0.05
+    pf_z: 0.99
+    recovery_alpha_fast: 0.0
+    recovery_alpha_slow: 0.0
+    resample_interval: 1
+    robot_model_type: "nav2_amcl::DifferentialMotionModel"
+    save_pose_rate: 0.5
+    sigma_hit: 0.2
+    tf_broadcast: true
+    transform_tolerance: 1.0
+    update_min_a: 0.2
+    update_min_d: 0.25
+    z_hit: 0.5
+    z_max: 0.05
+    z_rand: 0.5
+    z_short: 0.05
+    scan_topic: scan
+    set_initial_pose: False
+
+bt_navigator:
+  ros__parameters:
+    use_sim_time: True
+    global_frame: map
+    robot_base_frame: base_link
+    odom_topic: odom
+    bt_loop_duration: 10
+    default_server_timeout: 20
+    # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults:
+    # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml
+    # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml
+    # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2.
+    plugin_lib_names:
+      - nav2_compute_path_to_pose_action_bt_node
+      - nav2_compute_path_through_poses_action_bt_node
+      - nav2_smooth_path_action_bt_node
+      - nav2_follow_path_action_bt_node
+      - nav2_spin_action_bt_node
+      - nav2_wait_action_bt_node
+      - nav2_assisted_teleop_action_bt_node
+      - nav2_back_up_action_bt_node
+      - nav2_drive_on_heading_bt_node
+      - nav2_clear_costmap_service_bt_node
+      - nav2_is_stuck_condition_bt_node
+      - nav2_goal_reached_condition_bt_node
+      - nav2_goal_updated_condition_bt_node
+      - nav2_globally_updated_goal_condition_bt_node
+      - nav2_is_path_valid_condition_bt_node
+      - nav2_initial_pose_received_condition_bt_node
+      - nav2_reinitialize_global_localization_service_bt_node
+      - nav2_rate_controller_bt_node
+      - nav2_distance_controller_bt_node
+      - nav2_speed_controller_bt_node
+      - nav2_truncate_path_action_bt_node
+      - nav2_truncate_path_local_action_bt_node
+      - nav2_goal_updater_node_bt_node
+      - nav2_recovery_node_bt_node
+      - nav2_pipeline_sequence_bt_node
+      - nav2_round_robin_node_bt_node
+      - nav2_transform_available_condition_bt_node
+      - nav2_time_expired_condition_bt_node
+      - nav2_path_expiring_timer_condition
+      - nav2_distance_traveled_condition_bt_node
+      - nav2_single_trigger_bt_node
+      - nav2_goal_updated_controller_bt_node
+      - nav2_is_battery_low_condition_bt_node
+      - nav2_navigate_through_poses_action_bt_node
+      - nav2_navigate_to_pose_action_bt_node
+      - nav2_remove_passed_goals_action_bt_node
+      - nav2_planner_selector_bt_node
+      - nav2_controller_selector_bt_node
+      - nav2_goal_checker_selector_bt_node
+      - nav2_controller_cancel_bt_node
+      - nav2_path_longer_on_approach_bt_node
+      - nav2_wait_cancel_bt_node
+      - nav2_spin_cancel_bt_node
+      - nav2_back_up_cancel_bt_node
+      - nav2_assisted_teleop_cancel_bt_node
+      - nav2_drive_on_heading_cancel_bt_node
+      - nav2_would_a_controller_recovery_help_condition_bt_node
+      - nav2_would_a_planner_recovery_help_condition_bt_node
+      - nav2_would_a_smoother_recovery_help_condition_bt_node
+
+bt_navigator_navigate_through_poses_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+bt_navigator_navigate_to_pose_rclcpp_node:
+  ros__parameters:
+    use_sim_time: True
+
+controller_server:
+  ros__parameters:
+    use_sim_time: True
+    controller_frequency: 20.0
+    min_x_velocity_threshold: 0.001
+    min_y_velocity_threshold: 0.5
+    min_theta_velocity_threshold: 0.001
+    progress_checker_plugin: "progress_checker"
+    goal_checker_plugins: ["goal_checker"]
+    controller_plugins: ["FollowPath"]
+
+    # Progress checker parameters
+    progress_checker:
+      plugin: "nav2_controller::SimpleProgressChecker"
+      required_movement_radius: 0.5
+      movement_time_allowance: 10.0
+    # Goal checker parameters
+    goal_checker:
+      plugin: "nav2_controller::SimpleGoalChecker"
+      xy_goal_tolerance: 0.25
+      yaw_goal_tolerance: 0.25
+      stateful: True
+    # DWB parameters
+    FollowPath:
+      plugin: "dwb_core::DWBLocalPlanner"
+      debug_trajectory_details: True
+      min_vel_x: 0.0
+      min_vel_y: 0.0
+      max_vel_x: 0.26
+      max_vel_y: 0.0
+      max_vel_theta: 1.0
+      min_speed_xy: 0.0
+      max_speed_xy: 0.26
+      min_speed_theta: 0.0
+      acc_lim_x: 2.5
+      acc_lim_y: 0.0
+      acc_lim_theta: 3.2
+      decel_lim_x: -2.5
+      decel_lim_y: 0.0
+      decel_lim_theta: -3.2
+      vx_samples: 20
+      vy_samples: 5
+      vtheta_samples: 20
+      sim_time: 1.7
+      linear_granularity: 0.05
+      angular_granularity: 0.025
+      transform_tolerance: 0.2
+      trans_stopped_velocity: 0.25
+      short_circuit_trajectory_evaluation: True
+      stateful: True
+      critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
+      BaseObstacle.scale: 0.02
+      PathAlign.scale: 0.0
+      GoalAlign.scale: 0.0
+      PathDist.scale: 32.0
+      GoalDist.scale: 24.0
+      RotateToGoal.scale: 32.0
+      RotateToGoal.slowing_factor: 5.0
+      RotateToGoal.lookahead_time: -1.0
+
+local_costmap:
+  local_costmap:
+    ros__parameters:
+      robot_base_frame: "base_link"
+      use_sim_time: True
+      global_frame: odom
+      rolling_window: true
+      width: 3
+      height: 3
+      resolution: 0.05
+      robot_radius: 0.22
+      plugins: ["voxel_layer", "inflation_layer"]
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      voxel_layer:
+        plugin: "nav2_costmap_2d::VoxelLayer"
+        enabled: True
+        publish_voxel_map: False
+        origin_z: 0.0
+        z_resolution: 0.05
+        z_voxels: 16
+        max_obstacle_height: 2.0
+        mark_threshold: 0
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        map_subscribe_transient_local: True
+      always_send_full_costmap: True
+
+global_costmap:
+  global_costmap:
+    ros__parameters:
+      robot_base_frame: "base_link"
+      global_frame: "map"
+      use_sim_time: True
+      robot_radius: 0.22
+      plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
+      obstacle_layer:
+        plugin: "nav2_costmap_2d::ObstacleLayer"
+        enabled: True
+        observation_sources: scan
+        scan:
+          topic: /scan
+          max_obstacle_height: 2.0
+          clearing: True
+          marking: True
+          data_type: "LaserScan"
+          raytrace_max_range: 3.0
+          raytrace_min_range: 0.0
+          obstacle_max_range: 2.5
+          obstacle_min_range: 0.0
+      static_layer:
+        plugin: "nav2_costmap_2d::StaticLayer"
+        map_subscribe_transient_local: True
+      inflation_layer:
+        plugin: "nav2_costmap_2d::InflationLayer"
+        cost_scaling_factor: 3.0
+        inflation_radius: 0.55
+      always_send_full_costmap: True
+
+map_server:
+  ros__parameters:
+    use_sim_time: True
+    yaml_filename: "map_warehouse.yaml"
+    save_map_timeout: 5.0
+    frame_id: "map"
+
+planner_server:
+  ros__parameters:
+    use_sim_time: True
+    planner_plugins: ["GridBased"]
+    GridBased:
+      plugin: "nav2_navfn_planner/NavfnPlanner"
+      tolerance: 0.5
+      use_astar: false
+      allow_unknown: true
+
+smoother_server:
+  ros__parameters:
+    use_sim_time: True
+    robot_base_frame: "base_link"
+
+behavior_server:
+  ros__parameters:
+    costmap_topic: local_costmap/costmap_raw
+    footprint_topic: local_costmap/published_footprint
+    cycle_frequency: 10.0
+    behavior_plugins: ["spin", "backup", "drive_on_heading", "wait"]
+    spin:
+      plugin: "nav2_behaviors/Spin"
+    backup:
+      plugin: "nav2_behaviors/BackUp"
+    drive_on_heading:
+      plugin: "nav2_behaviors/DriveOnHeading"
+    wait:
+      plugin: "nav2_behaviors/Wait"
+    global_frame: odom
+    robot_base_frame: base_link
+    transform_tolerance: 0.1
+    use_sim_time: true
+    simulate_ahead_time: 2.0
+    max_rotational_vel: 1.0
+    min_rotational_vel: 0.4
+    rotational_acc_lim: 3.2
+
+robot_state_publisher:
+  ros__parameters:
+    use_sim_time: True
+
+waypoint_follower:
+  ros__parameters:
+    loop_rate: 20
+    stop_on_failure: false
+    waypoint_task_executor_plugin: "wait_at_waypoint"
+    wait_at_waypoint:
+      plugin: "nav2_waypoint_follower::WaitAtWaypoint"
+      enabled: True
+      waypoint_pause_duration: 200

+ 0 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/resource/o3de_fleet_nav


+ 322 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/rviz/nav2_namespaced_view.rviz

@@ -0,0 +1,322 @@
+Panels:
+  - Class: rviz_common/Displays
+    Help Height: 195
+    Name: Displays
+    Property Tree Widget:
+      Expanded:
+        - /Global Options1
+        - /RobotModel1/Status1
+        - /TF1/Frames1
+        - /TF1/Tree1
+        - /Global Planner1/Global Costmap1
+      Splitter Ratio: 0.5833333134651184
+    Tree Height: 464
+  - Class: rviz_common/Selection
+    Name: Selection
+  - Class: rviz_common/Tool Properties
+    Expanded:
+      - /Publish Point1
+    Name: Tool Properties
+    Splitter Ratio: 0.5886790156364441
+  - Class: rviz_common/Views
+    Expanded:
+      - /Current View1
+    Name: Views
+    Splitter Ratio: 0.5
+  - Class: nav2_rviz_plugins/Navigation 2
+    Name: Navigation 2
+Visualization Manager:
+  Class: ""
+  Displays:
+    - Alpha: 0.5
+      Cell Size: 1
+      Class: rviz_default_plugins/Grid
+      Color: 160; 160; 164
+      Enabled: true
+      Line Style:
+        Line Width: 0.029999999329447746
+        Value: Lines
+      Name: Grid
+      Normal Cell Count: 0
+      Offset:
+        X: 0
+        Y: 0
+        Z: 0
+      Plane: XY
+      Plane Cell Count: 10
+      Reference Frame: <Fixed Frame>
+      Value: true
+    - Class: rviz_default_plugins/TF
+      Enabled: true
+      Frame Timeout: 15
+      Frames:
+        All Enabled: false
+      Marker Scale: 1
+      Name: TF
+      Show Arrows: true
+      Show Axes: true
+      Show Names: false
+      Tree:
+        {}
+      Update Interval: 0
+      Value: true
+    - Alpha: 1
+      Autocompute Intensity Bounds: true
+      Autocompute Value Bounds:
+        Max Value: 10
+        Min Value: -10
+        Value: true
+      Axis: Z
+      Channel Name: intensity
+      Class: rviz_default_plugins/LaserScan
+      Color: 255; 0; 0
+      Color Transformer: FlatColor
+      Decay Time: 0
+      Enabled: true
+      Invert Rainbow: false
+      Max Color: 255; 255; 255
+      Max Intensity: 0
+      Min Color: 0; 0; 0
+      Min Intensity: 0
+      Name: LaserScan
+      Position Transformer: XYZ
+      Selectable: true
+      Size (Pixels): 3
+      Size (m): 0.03
+      Style: Flat Squares
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        History Policy: Keep Last
+        Reliability Policy: Best Effort
+        Value: <robot_namespace>/scan
+      Use Fixed Frame: true
+      Use rainbow: true
+      Value: true
+    - Alpha: 1
+      Class: rviz_default_plugins/Map
+      Color Scheme: map
+      Draw Behind: true
+      Enabled: true
+      Name: Map
+      Topic:
+        Depth: 1
+        Durability Policy: Transient Local
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: <robot_namespace>/map
+      Use Timestamp: false
+      Value: true
+    - Alpha: 1
+      Class: nav2_rviz_plugins/ParticleCloud
+      Color: 0; 180; 0
+      Enabled: true
+      Max Arrow Length: 0.3
+      Min Arrow Length: 0.02
+      Name: Amcl Particle Swarm
+      Shape: Arrow (Flat)
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        History Policy: Keep Last
+        Reliability Policy: Best Effort
+        Value: <robot_namespace>/particle_cloud
+      Value: true
+    - Class: rviz_common/Group
+      Displays:
+        - Alpha: 0.30000001192092896
+          Class: rviz_default_plugins/Map
+          Color Scheme: costmap
+          Draw Behind: false
+          Enabled: true
+          Name: Global Costmap
+          Topic:
+            Depth: 1
+            Durability Policy: Transient Local
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/global_costmap/costmap
+          Use Timestamp: false
+          Value: true
+        - Alpha: 1
+          Buffer Length: 1
+          Class: rviz_default_plugins/Path
+          Color: 255; 0; 0
+          Enabled: true
+          Head Diameter: 0.019999999552965164
+          Head Length: 0.019999999552965164
+          Length: 0.30000001192092896
+          Line Style: Lines
+          Line Width: 0.029999999329447746
+          Name: Path
+          Offset:
+            X: 0
+            Y: 0
+            Z: 0
+          Pose Color: 255; 85; 255
+          Pose Style: Arrows
+          Radius: 0.029999999329447746
+          Shaft Diameter: 0.004999999888241291
+          Shaft Length: 0.019999999552965164
+          Topic:
+            Depth: 5
+            Durability Policy: Volatile
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/plan
+          Value: true
+        - Alpha: 1
+          Class: rviz_default_plugins/Polygon
+          Color: 25; 255; 0
+          Enabled: false
+          Name: Polygon
+          Topic:
+            Depth: 5
+            Durability Policy: Volatile
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/global_costmap/published_footprint
+          Value: false
+      Enabled: true
+      Name: Global Planner
+    - Class: rviz_common/Group
+      Displays:
+        - Alpha: 0.699999988079071
+          Class: rviz_default_plugins/Map
+          Color Scheme: costmap
+          Draw Behind: false
+          Enabled: true
+          Name: Local Costmap
+          Topic:
+            Depth: 1
+            Durability Policy: Transient Local
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/local_costmap/costmap
+          Use Timestamp: false
+          Value: true
+        - Alpha: 1
+          Buffer Length: 1
+          Class: rviz_default_plugins/Path
+          Color: 0; 12; 255
+          Enabled: true
+          Head Diameter: 0.30000001192092896
+          Head Length: 0.20000000298023224
+          Length: 0.30000001192092896
+          Line Style: Lines
+          Line Width: 0.029999999329447746
+          Name: Local Plan
+          Offset:
+            X: 0
+            Y: 0
+            Z: 0
+          Pose Color: 255; 85; 255
+          Pose Style: None
+          Radius: 0.029999999329447746
+          Shaft Diameter: 0.10000000149011612
+          Shaft Length: 0.10000000149011612
+          Topic:
+            Depth: 5
+            Durability Policy: Volatile
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/local_plan
+          Value: true
+        - Class: rviz_default_plugins/MarkerArray
+          Enabled: false
+          Name: Trajectories
+          Namespaces:
+            {}
+          Topic:
+            Depth: 5
+            Durability Policy: Volatile
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/marker
+          Value: false
+        - Alpha: 1
+          Class: rviz_default_plugins/Polygon
+          Color: 25; 255; 0
+          Enabled: true
+          Name: Polygon
+          Topic:
+            Depth: 5
+            Durability Policy: Volatile
+            History Policy: Keep Last
+            Reliability Policy: Reliable
+            Value: <robot_namespace>/local_costmap/published_footprint
+          Value: true
+      Enabled: true
+      Name: Controller
+    - Class: rviz_default_plugins/MarkerArray
+      Enabled: true
+      Name: MarkerArray
+      Namespaces:
+        {}
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: <robot_namespace>/waypoints
+      Value: true
+  Enabled: true
+  Global Options:
+    Background Color: 48; 48; 48
+    Fixed Frame: map
+    Frame Rate: 30
+  Name: root
+  Tools:
+    - Class: rviz_default_plugins/MoveCamera
+    - Class: rviz_default_plugins/Select
+    - Class: rviz_default_plugins/FocusCamera
+    - Class: rviz_default_plugins/Measure
+      Line color: 128; 128; 0
+    - Class: rviz_default_plugins/SetInitialPose
+      Topic:
+        Depth: 5
+        Durability Policy: Volatile
+        History Policy: Keep Last
+        Reliability Policy: Reliable
+        Value: <robot_namespace>/initialpose
+    - Class: nav2_rviz_plugins/GoalTool
+  Transformation:
+    Current:
+      Class: rviz_default_plugins/TF
+  Value: true
+  Views:
+    Current:
+      Angle: -1.5700000524520874
+      Class: rviz_default_plugins/TopDownOrtho
+      Enable Stereo Rendering:
+        Stereo Eye Separation: 0.05999999865889549
+        Stereo Focal Distance: 1
+        Swap Stereo Eyes: false
+        Value: false
+      Invert Z Axis: false
+      Name: Current View
+      Near Clip Distance: 0.009999999776482582
+      Scale: 134.638427734375
+      Target Frame: <Fixed Frame>
+      Value: TopDownOrtho (rviz_default_plugins)
+      X: -0.032615214586257935
+      Y: -0.0801941454410553
+    Saved: ~
+Window Geometry:
+  Displays:
+    collapsed: true
+  Height: 610
+  Hide Left Dock: true
+  Hide Right Dock: true
+  Navigation 2:
+    collapsed: false
+  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000208fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d00000208000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e0061007600690067006100740069006f006e00200032000000010c000001390000013900ffffff000000010000010f00000338fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000338000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000003200000020800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+  Selection:
+    collapsed: false
+  Tool Properties:
+    collapsed: false
+  Views:
+    collapsed: true
+  Width: 800
+  X: 920
+  Y: 544

+ 4 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/setup.cfg

@@ -0,0 +1,4 @@
+[develop]
+script_dir=$base/lib/o3de_fleet_nav
+[install]
+install_scripts=$base/lib/o3de_fleet_nav

+ 35 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/setup.py

@@ -0,0 +1,35 @@
+import os
+from glob import glob
+from setuptools import setup
+
+package_name = 'o3de_fleet_nav'
+
+setup(
+    name=package_name,
+    version='0.0.0',
+    packages=[package_name],
+    data_files=[
+        ('share/ament_index/resource_index/packages',
+            ['resource/' + package_name]),
+        ('share/' + package_name, ['package.xml']),
+        (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*launch.[pxy][yma]*'))),
+        (os.path.join('share', package_name, 'maps'), glob(os.path.join('maps', '*.pgm'))),
+        (os.path.join('share', package_name, 'maps'), glob(os.path.join('maps', '*.yaml'))),
+        (os.path.join('share', package_name, 'params', 'iron'), glob(os.path.join('params', 'iron', '*.yaml'))),
+        (os.path.join('share', package_name, 'params', 'humble'), glob(os.path.join('params', 'humble', '*.yaml'))),
+        (os.path.join('share', package_name, 'rviz'), glob(os.path.join('rviz', '*.rviz'))),
+        (os.path.join('share', package_name, 'config'), glob(os.path.join('config', '*.yaml')))
+    ],
+    install_requires=['setuptools'],
+    zip_safe=True,
+    maintainer='pjaroszek',
+    maintainer_email='[email protected]',
+    description='TODO: Package description',
+    license='TODO: License declaration',
+    tests_require=['pytest'],
+    entry_points={
+        'console_scripts': [
+            'robot_spawner = o3de_fleet_nav.robot_spawner:main',
+        ],
+    },
+)

+ 25 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/test/test_copyright.py

@@ -0,0 +1,25 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_copyright.main import main
+import pytest
+
+
+# Remove the `skip` decorator once the source file(s) have a copyright header
[email protected](reason='No copyright header has been placed in the generated source file.')
[email protected]
[email protected]
+def test_copyright():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found errors'

+ 25 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/test/test_flake8.py

@@ -0,0 +1,25 @@
+# Copyright 2017 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_flake8.main import main_with_errors
+import pytest
+
+
[email protected]
[email protected]
+def test_flake8():
+    rc, errors = main_with_errors(argv=[])
+    assert rc == 0, \
+        'Found %d code style errors / warnings:\n' % len(errors) + \
+        '\n'.join(errors)

+ 23 - 0
Templates/Ros2FleetRobotTemplate/Template/Examples/ros2_ws/src/o3de_fleet_nav/test/test_pep257.py

@@ -0,0 +1,23 @@
+# Copyright 2015 Open Source Robotics Foundation, Inc.
+#
+# 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.
+
+from ament_pep257.main import main
+import pytest
+
+
[email protected]
[email protected]
+def test_pep257():
+    rc = main(argv=['.', 'test'])
+    assert rc == 0, 'Found code style errors / warnings'

+ 14 - 15
Templates/Ros2FleetRobotTemplate/Template/Levels/Warehouse/Warehouse.prefab

@@ -92,14 +92,14 @@
                     "Id": 11259578117255245776,
                     "Controller": {
                         "Configuration": {
-                            "Editor entity id": "",
+                            "Editor entity id": "Entity_[112314723493220]",
                             "Spawnables": {
                                 "proteus": {
                                     "assetId": {
-                                        "guid": "{80419AAD-14CF-528D-A477-8B202D4C9B6D}",
-                                        "subId": 1966583575
+                                        "guid": "{D8E729B1-F767-5E45-8D90-7A49CFB9DA4B}",
+                                        "subId": 815852738
                                     },
-                                    "assetHint": "proteus.spawnable"
+                                    "assetHint": "prefabs/proteuslaserscanner.spawnable"
                                 }
                             }
                         }
@@ -397,8 +397,7 @@
                     "Id": 16880285896855930892,
                     "Controller": {
                         "Configuration": {
-                            "Field of View": 60.0,
-                            "EditorEntityId": 13315486001867137160
+                            "Field of View": 60.0
                         }
                     }
                 },
@@ -453,14 +452,8 @@
                 "Component_[5265045084611556958]": {
                     "$type": "EditorDisabledCompositionComponent",
                     "Id": 5265045084611556958,
-                    "DisabledComponents": [
-                        {
-                            "$type": "EditorLookAtComponent",
-                            "Id": 3614169361981986523,
-                            "Target": "",
-                            "ForwardAxis": 2
-                        },
-                        {
+                    "DisabledComponents": {
+                        "Component_[17802058751617023810]": {
                             "$type": "AZ::Render::EditorDepthOfFieldComponent",
                             "Id": 17802058751617023810,
                             "Controller": {
@@ -477,8 +470,14 @@
                                     ]
                                 }
                             }
+                        },
+                        "Component_[3614169361981986523]": {
+                            "$type": "EditorLookAtComponent",
+                            "Id": 3614169361981986523,
+                            "Target": "",
+                            "ForwardAxis": 2
                         }
-                    ]
+                    }
                 },
                 "Component_[5532915187718966079]": {
                     "$type": "AZ::Render::EditorBloomComponent",

A diferenza do arquivo foi suprimida porque é demasiado grande
+ 131 - 0
Templates/Ros2FleetRobotTemplate/Template/Prefabs/ProteusLaserScanner.prefab


+ 110 - 12
Templates/Ros2FleetRobotTemplate/template.json

@@ -1,6 +1,6 @@
 {
     "template_name": "Ros2FleetRobotTemplate",
-    "version": "1.0.0",
+    "version": "1.1.0",
     "origin": "Open 3D Engine Extras",
     "origin_url": "https://github.com/o3de/o3de-extras",
     "repo_uri": "https://raw.githubusercontent.com/o3de/o3de-extras/development",
@@ -247,6 +247,10 @@
             "file": "Passes/Taa.pass",
             "isTemplated": false
         },
+        {
+            "file": "Prefabs/ProteusLaserScanner.prefab",
+            "isTemplated": false
+        },
         {
             "file": "autoexec.cfg",
             "isTemplated": false
@@ -266,7 +270,92 @@
         {
             "file": "project.json",
             "isTemplated": true
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/maps/map_warehouse.yaml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/maps/map_warehouse.pgm",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/resource/o3de_fleet_nav",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/params/humble/nav2_multirobot_params.yaml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/params/humble/nav2_params.yaml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/params/iron/nav2_multirobot_params.yaml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/params/iron/nav2_params.yaml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/setup.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/package.xml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/NOTICE",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/config/fleet_config.yaml",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_rviz_launch.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_nav_launch.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/launch/o3de_fleet_nav_launch.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav/__init__.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav/robot_spawner.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/test/test_pep257.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/test/test_flake8.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/test/test_copyright.py",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/setup.cfg",
+            "isTemplated": false
+        },
+        {
+            "file": "Examples/ros2_ws/src/o3de_fleet_nav/rviz/nav2_namespaced_view.rviz",
+            "isTemplated": false
         }
+        
     ],
     "createDirectories": [
         {
@@ -359,6 +448,9 @@
         {
             "dir": "Shaders"
         },
+        {
+            "dir": "Prefabs"
+        },
         {
             "dir": "Shaders/ShaderResourceGroups"
         },
@@ -366,35 +458,41 @@
             "dir": "cmake"
         },
         {
-            "dir": "proteus_nav"
+            "dir": "Examples"
+        },
+        {
+            "dir": "Examples/ros2_ws"
+        },
+        {
+            "dir": "Examples/ros2_ws/src"
         },
         {
-            "dir": "proteus_nav/src"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/config"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/launch"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/launch"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/launch/__pycache__"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/maps"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/launch/config"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/proteus_nav"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/params"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/resource"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/resource"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/test"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/rviz"
         },
         {
-            "dir": "proteus_nav/src/proteus_nav/test/__pycache__"
+            "dir": "Examples/ros2_ws/src/o3de_fleet_nav/test"
         }
     ],
-    "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2fleetrobottemplate-1.0.0-template.zip"
+    "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2fleetrobottemplate-1.1.0-template.zip"
 }

Algúns arquivos non se mostraron porque demasiados arquivos cambiaron neste cambio