diff --git a/Gems/ROS2/Code/CMakeLists.txt b/Gems/ROS2/Code/CMakeLists.txt index a0ee8699a..f7422b191 100644 --- a/Gems/ROS2/Code/CMakeLists.txt +++ b/Gems/ROS2/Code/CMakeLists.txt @@ -70,8 +70,7 @@ ly_add_target( Gem::LmbrCentral.API ) -target_depends_on_ros2_packages(${gem_name}.Static rclcpp builtin_interfaces std_msgs sensor_msgs nav_msgs tf2_ros ackermann_msgs gazebo_msgs) -target_depends_on_ros2_package(${gem_name}.Static control_toolbox 2.2.0 REQUIRED) +target_depends_on_ros2_packages(${gem_name}.Static rclcpp builtin_interfaces std_msgs sensor_msgs nav_msgs tf2_ros ackermann_msgs gazebo_msgs control_msgs) ly_add_target( NAME ${gem_name}.API HEADERONLY @@ -256,4 +255,3 @@ if(PAL_TRAIT_BUILD_TESTS_SUPPORTED) endif() endif() -add_subdirectory(PythonTests) diff --git a/Gems/ROS2/Code/Include/ROS2/ROS2GemUtilities.h b/Gems/ROS2/Code/Include/ROS2/ROS2GemUtilities.h index 7652da825..d592f1d09 100644 --- a/Gems/ROS2/Code/Include/ROS2/ROS2GemUtilities.h +++ b/Gems/ROS2/Code/Include/ROS2/ROS2GemUtilities.h @@ -9,13 +9,25 @@ #include #include +#include #ifdef ROS2_EDITOR #include #endif + namespace ROS2 { namespace Utils { + //! Checks whether the entity has a component of the given type + //! @param entity pointer to entity + //! @param typeId type of the component + //! @returns true if entity has component with given type + inline bool HasComponentOfType(const AZ::Entity* entity, const AZ::Uuid typeId) + { + auto components = AZ::EntityUtils::FindDerivedComponents(entity, typeId); + return !components.empty(); + } + /// Create component for a given entity in safe way. /// @param entityId entity that will own component /// @param componentType Uuid of component to create @@ -26,7 +38,6 @@ namespace ROS2 /// We should use that that we are not sure if we access eg ROS2FrameComponent in game mode or from Editor /// @param entity pointer to entity eg with GetEntity() /// @return pointer to component with type T - template ComponentType* GetGameOrEditorComponent(const AZ::Entity* entity) { diff --git a/Gems/ROS2/Code/Include/ROS2/Utilities/Controllers/PidConfiguration.h b/Gems/ROS2/Code/Include/ROS2/Utilities/Controllers/PidConfiguration.h index f8602ea5f..e71188ca5 100644 --- a/Gems/ROS2/Code/Include/ROS2/Utilities/Controllers/PidConfiguration.h +++ b/Gems/ROS2/Code/Include/ROS2/Utilities/Controllers/PidConfiguration.h @@ -8,11 +8,11 @@ #pragma once #include -#include namespace ROS2::Controllers { - //! A wrapper for ROS 2 control_toolbox pid controller. + //! A PID controller. + //! Based on a ROS 2 control_toolbox implementation. //! @see control_toolbox. class PidConfiguration { @@ -38,7 +38,7 @@ namespace ROS2::Controllers const bool antiWindup, const double outputLimit); - //! Initialize PID using member fields as set by the user. + //! Initialize the controller void InitializePid(); //! Compute the value of PID command. @@ -54,8 +54,9 @@ namespace ROS2::Controllers double m_iMax = 10.0; //!< maximal allowable integral term. double m_iMin = -10.0; //!< minimal allowable integral term. bool m_antiWindup = false; //!< prevents condition of integrator overflow in integral action. + bool m_initialized = false; //!< is PID initialized. double m_outputLimit = 0.0; //!< limit PID output; set to 0.0 to disable. - - control_toolbox::Pid m_pid; //!< PID implementation object from control_toolbox (of ros2_control). + double m_previousError = 0.0; //!< previous recorded error. + double m_integral = 0.0; //!< integral accumulator. }; } // namespace ROS2::Controllers diff --git a/Gems/ROS2/Code/PythonTests/CMakeLists.txt b/Gems/ROS2/Code/PythonTests/CMakeLists.txt deleted file mode 100644 index 851171d69..000000000 --- a/Gems/ROS2/Code/PythonTests/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT - -if (PAL_TRAIT_BUILD_TESTS_SUPPORTED) - if (PAL_TRAIT_TEST_PYTEST_SUPPORTED) - # PAL_TRAIT_BUILD macros are used by platform detection. - ly_add_pytest( - NAME Gem::${gem_name}.PythonTests - TEST_SUITE smoke - TEST_SERIAL - PATH ${CMAKE_CURRENT_LIST_DIR}/SmokeTests_Periodic.py - RUNTIME_DEPENDENCIES - Legacy::Editor - AZ::AssetProcessor - ${gem_name}.Editor - COMPONENT - SmokeTests - ) - endif () -endif () diff --git a/Gems/ROS2/Code/PythonTests/SmokeTests_Periodic.py b/Gems/ROS2/Code/PythonTests/SmokeTests_Periodic.py deleted file mode 100644 index e29628128..000000000 --- a/Gems/ROS2/Code/PythonTests/SmokeTests_Periodic.py +++ /dev/null @@ -1,19 +0,0 @@ -# -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT -# - -import pytest -from ly_test_tools.o3de.editor_test import EditorTestSuite, EditorSingleTest - - -@pytest.mark.SUITE_periodic # Marks the test suite as being part of a Periodic test suite -@pytest.mark.parametrize("launcher_platform", ['linux_editor']) # This test works on Linux editor -@pytest.mark.parametrize("project", ["AutomatedTesting"]) # Use the AutomatedTesting project -class TestAutomation(EditorTestSuite): - # Declaring a class that extends from EditorSingleTest declares a single test. - class SmokeTests_EnterGameModeWorks(EditorSingleTest): - # This runs a Single Test in a single Editor. For further work check EditorSingleTest siblings - from .tests import SmokeTests_EnterGameModeWorks as test_module diff --git a/Gems/ROS2/Code/PythonTests/__init__.py b/Gems/ROS2/Code/PythonTests/__init__.py deleted file mode 100755 index f5193b300..000000000 --- a/Gems/ROS2/Code/PythonTests/__init__.py +++ /dev/null @@ -1,6 +0,0 @@ -""" -Copyright (c) Contributors to the Open 3D Engine Project. -For complete copyright and license terms please see the LICENSE at the root of this distribution. - -SPDX-License-Identifier: Apache-2.0 OR MIT -""" diff --git a/Gems/ROS2/Code/PythonTests/tests/SmokeTests_EnterGameModeWorks.py b/Gems/ROS2/Code/PythonTests/tests/SmokeTests_EnterGameModeWorks.py deleted file mode 100644 index 86ce4f4f4..000000000 --- a/Gems/ROS2/Code/PythonTests/tests/SmokeTests_EnterGameModeWorks.py +++ /dev/null @@ -1,114 +0,0 @@ -# -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT -# - -# Test Case Title : Check that entering into game mode works - -# List of results that we want to check, this is not 100% necessary but its a good -# practice to make it easier to debug tests. -# Here we define a tuple of tests - -# Paths to ROS rclpy are added directly as pytest is not accessing PYTHONPATH environment variable -import sys - -sys.path.append('/opt/ros/humble/lib/python3.10/site-packages') -sys.path.append('/opt/ros/humble/local/lib/python3.10/dist-packages') - - -class Tests: - enter_game_mode = ("Entered game mode", "Failed to enter game mode") - topics_published = ("Topics were published during game mode", "Failed to publish topics during game mode") - topics_not_published_outside_of_game_mode = ( - "All simulation topics closed", "Failed to close publishers after simulation") - - -def check_result(result, msg): - from editor_python_test_tools.utils import Report - if not result: - Report.result(msg, False) - raise Exception(msg + " : FAILED") - - -def check_topics(): - import rclpy - from rclpy.node import Node - - def get_topic_list(): - node_dummy = Node("_ros2cli_dummy_to_show_topic_list") - result = node_dummy.get_topic_names_and_types() - node_dummy.destroy_node() - return result - - topics = [] - rclpy.init() - topic_list = get_topic_list() - - for info in topic_list: - topics.append(info[0]) - rclpy.shutdown() - return topics - - -def SmokeTest_EnterGameModeWorks(): - # Description: This test checks that entering into game mode works by opening an empty level - # and entering into the game mode. The is in game mode state should be changed after doing it - # Next it checks if there are some additional ROS topics published during the game mode - - # Import report and test helper utilities - from editor_python_test_tools.utils import Report - from editor_python_test_tools.utils import TestHelper as helper - # All exposed python bindings are in azlmbr - import azlmbr.legacy.general as general - - # Required for automated tests - helper.init_idle() - - # Open the level called "DefaultLevel". - # We use a DefaultLevel level for a smoke test. - # ROS2 System Component should publish topics listed below regardless of level - # - /tf - # - /tf_static - # - /clock - helper.open_level(level="DefaultLevel", directory='') - - topics_before_game_mode = check_topics() - - # Using the exposed Python API from editor in CryEditPy.py we can enter into game mode this way - general.enter_game_mode() - - # The script drives the execution of the test, to return the flow back to the editor, - # we will tick it one time - general.idle_wait_frames(1) - - # Now we can use the Report.result() to report the state of a result - # if the second argument is false, it will mark this test as failed, however it will keep going. - Report.result(Tests.enter_game_mode, general.is_in_game_mode()) - - topics_in_game_mode = check_topics() - - Report.result(Tests.topics_published, len(topics_in_game_mode) > len(topics_before_game_mode)) - - # Instead of using Report.result(), you can also use: - # assert is_in_game_mode, "Didn't enter into game mode" - # However this would stop the test at this point and not report anything when it succeeds - - # The test will end at this point, is good practice to exit game mode or reset any changed stated - # *DO NOT* close the editor, the editor will close automatically and report the error code - general.exit_game_mode() - - # this line is needed to update the simulation state - general.idle_wait_frames(1) - - topics_after_game_mode = check_topics() - Report.result(Tests.topics_not_published_outside_of_game_mode, - len(topics_after_game_mode) == len(topics_before_game_mode)) - - -if __name__ == "__main__": - # This utility starts up the test and sets up the state for knowing what test is currently being run - from editor_python_test_tools.utils import Report - - Report.start_test(SmokeTest_EnterGameModeWorks) diff --git a/Gems/ROS2/Code/Source/Camera/CameraSensor.cpp b/Gems/ROS2/Code/Source/Camera/CameraSensor.cpp index da6ea6710..9deb853ff 100644 --- a/Gems/ROS2/Code/Source/Camera/CameraSensor.cpp +++ b/Gems/ROS2/Code/Source/Camera/CameraSensor.cpp @@ -158,15 +158,33 @@ namespace ROS2 m_passHierarchy.push_back("CopyToSwapChain"); m_pipeline->SetDefaultView(m_view); - const AZ::RPI::ViewPtr targetView = m_scene->GetDefaultRenderPipeline()->GetDefaultView(); + UpdateViewAlias(); + + Camera::CameraNotificationBus::Handler::BusConnect(); + } + + void CameraSensor::OnCameraRemoved(const AZ::EntityId& cameraEntityId) + { + UpdateViewAlias(); + } + + void CameraSensor::OnActiveViewChanged(const AZ::EntityId& cameraEntityId) + { + UpdateViewAlias(); + } + + void CameraSensor::UpdateViewAlias() + { if (auto* fp = m_scene->GetFeatureProcessor()) { + const AZ::RPI::ViewPtr targetView = m_scene->GetDefaultRenderPipeline()->GetDefaultView(); fp->SetViewAlias(m_view, targetView); } } CameraSensor::~CameraSensor() { + Camera::CameraNotificationBus::Handler::BusDisconnect(); if (m_scene) { if (auto* fp = m_scene->GetFeatureProcessor()) diff --git a/Gems/ROS2/Code/Source/Camera/CameraSensor.h b/Gems/ROS2/Code/Source/Camera/CameraSensor.h index 43096f9d5..380169352 100644 --- a/Gems/ROS2/Code/Source/Camera/CameraSensor.h +++ b/Gems/ROS2/Code/Source/Camera/CameraSensor.h @@ -10,6 +10,7 @@ #include "CameraPublishers.h" #include #include +#include #include #include #include @@ -20,7 +21,7 @@ namespace ROS2 { //! Class to create camera sensor using Atom renderer //! It creates dedicated rendering pipeline for each camera - class CameraSensor + class CameraSensor : public Camera::CameraNotificationBus::Handler { public: //! Initializes rendering pipeline for the camera sensor. @@ -40,6 +41,12 @@ namespace ROS2 [[nodiscard]] const CameraSensorDescription& GetCameraSensorDescription() const; private: + // CameraNotificationBus overrides + void OnCameraRemoved(const AZ::EntityId& cameraEntityId) override; + void OnActiveViewChanged(const AZ::EntityId& cameraEntityId) override; + + void UpdateViewAlias(); + AZStd::vector m_passHierarchy; AZ::RPI::ViewPtr m_view; AZ::RPI::Scene* m_scene = nullptr; diff --git a/Gems/ROS2/Code/Source/Frame/Conversions/FrameConversion.py b/Gems/ROS2/Code/Source/Frame/Conversions/FrameConversion.py index dd7c2e3e2..a9b6740d5 100644 --- a/Gems/ROS2/Code/Source/Frame/Conversions/FrameConversion.py +++ b/Gems/ROS2/Code/Source/Frame/Conversions/FrameConversion.py @@ -47,6 +47,8 @@ def search_for_components(item, foundComponents, insidePatches=False): "m_template/Joint Name" ]): item["path"] = item["path"].replace("m_template", "ROS2FrameConfiguration") + if item["op"] == "remove" and "ROS2FrameComponent" in item["path"]: + item["path"] = item["path"].replace("ROS2FrameComponent", "ROS2FrameEditorComponent") for key, value in item.items(): search_for_components(value, foundComponents, insidePatches) diff --git a/Gems/ROS2/Code/Source/Frame/ROS2FrameComponent.cpp b/Gems/ROS2/Code/Source/Frame/ROS2FrameComponent.cpp index 20c99557d..b48f8bfa0 100644 --- a/Gems/ROS2/Code/Source/Frame/ROS2FrameComponent.cpp +++ b/Gems/ROS2/Code/Source/Frame/ROS2FrameComponent.cpp @@ -8,7 +8,6 @@ #include "ROS2FrameSystemComponent.h" #include -#include #include #include #include @@ -21,6 +20,9 @@ #include #include #include +#include +#include +#include #include #include @@ -68,17 +70,6 @@ namespace ROS2 // Found the component! return component; } - - //! Checks whether the entity has a component of the given type - //! @param entity pointer to entity - //! @param typeId type of the component - //! @returns true if entity has component with given type - static bool CheckIfEntityHasComponentOfType(const AZ::Entity* entity, const AZ::Uuid typeId) - { - auto components = AZ::EntityUtils::FindDerivedComponents(entity, typeId); - return !components.empty(); - } - } // namespace Internal AZ::JsonSerializationResult::Result JsonFrameComponentConfigSerializer::Load( @@ -160,12 +151,9 @@ namespace ROS2 // Otherwise it'll be dynamic when it has joints and it's not a fixed joint. else { - const bool hasJoints = Internal::CheckIfEntityHasComponentOfType( - m_entity, AZ::Uuid("{B01FD1D2-1D91-438D-874A-BF5EB7E919A8}")); // Physx::JointComponent; - const bool hasFixedJoints = Internal::CheckIfEntityHasComponentOfType( - m_entity, AZ::Uuid("{02E6C633-8F44-4CEE-AE94-DCB06DE36422}")); // Physx::FixedJointComponent - const bool hasArticulations = Internal::CheckIfEntityHasComponentOfType( - m_entity, AZ::Uuid("{48751E98-B35F-4A2F-A908-D9CDD5230264}")); // Physx::ArticulationComponent + const bool hasJoints = Utils::HasComponentOfType(m_entity, PhysX::JointComponent::TYPEINFO_Uuid()); + const bool hasFixedJoints = Utils::HasComponentOfType(m_entity, PhysX::FixedJointComponent::TYPEINFO_Uuid()); + const bool hasArticulations = Utils::HasComponentOfType(m_entity, PhysX::ArticulationLinkComponent::TYPEINFO_Uuid()); m_isDynamic = (hasJoints && !hasFixedJoints) || hasArticulations; } diff --git a/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.cpp b/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.cpp index 2036385e5..28eb67380 100644 --- a/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.cpp +++ b/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.cpp @@ -23,16 +23,6 @@ namespace ROS2 AZStd::bind(&FollowJointTrajectoryActionServer::GoalAcceptedCallback, this, AZStd::placeholders::_1)); } - JointsTrajectoryRequests::TrajectoryActionStatus FollowJointTrajectoryActionServer::GetGoalStatus() const - { - return m_goalStatus; - } - - void FollowJointTrajectoryActionServer::SetGoalSuccess() - { - m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Succeeded; - } - void FollowJointTrajectoryActionServer::CancelGoal(std::shared_ptr result) { AZ_Assert(m_goalHandle, "Invalid goal handle!"); @@ -50,7 +40,6 @@ namespace ROS2 { AZ_Trace("FollowJointTrajectoryActionServer", "Goal succeeded\n"); m_goalHandle->succeed(result); - m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Succeeded; } } @@ -102,7 +91,6 @@ namespace ROS2 return rclcpp_action::CancelResponse::REJECT; } - m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Cancelled; return rclcpp_action::CancelResponse::ACCEPT; } @@ -149,6 +137,5 @@ namespace ROS2 m_goalHandle = goalHandle; // m_goalHandle->execute(); // No need to call this, as we are already executing the goal due to ACCEPT_AND_EXECUTE - m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Executing; } } // namespace ROS2 diff --git a/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.h b/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.h index 2d3eb11f5..a3928984a 100644 --- a/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.h +++ b/Gems/ROS2/Code/Source/Manipulation/FollowJointTrajectoryActionServer.h @@ -32,17 +32,10 @@ namespace ROS2 //! server documentation FollowJointTrajectoryActionServer(const AZStd::string& actionName, const AZ::EntityId& entityId); - //! Return trajectory action status. - //! @return Status of the trajectory execution. - JointsTrajectoryRequests::TrajectoryActionStatus GetGoalStatus() const; - //! Cancel the current goal. //! @param result Result to be passed to through action server to the client. void CancelGoal(std::shared_ptr result); - //! Sets the goal status to success - void SetGoalSuccess(); - //! Report goal success to the action server. //! @param result Result which contains success code. void GoalSuccess(std::shared_ptr result); @@ -56,7 +49,6 @@ namespace ROS2 using TrajectoryActionStatus = JointsTrajectoryRequests::TrajectoryActionStatus; AZ::EntityId m_entityId; - TrajectoryActionStatus m_goalStatus = TrajectoryActionStatus::Idle; rclcpp_action::Server::SharedPtr m_actionServer; std::shared_ptr m_goalHandle; diff --git a/Gems/ROS2/Code/Source/Manipulation/JointUtils.cpp b/Gems/ROS2/Code/Source/Manipulation/JointUtils.cpp new file mode 100644 index 000000000..ac6aeb238 --- /dev/null +++ b/Gems/ROS2/Code/Source/Manipulation/JointUtils.cpp @@ -0,0 +1,31 @@ +/* + * Copyright (c) Contributors to the Open 3D Engine Project. + * For complete copyright and license terms please see the LICENSE at the root of this distribution. + * + * SPDX-License-Identifier: Apache-2.0 OR MIT + * + */ + +#include "JointUtils.h" + +#include +#include +#include +#include +#include +#include + +namespace ROS2::JointUtils +{ + + bool HasNonFixedJoints(const AZ::Entity* entity) + { + const bool hasPrismaticJoints = Utils::HasComponentOfType(entity, PhysX::EditorPrismaticJointComponent::TYPEINFO_Uuid()); + const bool hasBallJoints = Utils::HasComponentOfType(entity, PhysX::EditorBallJointComponent::TYPEINFO_Uuid()); + const bool hasHingeJoints = Utils::HasComponentOfType(entity, PhysX::EditorHingeJointComponent::TYPEINFO_Uuid()); + const bool hasArticulations = Utils::HasComponentOfType(entity, PhysX::EditorArticulationLinkComponent::TYPEINFO_Uuid()); + const bool hasJoints = hasPrismaticJoints || hasBallJoints || hasHingeJoints || hasArticulations; + + return hasJoints; + } +} // namespace ROS2::Utils diff --git a/Gems/ROS2/Code/Source/Manipulation/JointUtils.h b/Gems/ROS2/Code/Source/Manipulation/JointUtils.h new file mode 100644 index 000000000..2273784d1 --- /dev/null +++ b/Gems/ROS2/Code/Source/Manipulation/JointUtils.h @@ -0,0 +1,19 @@ +/* + * Copyright (c) Contributors to the Open 3D Engine Project. + * For complete copyright and license terms please see the LICENSE at the root of this distribution. + * + * SPDX-License-Identifier: Apache-2.0 OR MIT + * + */ + +#pragma once + +#include + +namespace ROS2::JointUtils +{ + //! Check if the entity has any of the non fixed joint or articulation components. + //! @param entity Entity to check. + //! @return True if the entity has any of the joint or articulation components. + bool HasNonFixedJoints(const AZ::Entity* entity); +} // namespace ROS2::Utils diff --git a/Gems/ROS2/Code/Source/Manipulation/JointsManipulationEditorComponent.cpp b/Gems/ROS2/Code/Source/Manipulation/JointsManipulationEditorComponent.cpp index 7429856ad..8d7cfe989 100644 --- a/Gems/ROS2/Code/Source/Manipulation/JointsManipulationEditorComponent.cpp +++ b/Gems/ROS2/Code/Source/Manipulation/JointsManipulationEditorComponent.cpp @@ -7,6 +7,7 @@ */ #include "JointsManipulationEditorComponent.h" +#include "JointUtils.h" #include "JointsManipulationComponent.h" #include #include @@ -108,8 +109,10 @@ namespace ROS2 azrtti_cast(Utils::GetGameOrEditorComponent(entity)); AZ_Assert(frameEditorComponent, "ROS2FrameEditorComponent does not exist!"); + const bool hasNonFixedJoints = JointUtils::HasNonFixedJoints(entity); + AZStd::string jointName(frameEditorComponent->GetJointName().GetCStr()); - if (!jointName.empty()) + if (!jointName.empty() && hasNonFixedJoints) { m_initialPositions.emplace_back(AZStd::make_pair(jointName, configBackup[jointName])); } diff --git a/Gems/ROS2/Code/Source/Manipulation/JointsPositionsEditorComponent.cpp b/Gems/ROS2/Code/Source/Manipulation/JointsPositionsEditorComponent.cpp index f08747bca..8730ee08d 100644 --- a/Gems/ROS2/Code/Source/Manipulation/JointsPositionsEditorComponent.cpp +++ b/Gems/ROS2/Code/Source/Manipulation/JointsPositionsEditorComponent.cpp @@ -9,6 +9,7 @@ #include "JointsPositionsEditorComponent.h" #include "JointPositionsSubscriptionHandler.h" +#include "JointUtils.h" #include "JointsPositionsComponent.h" #include @@ -76,14 +77,17 @@ namespace ROS2 AZ::Crc32 JointsPositionsEditorComponent::FindAllJoints() { + m_jointNames.clear(); AZStd::function getAllJointsHierarchy = [&](const AZ::Entity* entity) { auto* frameEditorComponent = azrtti_cast(Utils::GetGameOrEditorComponent(entity)); AZ_Assert(frameEditorComponent, "ROS2FrameEditorComponent does not exist!"); + const bool hasNonFixedJoints = JointUtils::HasNonFixedJoints(entity); + AZStd::string jointName(frameEditorComponent->GetJointName().GetCStr()); - if (!jointName.empty()) + if (!jointName.empty() && hasNonFixedJoints) { m_jointNames.emplace_back(jointName); } diff --git a/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.cpp b/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.cpp index a4d8b46cd..ed21dd17c 100644 --- a/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.cpp +++ b/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.cpp @@ -12,8 +12,8 @@ #include #include #include -#include #include +#include namespace ROS2 { @@ -92,7 +92,7 @@ namespace ROS2 AZ::Outcome JointsTrajectoryComponent::StartTrajectoryGoal( TrajectoryGoalPtr trajectoryGoal) { - if (m_trajectoryInProgress) + if (m_goalStatus == JointsTrajectoryRequests::TrajectoryActionStatus::Executing) { auto result = JointsTrajectoryComponent::TrajectoryResult(); result.error_code = JointsTrajectoryComponent::TrajectoryResult::INVALID_GOAL; @@ -107,7 +107,7 @@ namespace ROS2 } m_trajectoryGoal = *trajectoryGoal; m_trajectoryExecutionStartTime = rclcpp::Time(ROS2::ROS2Interface::Get()->GetROSTimestamp()); - m_trajectoryInProgress = true; + m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Executing; return AZ::Success(); } @@ -186,13 +186,13 @@ namespace ROS2 AZ::Outcome JointsTrajectoryComponent::CancelTrajectoryGoal() { m_trajectoryGoal.trajectory.points.clear(); - m_trajectoryInProgress = false; + m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Cancelled; return AZ::Success(); } JointsTrajectoryRequests::TrajectoryActionStatus JointsTrajectoryComponent::GetGoalStatus() { - return m_followTrajectoryServer->GetGoalStatus(); + return m_goalStatus; } void JointsTrajectoryComponent::FollowTrajectory(const uint64_t deltaTimeNs) @@ -205,7 +205,6 @@ namespace ROS2 result->error_string = "User Cancelled"; result->error_code = FollowJointTrajectoryActionServer::FollowJointTrajectory::Result::SUCCESSFUL; m_followTrajectoryServer->CancelGoal(result); - m_followTrajectoryServer->SetGoalSuccess(); return; } @@ -219,7 +218,7 @@ namespace ROS2 AZ_TracePrintf("JointsManipulationComponent", "Goal Concluded: all points reached\n"); auto successResult = std::make_shared(); //!< Empty defaults to success. m_followTrajectoryServer->GoalSuccess(successResult); - m_trajectoryInProgress = false; + m_goalStatus = JointsTrajectoryRequests::TrajectoryActionStatus::Succeeded; return; } diff --git a/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.h b/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.h index 5c6ac6c91..5f214b3aa 100644 --- a/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.h +++ b/Gems/ROS2/Code/Source/Manipulation/JointsTrajectoryComponent.h @@ -64,9 +64,9 @@ namespace ROS2 AZStd::string m_followTrajectoryActionName{ "arm_controller/follow_joint_trajectory" }; AZStd::unique_ptr m_followTrajectoryServer; TrajectoryGoal m_trajectoryGoal; + TrajectoryActionStatus m_goalStatus = TrajectoryActionStatus::Idle; rclcpp::Time m_trajectoryExecutionStartTime; ManipulationJoints m_manipulationJoints; - bool m_trajectoryInProgress{ false }; builtin_interfaces::msg::Time m_lastTickTimestamp; //!< ROS 2 Timestamp during last OnTick call }; } // namespace ROS2 diff --git a/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.cpp b/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.cpp index 0e9cb83b5..84011ef07 100644 --- a/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.cpp +++ b/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.cpp @@ -6,10 +6,10 @@ * */ +#include "ROS2OdometrySensorComponent.h" #include #include #include -#include "ROS2OdometrySensorComponent.h" #include #include @@ -55,6 +55,11 @@ namespace ROS2 required.push_back(AZ_CRC_CE("ROS2Frame")); } + void ROS2OdometrySensorComponent::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible) + { + incompatible.push_back(AZ_CRC("ArticulationLinkService")); + } + void ROS2OdometrySensorComponent::OnOdometryEvent(AzPhysics::SceneHandle sceneHandle) { if (m_bodyHandle == AzPhysics::InvalidSimulatedBodyHandle) diff --git a/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.h b/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.h index 27ca208c4..d70ee84b8 100644 --- a/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.h +++ b/Gems/ROS2/Code/Source/Odometry/ROS2OdometrySensorComponent.h @@ -10,10 +10,10 @@ #include #include #include -#include -#include #include #include +#include +#include namespace ROS2 { @@ -21,14 +21,14 @@ namespace ROS2 //! It constructs and publishes an odometry message, which contains information about vehicle velocity and position in space. //! This is a ground truth "sensor", which can be helpful for development and machine learning. //! @see nav_msgs package. - class ROS2OdometrySensorComponent - : public ROS2SensorComponentBase + class ROS2OdometrySensorComponent : public ROS2SensorComponentBase { public: AZ_COMPONENT(ROS2OdometrySensorComponent, "{61387448-63AA-4563-AF87-60C72B05B863}", SensorBaseType); ROS2OdometrySensorComponent(); ~ROS2OdometrySensorComponent() = default; static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required); + static void GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible); static void Reflect(AZ::ReflectContext* context); ////////////////////////////////////////////////////////////////////////// // Component overrides diff --git a/Gems/ROS2/Code/Source/RobotImporter/RobotImporterWidget.cpp b/Gems/ROS2/Code/Source/RobotImporter/RobotImporterWidget.cpp index c3ba307ba..987eadf43 100644 --- a/Gems/ROS2/Code/Source/RobotImporter/RobotImporterWidget.cpp +++ b/Gems/ROS2/Code/Source/RobotImporter/RobotImporterWidget.cpp @@ -656,7 +656,6 @@ namespace ROS2 { const auto filePath = m_robotDescriptionPage->GetModifiedUrdfName(); const auto& streamData = m_modifiedUrdfWindow->GetUrdfData(); - bool success = false; AZ::IO::FileIOBase* fileIo = AZ::IO::FileIOBase::GetInstance(); AZ::IO::FixedMaxPathString resolvedPath; if (fileIo == nullptr || !fileIo->ResolvePath(filePath.c_str(), resolvedPath.data(), resolvedPath.capacity() + 1)) @@ -667,11 +666,10 @@ namespace ROS2 resolvedPath.c_str(), AZ::IO::SystemFile::SF_OPEN_CREATE | AZ::IO::SystemFile::SF_OPEN_CREATE_PATH | AZ::IO::SystemFile::SF_OPEN_WRITE_ONLY)) { - AZ::IO::SizeType bytesWritten = fileHandle.Write(streamData.data(), streamData.size()); - success = (bytesWritten == streamData.size()); + [[maybe_unused]] const AZ::IO::SizeType bytesWritten = fileHandle.Write(streamData.data(), streamData.size()); + AZ_Warning( + "onSaveModifiedUrdfPressed", (bytesWritten == streamData.size()), "Cannot save the output file %s", filePath.c_str()); } - - AZ_Warning("onSaveModifiedUrdfPressed", success, "Cannot save the output file %s", filePath.c_str()); } void RobotImporterWidget::onShowModifiedUrdfPressed() diff --git a/Gems/ROS2/Code/Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp b/Gems/ROS2/Code/Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp index 3a5fe53b4..236c903f3 100644 --- a/Gems/ROS2/Code/Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp +++ b/Gems/ROS2/Code/Source/RobotImporter/SDFormat/Hooks/ROS2SkidSteeringModelHook.cpp @@ -103,7 +103,6 @@ namespace ROS2::SDFormat if (element->HasElement("wheel_separation") && element->HasElement("wheel_diameter")) { // ROS 2 version of either libgazebo_ros_skid_steer_drive.so or libgazebo_ros_diff_drive.so - const auto wheelPairs = element->Get("num_wheel_pairs", 1).first; int dataCount = 0; auto wheelSeparation = element->GetElement("wheel_separation"); @@ -120,10 +119,9 @@ namespace ROS2::SDFormat } else { - constexpr float epsilon = 0.001f; AZ_Warning( "CreateVehicleConfiguration", - AZ::IsClose(configuration.m_wheelbase, wheelSeparation->Get(), epsilon), + AZ::IsClose(configuration.m_wheelbase, wheelSeparation->Get()), "Different wheel separation distances in one model are not supported."); } @@ -138,6 +136,7 @@ namespace ROS2::SDFormat wheelSeparation = wheelSeparation->GetNextElement("wheel_separation"); wheelDiameter = wheelDiameter->GetNextElement("wheel_diameter"); } + [[maybe_unused]] const auto wheelPairs = element->Get("num_wheel_pairs", 1).first; AZ_Warning( "CreateVehicleConfiguration", wheelPairs == configuration.m_axles.size(), diff --git a/Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp b/Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp index 673fd78d3..5fdba1559 100644 --- a/Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp +++ b/Gems/ROS2/Code/Source/Spawner/ROS2SpawnerComponent.cpp @@ -107,6 +107,7 @@ namespace ROS2 { response->model_names.emplace_back(spawnable.first.c_str()); } + response->success = true; } void ROS2SpawnerComponent::SpawnEntity( diff --git a/Gems/ROS2/Code/Source/Utilities/Controllers/PidConfiguration.cpp b/Gems/ROS2/Code/Source/Utilities/Controllers/PidConfiguration.cpp index cbfce6e7f..32b744bf5 100644 --- a/Gems/ROS2/Code/Source/Utilities/Controllers/PidConfiguration.cpp +++ b/Gems/ROS2/Code/Source/Utilities/Controllers/PidConfiguration.cpp @@ -6,6 +6,7 @@ * */ +#include #include #include #include @@ -70,15 +71,59 @@ namespace ROS2::Controllers void PidConfiguration::InitializePid() { - m_pid.initPid(m_p, m_i, m_d, m_iMax, m_iMin, m_antiWindup); + if (m_iMin > m_iMax) + { + AZ_Error("PidConfiguration", false, "Invalid PID configuration."); + } + else + { + m_initialized = true; + } } double PidConfiguration::ComputeCommand(double error, uint64_t deltaTimeNanoseconds) { - double output = m_pid.computeCommand(error, deltaTimeNanoseconds); + const double dt = aznumeric_cast(deltaTimeNanoseconds) / 1.e9; + + if (!m_initialized) + { + AZ_Error("PidConfiguration", false, "PID not initialized, ignoring."); + return 0.0; + } + + if (dt <= 0.0 || !azisfinite(error)) + { + AZ_Warning("PidConfiguration", false, "Invalid PID conditions."); + return 0.0; + } + + const double proportionalTerm = m_p * error; + + m_integral += error * dt; + + if (m_antiWindup && m_i != 0) + { + AZStd::pair bounds = AZStd::minmax(m_iMin / m_i, m_iMax / m_i); + m_integral = AZStd::clamp(m_integral, bounds.first, bounds.second); + } + + double integralTerm = m_i * m_integral; + + if (m_antiWindup) + { + integralTerm = AZStd::clamp(integralTerm, m_iMin, m_iMax); + } + + const double derivative = (error - m_previousError) / dt; + const double derivativeTerm = m_d * derivative; + + m_previousError = error; + + double output = proportionalTerm + integralTerm + derivativeTerm; + if (m_outputLimit > 0.0) { - output = AZStd::clamp(output, -m_outputLimit, m_outputLimit); + output = AZStd::clamp(output, 0.0, m_outputLimit); } return output; } diff --git a/Gems/ROS2/Code/Tests/PIDTest.cpp b/Gems/ROS2/Code/Tests/PIDTest.cpp new file mode 100644 index 000000000..e6d50ec4b --- /dev/null +++ b/Gems/ROS2/Code/Tests/PIDTest.cpp @@ -0,0 +1,195 @@ +/* + * Copyright (c) Contributors to the Open 3D Engine Project. + * For complete copyright and license terms please see the LICENSE at the root of this distribution. + * + * SPDX-License-Identifier: Apache-2.0 OR MIT + * + */ + +#include +#include + +#include + +namespace UnitTest +{ + static const uint64_t secToNanosec = 1e9; + + class PIDTest : public LeakDetectionFixture + { + }; + + TEST_F(PIDTest, iClampAntiwindup) + { + double iGain = 1.0; + double iMin = -1.0; + double iMax = 1.0; + + ROS2::Controllers::PidConfiguration pid(0.0, iGain, 0.0, iMax, iMin, true, 1.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-10.0, 1 * secToNanosec); + EXPECT_EQ(0.0, output); + + output = pid.ComputeCommand(30.0, 1 * secToNanosec); + EXPECT_EQ(1.0, output); + } + + TEST_F(PIDTest, iClampNoGain) + { + double iGain = 0.0; + double iMin = -1.0; + double iMax = 1.0; + + ROS2::Controllers::PidConfiguration pid(0.0, iGain, 0.0, iMax, iMin, false, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_LE(iMin, output); + EXPECT_LE(output, iMax); + EXPECT_EQ(0.0, output); + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_LE(iMin, output); + EXPECT_LE(output, iMax); + EXPECT_EQ(0.0, output); + } + + TEST_F(PIDTest, iAntiwindup) + { + double iGain = 2.0; + double iMin = -1.0; + double iMax = 1.0; + + ROS2::Controllers::PidConfiguration pid(0.0, iGain, 0.0, iMax, iMin, true, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + + output = pid.ComputeCommand(0.5, 1 * secToNanosec); + EXPECT_EQ(0.0, output); + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + } + + TEST_F(PIDTest, negativeIAntiwindup) + { + double iGain = -2.5; + double iMin = -0.2; + double iMax = 0.5; + + ROS2::Controllers::PidConfiguration pid(0.0, iGain, 0.0, iMax, iMin, true, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(0.1, 1 * secToNanosec); + EXPECT_EQ(-0.2, output); + + output = pid.ComputeCommand(0.1, 1 * secToNanosec); + EXPECT_EQ(-0.2, output); + + output = pid.ComputeCommand(-0.05, 1 * secToNanosec); + EXPECT_EQ(-0.075, output); + + output = pid.ComputeCommand(0.1, 1 * secToNanosec); + EXPECT_EQ(-0.2, output); + } + + TEST_F(PIDTest, pOnly) + { + ROS2::Controllers::PidConfiguration pid(1.0, 0.0, 0.0, 0.0, 0.0, false, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-0.5, output); + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-0.5, output); + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + + output = pid.ComputeCommand(0.5, 1 * secToNanosec); + EXPECT_EQ(0.5, output); + } + + TEST_F(PIDTest, iOnly) + { + ROS2::Controllers::PidConfiguration pid(0.0, 1.0, 0.0, 5.0, -5.0, false, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-0.5, output); + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + + output = pid.ComputeCommand(0.0, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + + output = pid.ComputeCommand(0.0, 1 * secToNanosec); + EXPECT_EQ(-1.0, output); + + output = pid.ComputeCommand(1.0, 1 * secToNanosec); + EXPECT_EQ(0.0, output); + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-0.5, output); + } + + TEST_F(PIDTest, dOnly) + { + ROS2::Controllers::PidConfiguration pid(0.0, 0.0, 1.0, 0.0, 0.0, false, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-0.5, output); + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(0.0, output); + + output = pid.ComputeCommand(-0.5, 0 * secToNanosec); + EXPECT_EQ(0.0, output); + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_EQ(-0.5, output); + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(0.5, output); + } + + TEST_F(PIDTest, completePID) + { + ROS2::Controllers::PidConfiguration pid(1.0, 1.0, 1.0, 5.0, -5.0, false, 0.0); + pid.InitializePid(); + + double output = 0.0; + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-1.5, output); + + output = pid.ComputeCommand(-0.5, 1 * secToNanosec); + EXPECT_EQ(-1.5, output); + + output = pid.ComputeCommand(-1.0, 1 * secToNanosec); + EXPECT_EQ(-3.5, output); + } +} // namespace UnitTest diff --git a/Gems/ROS2/Code/ros2_editor_files.cmake b/Gems/ROS2/Code/ros2_editor_files.cmake index f0bfe1474..2cbe99b49 100644 --- a/Gems/ROS2/Code/ros2_editor_files.cmake +++ b/Gems/ROS2/Code/ros2_editor_files.cmake @@ -18,6 +18,8 @@ set(FILES Source/Manipulation/JointsPositionsEditorComponent.h Source/Manipulation/JointsManipulationEditorComponent.cpp Source/Manipulation/JointsManipulationEditorComponent.h + Source/Manipulation/JointUtils.cpp + Source/Manipulation/JointUtils.h Source/RobotImporter/FixURDF/FixURDF.cpp Source/RobotImporter/FixURDF/FixURDF.h Source/RobotImporter/Pages/ModifiedURDFWindow.cpp diff --git a/Gems/ROS2/Code/ros2_tests_files.cmake b/Gems/ROS2/Code/ros2_tests_files.cmake index 463eac5b9..fc66ed24a 100644 --- a/Gems/ROS2/Code/ros2_tests_files.cmake +++ b/Gems/ROS2/Code/ros2_tests_files.cmake @@ -6,4 +6,5 @@ set(FILES Tests/ROS2Test.cpp Tests/GNSSTest.cpp + Tests/PIDTest.cpp ) diff --git a/Gems/ROS2/gem.json b/Gems/ROS2/gem.json index ae4929921..867273ed0 100644 --- a/Gems/ROS2/gem.json +++ b/Gems/ROS2/gem.json @@ -1,6 +1,6 @@ { "gem_name": "ROS2", - "version": "3.2.2", + "version": "3.2.3", "platforms": [ "Linux" ], @@ -23,7 +23,7 @@ "o3de>=2.3.0" ], "icon_path": "preview.png", - "requirements": "Requires ROS 2 installation (supported distributions: Humble). Source your workspace before building the Gem", + "requirements": "Requires ROS 2 installation (supported distributions: Humble, Jazzy). Source your workspace before building the Gem", "documentation_url": "https://docs.o3de.org/docs/user-guide/gems/reference/robotics/ros2/", "dependencies": [ "Atom_RPI", @@ -36,5 +36,5 @@ ], "restricted": "ROS2", "repo_uri": "https://raw.githubusercontent.com/o3de/o3de-extras/development", - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2-3.2.2-gem.zip" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2-3.2.3-gem.zip" } diff --git a/Gems/RosRobotSample/Assets/ROSbot.prefab b/Gems/RosRobotSample/Assets/ROSbot.prefab index 5ba740f22..e5edf61c6 100755 --- a/Gems/RosRobotSample/Assets/ROSbot.prefab +++ b/Gems/RosRobotSample/Assets/ROSbot.prefab @@ -2091,4 +2091,4 @@ } } } -} \ No newline at end of file +} diff --git a/Templates/Ros2FleetRobotTemplate/Template/Gem/gem.json b/Templates/Ros2FleetRobotTemplate/Template/Gem/gem.json index 2dc1f96b6..a8762c271 100644 --- a/Templates/Ros2FleetRobotTemplate/Template/Gem/gem.json +++ b/Templates/Ros2FleetRobotTemplate/Template/Gem/gem.json @@ -21,6 +21,7 @@ "requirements": "", "documentation_url": "", "dependencies": [ + "ROS2>=3.1.0" ], "compatible_engines": [ "o3de-sdk>=1.2.0", diff --git a/Templates/Ros2FleetRobotTemplate/template.json b/Templates/Ros2FleetRobotTemplate/template.json index 78a0b20c1..744636a48 100644 --- a/Templates/Ros2FleetRobotTemplate/template.json +++ b/Templates/Ros2FleetRobotTemplate/template.json @@ -1,6 +1,6 @@ { "template_name": "Ros2FleetRobotTemplate", - "version": "2.0.2", + "version": "2.0.3", "origin": "Open 3D Engine Extras", "origin_url": "https://github.com/o3de/o3de-extras", "repo_uri": "https://raw.githubusercontent.com/o3de/o3de-extras/development", @@ -493,5 +493,5 @@ "dir": "Examples/ros2_ws/src/o3de_fleet_nav/test" } ], - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2fleetrobottemplate-2.0.2-template.zip" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2fleetrobottemplate-2.0.3-template.zip" } diff --git a/Templates/Ros2ProjectTemplate/Docker/Dockerfile b/Templates/Ros2ProjectTemplate/Docker/Dockerfile deleted file mode 100644 index 78e84d48f..000000000 --- a/Templates/Ros2ProjectTemplate/Docker/Dockerfile +++ /dev/null @@ -1,114 +0,0 @@ -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT -# - -ARG ROS_VERSION=jazzy - -FROM ros:${ROS_VERSION}-ros-base - -# Argument to determining the image type ('simulation' or 'navstack') -ARG IMAGE_TYPE=simulation # Default to 'simulation' - -# Arguments for the source repos needed for the Ros2Template sample docker -ARG O3DE_REPO=https://github.com/o3de/o3de.git -ARG O3DE_BRANCH=main - -ARG O3DE_EXTRAS_REPO=https://github.com/o3de/o3de-extras.git -ARG O3DE_EXTRAS_BRANCH=main - -# Additional argument to control build concurrency -ARG CMAKE_JOBS=8 - -ENV WORKSPACE=/data/workspace - -ENV PROJECT_PATH=/data/workspace/Ros2Project - -WORKDIR $WORKSPACE - -RUN apt-get update && apt-get upgrade -y - -# Install packages needed for cloning and building from the source repos -RUN apt-get install -y --no-install-recommends \ - git \ - git-lfs \ - clang \ - ninja-build \ - cmake \ - libglu1-mesa-dev \ - libxcb-xinerama0 \ - libxcb-xinput0 \ - libxcb-xinput-dev \ - libxcb-xfixes0-dev \ - libxcb-xkb-dev \ - libxkbcommon-dev \ - libxkbcommon-x11-dev \ - libfontconfig1-dev \ - libcurl4-openssl-dev \ - libsdl2-dev \ - zlib1g-dev \ - mesa-common-dev \ - libssl-dev libxcb-icccm4 \ - libxcb-image0 \ - libxcb-keysyms1 \ - libxcb-render-util0 \ - libxcb-randr0 \ - libnvidia-gl-470 \ - ufw \ - ros-${ROS_DISTRO}-slam-toolbox \ - ros-${ROS_DISTRO}-navigation2 \ - ros-${ROS_DISTRO}-nav2-bringup \ - ros-${ROS_DISTRO}-pointcloud-to-laserscan \ - ros-${ROS_DISTRO}-gazebo-msgs \ - ros-${ROS_DISTRO}-ackermann-msgs \ - ros-${ROS_DISTRO}-rmw-cyclonedds-cpp \ - ros-${ROS_DISTRO}-control-toolbox \ - ros-${ROS_DISTRO}-nav-msgs \ - ros-${ROS_DISTRO}-desktop - - -# Copy script used to remove build artifacts -COPY cleanup.bash /data/workspace/cleanup.bash - -# Clone and register O3DE repos -RUN if [ "${IMAGE_TYPE}" = "simulation" ]; then \ - cd $WORKSPACE && \ - git clone --recursive $O3DE_REPO && \ - git -C $WORKSPACE/o3de checkout $O3DE_BRANCH &&\ - git -C $WORKSPACE/o3de lfs install && \ - git -C $WORKSPACE/o3de lfs pull && \ - $WORKSPACE/o3de/python/get_python.sh && \ - $WORKSPACE/o3de/scripts/o3de.sh register -ep $WORKSPACE/o3de && \ - git clone $O3DE_EXTRAS_REPO && \ - git -C $WORKSPACE/o3de-extras checkout $O3DE_EXTRAS_BRANCH && \ - $WORKSPACE/o3de/scripts/o3de.sh register -gp $WORKSPACE/o3de-extras/Gems/ROS2 && \ - $WORKSPACE/o3de/scripts/o3de.sh register -gp $WORKSPACE/o3de-extras/Gems/RosRobotSample && \ - $WORKSPACE/o3de/scripts/o3de.sh register -gp $WORKSPACE/o3de-extras/Gems/WarehouseAssets && \ - $WORKSPACE/o3de/scripts/o3de.sh register -gp $WORKSPACE/o3de-extras/Gems/WarehouseSample; \ - elif [ "${IMAGE_TYPE}" = "navstack" ]; then \ - cd $WORKSPACE && \ - git clone $O3DE_EXTRAS_REPO && \ - git -C $WORKSPACE/o3de-extras checkout $O3DE_EXTRAS_BRANCH; \ - else \ - echo "Unsupported IMAGE_TYPE: ${IMAGE_TYPE}" && exit 1; \ - fi - -# Build and cleanup in the same layer to reduce the size -RUN if [ "${IMAGE_TYPE}" = "simulation" ]; then \ - . /opt/ros/${ROS_DISTRO}/setup.sh && \ - $WORKSPACE/o3de/scripts/o3de.sh create-project --project-path $PROJECT_PATH --template-path $WORKSPACE/o3de-extras/Templates/Ros2ProjectTemplate && \ - cmake -B $PROJECT_PATH/build/linux -S $PROJECT_PATH -G "Ninja Multi-Config" -DLY_STRIP_DEBUG_SYMBOLS=TRUE -DLY_DISABLE_TEST_MODULES=ON && \ - cmake --build $PROJECT_PATH/build/linux --config profile --target Ros2Project Editor Ros2Project.Assets Ros2Project.GameLauncher -j $CMAKE_JOBS && \ - $WORKSPACE/cleanup.bash ; \ - fi - -COPY LaunchSimulation.bash /data/workspace/LaunchSimulation.bash -COPY LaunchNavStack.bash /data/workspace/LaunchNavStack.bash - -ENV RMW_IMPLEMENTATION=rmw_cyclonedds_cpp -ENV LAUNCH_FULLSCREEN_OPT=0 -ENV NVIDIA_VISIBLE_DEVICES all -ENV NVIDIA_DRIVER_CAPABILITIES all - -ENTRYPOINT ["/bin/bash"] diff --git a/Templates/Ros2ProjectTemplate/Docker/LaunchNavStack.bash b/Templates/Ros2ProjectTemplate/Docker/LaunchNavStack.bash deleted file mode 100755 index ece16e22e..000000000 --- a/Templates/Ros2ProjectTemplate/Docker/LaunchNavStack.bash +++ /dev/null @@ -1,15 +0,0 @@ -#!/bin/bash - -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT -# - -unset LD_LIBRARY_PATH - -source /opt/ros/$ROS_DISTRO/setup.bash - -cd /data/workspace/o3de-extras/Templates/Ros2ProjectTemplate/Template/Examples/slam_navigation/launch - -ros2 launch navigation.launch.py diff --git a/Templates/Ros2ProjectTemplate/Docker/LaunchSimulation.bash b/Templates/Ros2ProjectTemplate/Docker/LaunchSimulation.bash deleted file mode 100755 index 47a41eaa5..000000000 --- a/Templates/Ros2ProjectTemplate/Docker/LaunchSimulation.bash +++ /dev/null @@ -1,22 +0,0 @@ -#!/bin/bash - -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT -# - -unset LD_LIBRARY_PATH - -source /opt/ros/$ROS_DISTRO/setup.bash - -export LD_LIBRARY_PATH=/data/workspace/Ros2Project/build/linux/bin/profile:$LD_LIBRARY_PATH - -if [ -d /data/workspace/Ros2Project/build/linux/bin/profile ] -then - cd /data/workspace/Ros2Project/build/linux/bin/profile - ./Ros2Project.GameLauncher -r_fullscreen=$LAUNCH_FULLSCREEN_OPT -bg_ConnectToAssetProcessor=0 > /data/workspace/simulation_launch.log 2>&1 -else - echo "Simulation not installed on this image" -fi - diff --git a/Templates/Ros2ProjectTemplate/Docker/README.md b/Templates/Ros2ProjectTemplate/Docker/README.md deleted file mode 100644 index 21f936eb3..000000000 --- a/Templates/Ros2ProjectTemplate/Docker/README.md +++ /dev/null @@ -1,119 +0,0 @@ -# Docker scripts for running the O3DE Ros2Project based on O3DE Ros2ProjectTemplate - -The following Dockerfiles defined in this path will prepare the appropriate ROS2 package (Ubuntu 20.04/Focal + Galactic or Ubuntu 22.04/Jammy + Iron) based environment and build the components necessary to run the O3DE demo project simulator through the O3DE engine using the Ros2Project template. - -## Prerequisites - -* [Hardware requirements of o3de](https://www.o3de.org/docs/welcome-guide/requirements/) -* Ubuntu 20.04 (Focal) or 22.04 (Jammy) -* At least 60 GB of free disk space -* Docker 24.0 installed and configured - * **Note** It is recommended to have Docker installed correctly and in a secure manner so that the docker commands in this guide do not require elevated privileges (sudo) to run them. See [Docker Engine post-installation steps](https://docs.docker.com/engine/install/linux-postinstall/) for more details. -* [NVidia container toolkit](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html#docker) - -## Building the Docker Image - -By default, the docker script provided in this template will build a docker image to run the Ros2Project sample using Ubuntu 22.04 (jammy) with the ROS2 Iron distribution. All obsolete source code, git artifacts, and build artifacts will be removed by the 'cleanup.bash' script when completed. - -Run the following command to build the docker image with a default configuration: - -``` -docker build -t o3de_ros2project:latest -f Dockerfile . -``` - -**Note** -The above command example tags specific commits for O3DE, and the ROS2 gem repos based on known working commits. See the Advanced Options section below for more information. - -This will create a docker image named 'o3de_ros2project' with the tag 'latest' that contains both the simulation launcher and the navigation stack. - -It will also contain helper scripts that will launch either the simulation (LaunchSimulation.bash) or the RViz2 (LaunchNavStack.bash). - -You can also create a separate docker image that only contains the navigation stack and RViz2 by supplying the argument `IMAGE_TYPE` and setting it to 'navstack': - -``` -docker build --build-arg IMAGE_TYPE=navstack -t o3de_ros2project_nav:latest . -``` - -ROS2 allows for communication across multiple docker images running on the same host, provided that they specify the 'bridge' network type when launching. - -## Running the Docker Image - -Launching O3DE applications in a Docker container requires GPU acceleration support. (Make sure that the [nvidia-docker 2](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html#docker) is installed.) - -### Direct Access to the X Server -The simulation docker image should be launched before bringing up the robot application. To run the robot application, first, allow the container root user to access the running X server for display - -``` -xhost +local:root -``` - -Then launch the built simulation docker image with the following command - -``` -docker run --rm --network="bridge" --gpus all -e DISPLAY=:1 -v /tmp/.X11-unix:/tmp/.X11-unix -it o3de_ros2project:latest /data/workspace/LaunchSimulation.bash -``` - -Once the simulation is up and running, launch the navigation stack inside the simulation docker image, which will bring up RViz to control the robot. - -``` -docker run --rm --network="bridge" --gpus all -e DISPLAY=:1 -v /tmp/.X11-unix:/tmp/.X11-unix -it o3de_ros2project:latest /data/workspace/LaunchNavStack.bash - -``` - -If you created a separate docker image 'o3de_ros2project_nav:latest', which only contains the navigation stack and RViz2, you can launch it using that image, provided that the simulation docker image 'o3de_ros2project' is running. - -``` -docker run --rm --network="bridge" --gpus all -e DISPLAY=:1 -v /tmp/.X11-unix:/tmp/.X11-unix -it o3de_ros2project_nav:latest /data/workspace/LaunchNavStack.bash -``` -Make sure to revoke access to the X server when the simulation ends. - -``` -xhost -local:root -``` - -### Running using Rocker - -Alternatively, you can use [Rocker](https://github.com/osrf/rocker) to run a GPU-accelerated docker image. - -Launch the built simulation docker image with the following rocker command - -``` -rocker --x11 --nvidia o3de_ros2project:latest /data/workspace/LaunchSimulation.bash -``` - -Once the simulation is up and running, launch the robot application docker image, which will bring up RViz to control the robot. - -``` -rocker --x11 --nvidia o3de_ros2project:latest /data/workspace/LaunchNavStack.bash -``` - -## Advanced Options - -### Target ROS2 Distribution -The Docker script defaults to building an image based on Ubuntu 22.04 (jammy) and the ROS2 Iron distribution. This can be overridden with a combination if the `ROS_VERSION` and `UBUNTU_VERSION` arguments. - -| ROS2 Distro | Repository | -|---------------|-------------------------------------------| -| galactic | ROS_VERSION=galactic UBUNTU_VERSION=focal | -| humble | ROS_VERSION=humble UBUNTU_VERSION=jammy | -| iron | ROS_VERSION=iron UBUNTU_VERSION=jammy | - -### Custom source repos and branches - -The Dockerscripts use the following arguments to determine the repository to pull the source: - -| Argument | Repository | Default | -|-----------------------|----------------------------|----------------------------------------------| -| O3DE_REPO | O3DE | https://github.com/o3de/o3de.git | -| O3DE_EXTRAS_REPO | O3DE Extras | https://github.com/o3de/o3de-extras.git | - -In addition to repositories, the following arguments target the branch, commit, or tag to pull from their corresponding repository: - -| Argument | Repository | Default | -|-------------------------|----------------------------------|-------------| -| O3DE_BRANCH | O3DE | 2305.0 | -| O3DE_EXTRAS_BRANCH | O3DE Extras | 2305.0 | - -### Optimizing the build process ### -The docker script provides a cmake-specific argument override to control the number of parallel jobs that can be used during the build of the docker image. `CMAKE_JOBS` sets the maximum number of concurrent jobs cmake will run during its build process and defaults to 8 jobs. This number can be adjusted to better suit the hardware which is running the docker image build. - diff --git a/Templates/Ros2ProjectTemplate/Docker/cleanup.bash b/Templates/Ros2ProjectTemplate/Docker/cleanup.bash deleted file mode 100755 index cb4e5e30f..000000000 --- a/Templates/Ros2ProjectTemplate/Docker/cleanup.bash +++ /dev/null @@ -1,43 +0,0 @@ -#!/bin/bash - -# Copyright (c) Contributors to the Open 3D Engine Project. -# For complete copyright and license terms please see the LICENSE at the root of this distribution. -# -# SPDX-License-Identifier: Apache-2.0 OR MIT -# - -# Delete obsolete files after the build of the code and assets are complete - -DELETE_LIST=(~/.o3de/3rdParty/ \ - o3de/.git \ - o3de/AutomatedTesting \ - o3de/python/downloaded_packages \ - o3de/Code \ - o3de/Gems \ - Ros2Project/build/linux/Azcg/ \ - Ros2Project/build/linux/CMake \ - Ros2Project/build/linux/CMakeFiles/ \ - Ros2Project/build/linux/External/ \ - Ros2Project/build/linux/Testing/ \ - Ros2Project/build/linux/_deps/ \ - Ros2Project/build/linux/cmake \ - Ros2Project/build/linux/lib/ \ - Ros2Project/build/linux/o3de/ \ - Ros2Project/build/linux/packages/ \ - Ros2Project/build/linux/runtime_dependencies/ - Ros2Project/build/linux/bin/profile/EditorPlugins \ - Ros2Project/build/linux/bin/profile/Editor \ - Ros2Project/build/linux/bin/profile/AssetProcessor \ - Ros2Project/build/linux/bin/profile/AssetProcessorBatch \ - Ros2Project/build/linux/bin/profile/MaterialEditor \ - Ros2Project/build/linux/bin/profile/AssetBuilder \ - Ros2Project/build/linux/bin/profile/MaterialCanvas ) - -for i in ${DELETE_LIST[@]} -do - echo "Deleting /data/workspace/$i" - rm -rf $i -done - -exit 0 - diff --git a/Templates/Ros2ProjectTemplate/Template/Gem/gem.json b/Templates/Ros2ProjectTemplate/Template/Gem/gem.json index c00215902..2cef09954 100644 --- a/Templates/Ros2ProjectTemplate/Template/Gem/gem.json +++ b/Templates/Ros2ProjectTemplate/Template/Gem/gem.json @@ -24,5 +24,6 @@ ], "documentation_url": "", "dependencies": [ + "ROS2>=3.1.0" ] } diff --git a/Templates/Ros2ProjectTemplate/Template/Levels/DemoLevel/DemoLevel.prefab b/Templates/Ros2ProjectTemplate/Template/Levels/DemoLevel/DemoLevel.prefab index c00b55b7a..0bb41d427 100644 --- a/Templates/Ros2ProjectTemplate/Template/Levels/DemoLevel/DemoLevel.prefab +++ b/Templates/Ros2ProjectTemplate/Template/Levels/DemoLevel/DemoLevel.prefab @@ -268,7 +268,7 @@ "$type": "GenericComponentWrapper", "Id": 2318932367744128274, "m_template": { - "$type": "R2PTSampleComponent", + "$type": "${SanitizedCppName}SampleComponent", "goals": [ "Entity_[549827034797]", "Entity_[545532067501]" diff --git a/Templates/Ros2ProjectTemplate/Template/Registry/load_level.setreg b/Templates/Ros2ProjectTemplate/Template/Registry/load_level.setreg new file mode 100644 index 000000000..f43e361c4 --- /dev/null +++ b/Templates/Ros2ProjectTemplate/Template/Registry/load_level.setreg @@ -0,0 +1,9 @@ +{ + "O3DE": { + "Autoexec": { + "ConsoleCommands": { + "LoadLevel": "demolevel" + } + } + } +} diff --git a/Templates/Ros2ProjectTemplate/Template/autoexec.cfg b/Templates/Ros2ProjectTemplate/Template/autoexec.cfg deleted file mode 100644 index e730d9c94..000000000 --- a/Templates/Ros2ProjectTemplate/Template/autoexec.cfg +++ /dev/null @@ -1 +0,0 @@ -LoadLevel levels/demolevel/demolevel.spawnable diff --git a/Templates/Ros2ProjectTemplate/template.json b/Templates/Ros2ProjectTemplate/template.json index 2f41fa37b..f1094ec32 100644 --- a/Templates/Ros2ProjectTemplate/template.json +++ b/Templates/Ros2ProjectTemplate/template.json @@ -1,6 +1,6 @@ { "template_name": "Ros2ProjectTemplate", - "version": "2.0.2", + "version": "2.0.3", "origin": "Open 3D Engine Extras", "origin_url": "https://github.com/o3de/o3de-extras", "license": "https://github.com/o3de/o3de-extras/tree/development/Templates/Ros2ProjectTemplate/Template/LICENSE.txt", @@ -402,10 +402,6 @@ "file": "ShaderLib/viewsrg.srgi", "isTemplated": true }, - { - "file": "autoexec.cfg", - "isTemplated": false - }, { "file": "game.cfg", "isTemplated": false @@ -561,5 +557,5 @@ } ], "repo_uri": "https://raw.githubusercontent.com/o3de/o3de-extras/development", - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.2-template.zip" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.3-template.zip" } diff --git a/Templates/Ros2RoboticManipulationTemplate/Template/Gem/gem.json b/Templates/Ros2RoboticManipulationTemplate/Template/Gem/gem.json index d55f5a462..522c2836f 100644 --- a/Templates/Ros2RoboticManipulationTemplate/Template/Gem/gem.json +++ b/Templates/Ros2RoboticManipulationTemplate/Template/Gem/gem.json @@ -21,6 +21,7 @@ "requirements": "", "documentation_url": "", "dependencies": [ + "ROS2>=3.1.0" ], "compatible_engines": [ ], diff --git a/Templates/Ros2RoboticManipulationTemplate/template.json b/Templates/Ros2RoboticManipulationTemplate/template.json index ea52beb64..259b61b91 100644 --- a/Templates/Ros2RoboticManipulationTemplate/template.json +++ b/Templates/Ros2RoboticManipulationTemplate/template.json @@ -1,6 +1,6 @@ { "template_name": "Ros2RoboticManipulationTemplate", - "version": "2.0.1", + "version": "2.0.2", "origin": "https://github.com/o3de/o3de-extras", "license": "https://github.com/o3de/o3de-extras/tree/development/Templates/Ros2RoboticManipulationTemplate/Template/LICENSE.txt", "display_name": "ROS2 Robotic Manipulation", @@ -834,5 +834,5 @@ } ], "repo_uri": "https://raw.githubusercontent.com/o3de/o3de-extras/development", - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2roboticmanipulationtemplate-2.0.1-template.zip" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2roboticmanipulationtemplate-2.0.2-template.zip" } diff --git a/repo.json b/repo.json index 892216496..42c3c0e2b 100644 --- a/repo.json +++ b/repo.json @@ -4,7 +4,7 @@ "repo_uri": "https://raw.githubusercontent.com/o3de/o3de-extras/development", "summary": "A repository to hold various gems, projects, and templates for the O3DE engine.", "additional_info": "Extras gems, projects, and templates for O3DE. See the README.md at the root of this repository for more information", - "last_updated": "2024-11-04", + "last_updated": "2025-02-20", "$schemaVersion": "1.0.0", "gems_data": [ { @@ -249,6 +249,28 @@ ], "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2-3.2.2-gem.zip", "sha256": "86bf6c09c2545db10210752e7749ed9d9784e32200196f8f1110bc7a4f704636" + }, + { + "version": "3.2.3", + "origin_url": "https://robotec.ai", + "source_control_uri": "https://github.com/o3de/o3de-extras/development/Gems/ROS2", + "compatible_engines": [ + "o3de-sdk>=2.3.0", + "o3de>=2.3.0" + ], + "requirements": "Requires ROS 2 installation (supported distributions: Humble, Jazzy). Source your workspace before building the Gem", + "documentation_url": "https://docs.o3de.org/docs/user-guide/gems/reference/robotics/ros2/", + "dependencies": [ + "Atom_RPI", + "Atom_Feature_Common", + "Atom_Component_DebugCamera", + "CommonFeaturesAtom", + "PhysX5", + "PrimitiveAssets", + "StartingPointInput" + ], + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2-3.2.3-gem.zip", + "sha256": "903ceef078984711d516ba9ab7466fb2165e9d3d447539cd10460c22d98563db" } ] }, @@ -4330,244 +4352,728 @@ ], "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2fleetrobottemplate-2.0.2-template.zip", "sha256": "7ac04e30e179f36884424049c777502d08a6518f5d4306bc1834177a7927b770" - } - ] - }, - { - "template_name": "Ros2ProjectTemplate", - "version": "1.0.0", - "origin": "Open 3D Engine Extras", - "origin_url": "https://github.com/o3de/o3de-extras", - "license": "https://github.com/o3de/o3de-extras/tree/development/Templates/Ros2ProjectTemplate/Template/LICENSE.txt", - "display_name": "ROS2 Project", - "summary": "Template for ROS2 projects.", - "canonical_tags": [], - "user_tags": [ - "Ros2ProjectTemplate", - "ROS2", - "ROS" - ], - "icon_path": "preview.png", - "copyFiles": [ - { - "file": ".gitattributes", - "isTemplated": false - }, - { - "file": ".gitignore", - "isTemplated": false - }, - { - "file": "CMakeLists.txt", - "isTemplated": true - }, - { - "file": "cmake/EngineFinder.cmake", - "isTemplated": true - }, - { - "file": "Config/default_aws_resource_mappings.json", - "isTemplated": false - }, - { - "file": "Config/shader_global_build_options.json", - "isTemplated": false - }, - { - "file": "Gem/${NameLower}_files.cmake", - "isTemplated": true - }, - { - "file": "Gem/${NameLower}_shared_files.cmake", - "isTemplated": true - }, - { - "file": "Gem/CMakeLists.txt", - "isTemplated": true - }, - { - "file": "Gem/Include/${Name}/${Name}Bus.h", - "isTemplated": true - }, - { - "file": "Gem/Platform/Android/${NameLower}_android_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Android/${NameLower}_shared_android_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Android/PAL_android.cmake", - "isTemplated": true - }, - { - "file": "Gem/Platform/Linux/${NameLower}_linux_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Linux/${NameLower}_shared_linux_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Linux/PAL_linux.cmake", - "isTemplated": true - }, - { - "file": "Gem/Platform/Mac/${NameLower}_mac_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Mac/${NameLower}_shared_mac_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Mac/PAL_mac.cmake", - "isTemplated": true - }, - { - "file": "Gem/Platform/Windows/${NameLower}_shared_windows_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Windows/${NameLower}_windows_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/Windows/PAL_windows.cmake", - "isTemplated": true - }, - { - "file": "Gem/Platform/iOS/${NameLower}_ios_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/iOS/${NameLower}_shared_ios_files.cmake", - "isTemplated": false - }, - { - "file": "Gem/Platform/iOS/PAL_ios.cmake", - "isTemplated": true - }, - { - "file": "Gem/Registry/assetprocessor_settings.setreg", - "isTemplated": true - }, - { - "file": "Gem/Source/${Name}Module.cpp", - "isTemplated": true - }, - { - "file": "Gem/Source/${Name}SystemComponent.cpp", - "isTemplated": true - }, - { - "file": "Gem/Source/${Name}SystemComponent.h", - "isTemplated": true - }, - { - "file": "Gem/enabled_gems.cmake", - "isTemplated": true - }, - { - "file": "Gem/gem.json", - "isTemplated": true - }, - { - "file": "Levels/DemoLevel/DemoLevel.prefab", - "isTemplated": false - }, - { - "file": "Platform/Android/android_project.cmake", - "isTemplated": false - }, - { - "file": "Platform/Android/android_project.json", - "isTemplated": true - }, - { - "file": "Platform/Linux/linux_project.cmake", - "isTemplated": false - }, - { - "file": "Platform/Linux/linux_project.json", - "isTemplated": false - }, - { - "file": "Platform/Mac/mac_project.cmake", - "isTemplated": false - }, - { - "file": "Platform/Mac/mac_project.json", - "isTemplated": false - }, - { - "file": "Platform/Windows/windows_project.cmake", - "isTemplated": false - }, - { - "file": "Platform/Windows/windows_project.json", - "isTemplated": false - }, - { - "file": "Platform/iOS/ios_project.cmake", - "isTemplated": false - }, - { - "file": "Platform/iOS/ios_project.json", - "isTemplated": false - }, - { - "file": "Registry/assetprocessor_settings.setreg", - "isTemplated": true - }, - { - "file": "Registry/awscoreconfiguration.setreg", - "isTemplated": false - }, - { - "file": "Registry/editorpreferences.setreg", - "isTemplated": false - }, - { - "file": "Registry/physxsystemconfiguration.setreg", - "isTemplated": false - }, - { - "file": "Registry/sceneassetimporter.setreg", - "isTemplated": false - }, - { - "file": "Resources/GameSDK.ico", - "isTemplated": false - }, - { - "file": "Resources/LegacyLogoLauncher.bmp", - "isTemplated": false - }, - { - "file": "Resources/Platform/Mac/Images.xcassets/Contents.json", - "isTemplated": false - }, - { - "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/Contents.json", - "isTemplated": false - }, - { - "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128.png", - "isTemplated": false - }, - { - "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128_2x.png", - "isTemplated": false - }, - { - "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16.png", - "isTemplated": false - }, - { - "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16_2x.png", - "isTemplated": false + }, + { + "version": "2.0.3", + "copyFiles": [ + { + "file": ".gitignore", + "isTemplated": false + }, + { + "file": "CMakeLists.txt", + "isTemplated": true + }, + { + "file": "Config/shader_global_build_options.json", + "isTemplated": false + }, + { + "file": "Gem/${Name}_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/${Name}_shared_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/CMakeLists.txt", + "isTemplated": true + }, + { + "file": "Gem/Include/${Name}/${Name}Bus.h", + "isTemplated": true + }, + { + "file": "Gem/Platform/Linux/${Name}_linux_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Linux/${Name}_shared_linux_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Linux/PAL_linux.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Mac/${Name}_mac_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Mac/${Name}_shared_mac_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Mac/PAL_mac.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Windows/${Name}_shared_windows_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Windows/${Name}_windows_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Windows/PAL_windows.cmake", + "isTemplated": true + }, + { + "file": "Gem/Registry/assetprocessor_settings.setreg", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}Module.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.h", + "isTemplated": true + }, + { + "file": "Gem/gem.json", + "isTemplated": true + }, + { + "file": "Levels/Warehouse/Warehouse.prefab", + "isTemplated": false + }, + { + "file": "Levels/playground/playground.prefab", + "isTemplated": false + }, + { + "file": "Platform/Linux/linux_project.cmake", + "isTemplated": true + }, + { + "file": "Platform/Linux/linux_project.json", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.cmake", + "isTemplated": true + }, + { + "file": "Platform/Mac/mac_project.json", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.cmake", + "isTemplated": true + }, + { + "file": "Platform/Windows/windows_project.json", + "isTemplated": false + }, + { + "file": "Registry/assetprocessor_settings.setreg", + "isTemplated": false + }, + { + "file": "Registry/awscoreconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxdebugconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxdefaultsceneconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxsystemconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/ros2.setreg", + "isTemplated": false + }, + { + "file": "Resources/GameSDK.ico", + "isTemplated": false + }, + { + "file": "Resources/LegacyLogoLauncher.bmp", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_32.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_32_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_512.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_512_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Info.plist", + "isTemplated": true + }, + { + "file": "ShaderLib/README.md", + "isTemplated": false + }, + { + "file": "ShaderLib/scenesrg.srgi", + "isTemplated": true + }, + { + "file": "ShaderLib/viewsrg.srgi", + "isTemplated": true + }, + { + "file": "Passes/ContrastAdaptiveSharpening.pass", + "isTemplated": false + }, + { + "file": "Passes/MainRenderPipeline.azasset", + "isTemplated": false + }, + { + "file": "Passes/PostProcessParent.pass", + "isTemplated": false + }, + { + "file": "Passes/SMAAConfiguration.azasset", + "isTemplated": false + }, + { + "file": "Passes/Taa.pass", + "isTemplated": false + }, + { + "file": "Prefabs/ProteusLaserScanner.prefab", + "isTemplated": false + }, + { + "file": "autoexec.cfg", + "isTemplated": false + }, + { + "file": "cmake/EngineFinder.cmake", + "isTemplated": false + }, + { + "file": "game.cfg", + "isTemplated": false + }, + { + "file": "preview.png", + "isTemplated": false + }, + { + "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/jazzy/nav2_multirobot_params.yaml", + "isTemplated": false + }, + { + "file": "Examples/ros2_ws/src/o3de_fleet_nav/params/jazzy/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": [ + { + "dir": "Assets" + }, + { + "dir": "Config" + }, + { + "dir": "Gem" + }, + { + "dir": "Gem/Include" + }, + { + "dir": "Gem/Include/${Name}" + }, + { + "dir": "Gem/Platform" + }, + { + "dir": "Gem/Platform/Linux" + }, + { + "dir": "Gem/Platform/Mac" + }, + { + "dir": "Gem/Platform/Windows" + }, + { + "dir": "Gem/Registry" + }, + { + "dir": "Gem/Source" + }, + { + "dir": "Levels" + }, + { + "dir": "Levels/Warehouse" + }, + { + "dir": "Levels/playground" + }, + { + "dir": "Levels/playground/_savebackup" + }, + { + "dir": "Levels/playground/_savebackup/2023-02-21 [13.25.33]" + }, + { + "dir": "Passes" + }, + { + "dir": "Platform" + }, + { + "dir": "Platform/Android" + }, + { + "dir": "Platform/Linux" + }, + { + "dir": "Platform/Mac" + }, + { + "dir": "Platform/Windows" + }, + { + "dir": "Registry" + }, + { + "dir": "Resources" + }, + { + "dir": "Resources/Platform" + }, + { + "dir": "Resources/Platform/Mac" + }, + { + "dir": "Resources/Platform/Mac/Images.xcassets" + }, + { + "dir": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset" + }, + { + "dir": "ShaderLib" + }, + { + "dir": "Shaders" + }, + { + "dir": "Prefabs" + }, + { + "dir": "Shaders/ShaderResourceGroups" + }, + { + "dir": "cmake" + }, + { + "dir": "Examples" + }, + { + "dir": "Examples/ros2_ws" + }, + { + "dir": "Examples/ros2_ws/src" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/config" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/launch" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/maps" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/o3de_fleet_nav" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/params" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/resource" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/rviz" + }, + { + "dir": "Examples/ros2_ws/src/o3de_fleet_nav/test" + } + ], + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2fleetrobottemplate-2.0.3-template.zip", + "sha256": "1fdb529bb39cbe1248b3af2ef6531cf1e95b8aadaf6db6aace0a2e221da67fd4" + } + ] + }, + { + "template_name": "Ros2ProjectTemplate", + "version": "1.0.0", + "origin": "Open 3D Engine Extras", + "origin_url": "https://github.com/o3de/o3de-extras", + "license": "https://github.com/o3de/o3de-extras/tree/development/Templates/Ros2ProjectTemplate/Template/LICENSE.txt", + "display_name": "ROS2 Project", + "summary": "Template for ROS2 projects.", + "canonical_tags": [], + "user_tags": [ + "Ros2ProjectTemplate", + "ROS2", + "ROS" + ], + "icon_path": "preview.png", + "copyFiles": [ + { + "file": ".gitattributes", + "isTemplated": false + }, + { + "file": ".gitignore", + "isTemplated": false + }, + { + "file": "CMakeLists.txt", + "isTemplated": true + }, + { + "file": "cmake/EngineFinder.cmake", + "isTemplated": true + }, + { + "file": "Config/default_aws_resource_mappings.json", + "isTemplated": false + }, + { + "file": "Config/shader_global_build_options.json", + "isTemplated": false + }, + { + "file": "Gem/${NameLower}_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/${NameLower}_shared_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/CMakeLists.txt", + "isTemplated": true + }, + { + "file": "Gem/Include/${Name}/${Name}Bus.h", + "isTemplated": true + }, + { + "file": "Gem/Platform/Android/${NameLower}_android_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Android/${NameLower}_shared_android_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Android/PAL_android.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Linux/${NameLower}_linux_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Linux/${NameLower}_shared_linux_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Linux/PAL_linux.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Mac/${NameLower}_mac_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Mac/${NameLower}_shared_mac_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Mac/PAL_mac.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Windows/${NameLower}_shared_windows_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Windows/${NameLower}_windows_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Windows/PAL_windows.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/iOS/${NameLower}_ios_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/iOS/${NameLower}_shared_ios_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/iOS/PAL_ios.cmake", + "isTemplated": true + }, + { + "file": "Gem/Registry/assetprocessor_settings.setreg", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}Module.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.h", + "isTemplated": true + }, + { + "file": "Gem/enabled_gems.cmake", + "isTemplated": true + }, + { + "file": "Gem/gem.json", + "isTemplated": true + }, + { + "file": "Levels/DemoLevel/DemoLevel.prefab", + "isTemplated": false + }, + { + "file": "Platform/Android/android_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Android/android_project.json", + "isTemplated": true + }, + { + "file": "Platform/Linux/linux_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Linux/linux_project.json", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.json", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.json", + "isTemplated": false + }, + { + "file": "Platform/iOS/ios_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/iOS/ios_project.json", + "isTemplated": false + }, + { + "file": "Registry/assetprocessor_settings.setreg", + "isTemplated": true + }, + { + "file": "Registry/awscoreconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/editorpreferences.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxsystemconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/sceneassetimporter.setreg", + "isTemplated": false + }, + { + "file": "Resources/GameSDK.ico", + "isTemplated": false + }, + { + "file": "Resources/LegacyLogoLauncher.bmp", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16_2x.png", + "isTemplated": false }, { "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256.png", @@ -4869,7 +5375,441 @@ "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-1.0.0-template.zip" }, { - "version": "1.1.0", + "version": "1.1.0", + "copyFiles": [ + { + "file": ".clang-format", + "isTemplated": false + }, + { + "file": ".gitattributes", + "isTemplated": false + }, + { + "file": ".gitignore", + "isTemplated": false + }, + { + "file": "CMakeLists.txt", + "isTemplated": true + }, + { + "file": "cmake/EngineFinder.cmake", + "isTemplated": true + }, + { + "file": "Config/default_aws_resource_mappings.json", + "isTemplated": false + }, + { + "file": "Config/shader_global_build_options.json", + "isTemplated": false + }, + { + "file": "Gem/${NameLower}_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/${NameLower}_editor_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/${NameLower}_shared_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/${NameLower}_editor_shared_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/CMakeLists.txt", + "isTemplated": true + }, + { + "file": "Gem/Include/${Name}/${Name}Bus.h", + "isTemplated": true + }, + { + "file": "Gem/Platform/Android/${NameLower}_android_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Android/${NameLower}_shared_android_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Android/PAL_android.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Linux/${NameLower}_linux_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Linux/${NameLower}_shared_linux_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Linux/PAL_linux.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Mac/${NameLower}_mac_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Mac/${NameLower}_shared_mac_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Mac/PAL_mac.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Windows/${NameLower}_shared_windows_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Windows/${NameLower}_windows_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Windows/PAL_windows.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/iOS/${NameLower}_ios_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/iOS/${NameLower}_shared_ios_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/iOS/PAL_ios.cmake", + "isTemplated": true + }, + { + "file": "Gem/Registry/assetprocessor_settings.setreg", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}Module.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}EditorModule.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}ModuleInterface.h", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.h", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}EditorSystemComponent.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}EditorSystemComponent.h", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SampleComponent.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SampleComponent.h", + "isTemplated": true + }, + { + "file": "Gem/gem.json", + "isTemplated": true + }, + { + "file": "Levels/DemoLevel/DemoLevel.prefab", + "isTemplated": true + }, + { + "file": "Platform/Android/android_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Android/android_project.json", + "isTemplated": true + }, + { + "file": "Platform/Linux/linux_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Linux/linux_project.json", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.json", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.json", + "isTemplated": false + }, + { + "file": "Platform/iOS/ios_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/iOS/ios_project.json", + "isTemplated": false + }, + { + "file": "Registry/assetprocessor_settings.setreg", + "isTemplated": true + }, + { + "file": "Registry/awscoreconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/editorpreferences.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxsystemconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/sceneassetimporter.setreg", + "isTemplated": false + }, + { + "file": "Resources/GameSDK.ico", + "isTemplated": false + }, + { + "file": "Resources/LegacyLogoLauncher.bmp", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_32.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_32_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_512.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_512_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Info.plist", + "isTemplated": true + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/iPadLaunchImage1024x768.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/iPadLaunchImage1536x2048.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/iPadLaunchImage2048x1536.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/iPadLaunchImage768x1024.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/iPhoneLaunchImage640x1136.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/LaunchImage.launchimage/iPhoneLaunchImage640x960.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadAppIcon152x152.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadAppIcon76x76.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadProAppIcon167x167.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadSettingsIcon29x29.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadSettingsIcon58x58.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadSpotlightIcon40x40.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPadSpotlightIcon80x80.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPhoneAppIcon120x120.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPhoneAppIcon180x180.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPhoneSettingsIcon58x58.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPhoneSettingsIcon87x87.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPhoneSpotlightIcon120x120.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Images.xcassets/AppIcon.appiconset/iPhoneSpotlightIcon80x80.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/iOS/Info.plist", + "isTemplated": true + }, + { + "file": "ShaderLib/README.md", + "isTemplated": false + }, + { + "file": "ShaderLib/scenesrg.srgi", + "isTemplated": true + }, + { + "file": "ShaderLib/viewsrg.srgi", + "isTemplated": true + }, + { + "file": "autoexec.cfg", + "isTemplated": false + }, + { + "file": "game.cfg", + "isTemplated": false + }, + { + "file": "preview.png", + "isTemplated": false + }, + { + "file": "project.json", + "isTemplated": true + }, + { + "file": "Examples/slam_navigation/launch/config/config.rviz", + "isTemplated": false + }, + { + "file": "Examples/slam_navigation/README.md", + "isTemplated": false + }, + { + "file": "Examples/slam_navigation/launch/config/navigation_params_humble.yaml", + "isTemplated": false + }, + { + "file": "Examples/slam_navigation/launch/config/navigation_params_jazzy.yaml", + "isTemplated": false + }, + { + "file": "Examples/slam_navigation/launch/config/slam_params.yaml", + "isTemplated": false + }, + { + "file": "Examples/slam_navigation/launch/navigation.launch.py", + "isTemplated": false + }, + { + "file": "Examples/slam_navigation/launch/slam.launch.py", + "isTemplated": false + } + ], + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-1.1.0-template.zip" + }, + { + "version": "2.0.0", "copyFiles": [ { "file": ".clang-format", @@ -5300,10 +6240,11 @@ "isTemplated": false } ], - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-1.1.0-template.zip" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.0-template.zip", + "sha256": "9d10edb8e3c51358ffcfc7a255af0db34981dafa3a37dd36ba68dda2c56e6866" }, { - "version": "2.0.0", + "version": "2.0.1", "copyFiles": [ { "file": ".clang-format", @@ -5525,6 +6466,10 @@ "file": "Registry/sceneassetimporter.setreg", "isTemplated": false }, + { + "file": "Registry/ros2.setreg", + "isTemplated": false + }, { "file": "Resources/GameSDK.ico", "isTemplated": false @@ -5734,11 +6679,11 @@ "isTemplated": false } ], - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.0-template.zip", - "sha256": "9d10edb8e3c51358ffcfc7a255af0db34981dafa3a37dd36ba68dda2c56e6866" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.1-template.zip", + "sha256": "dd56a62e5fa1cd7d412962382845885170edcc1373c1af4b388331f073404c9d" }, { - "version": "2.0.1", + "version": "2.0.2", "copyFiles": [ { "file": ".clang-format", @@ -6173,11 +7118,11 @@ "isTemplated": false } ], - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.1-template.zip", - "sha256": "dd56a62e5fa1cd7d412962382845885170edcc1373c1af4b388331f073404c9d" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.2-template.zip", + "sha256": "47192251cb1035ff041831e82f6062c8d3e6ed19f67a1b8dc34e46f8ce9dc8f0" }, { - "version": "2.0.2", + "version": "2.0.3", "copyFiles": [ { "file": ".clang-format", @@ -6567,10 +7512,6 @@ "file": "ShaderLib/viewsrg.srgi", "isTemplated": true }, - { - "file": "autoexec.cfg", - "isTemplated": false - }, { "file": "game.cfg", "isTemplated": false @@ -6612,8 +7553,8 @@ "isTemplated": false } ], - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.2-template.zip", - "sha256": "47192251cb1035ff041831e82f6062c8d3e6ed19f67a1b8dc34e46f8ce9dc8f0" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2projecttemplate-2.0.3-template.zip", + "sha256": "8ac02c3c0341804653a5a41b300f0bf9edff33f75076b5853f91a45e10b3826a" } ] }, @@ -7458,7 +8399,722 @@ "sha256": "0534490ddee493b0744a76493c1551879fb803890ed123c786e1699c5ddd1e13" }, { - "version": "2.0.1", + "version": "2.0.1", + "copyFiles": [ + { + "file": "CMakeLists.txt", + "isTemplated": true + }, + { + "file": "Assets/Room/Room.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Desk_M_Desk.material", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Desk.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Floor/plane_divided_DefaultMaterial_Ambient.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Floor/plane_divided_DefaultMaterial_Height.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Floor/plane_divided_DefaultMaterial_Base_color.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Floor/plane_divided_DefaultMaterial_Normal.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Floor/plane_divided_DefaultMaterial_Metallic.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Floor/plane_divided_DefaultMaterial_Roughness.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Desk/Room_M_Desk_Normal.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Desk/Room_M_Desk_Base_color.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Desk/Room_M_Desk_Height.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Desk/Room_M_Desk_Roughness.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Desk/Room_M_Desk_Metallic.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Desk/Room_M_Desk_Ambient.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Walls/Room_M_Walls_Height.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Walls/Room_M_Walls_Normal.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Walls/Room_M_Walls_Ambient.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Walls/Room_M_Walls_Roughness.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Walls/Room_M_Walls_Base_color.png", + "isTemplated": "false" + }, + { + "file": "Assets/Room/Textures/Walls/Room_M_Walls_Metallic.png", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/Box2.prefab", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/ConveyorBelt.fbx.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/ConveyorBelt_guards_segment.fbx.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/ConveyorBelt.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/conveyor_belt.physxmaterial", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/conveyor_guards.physxmaterial", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/ConveyorBelt_effector.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/ConveyorBelt_effector.fbx.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/Factory/ConveyorLine/ConveyorBelt_guards_segment.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/UR10_M_UR10.material", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/UR10.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/Textures/RoboticArm.json", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/Textures/UR10_Robotic_arm_Roughness.M_UR10.png", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/Textures/UR10_Robotic_arm_Metallic.M_UR10.png", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/Textures/UR10_Robotic_arm_BaseColor.M_UR10.png", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/Textures/UR10_Robotic_arm_Emissive.M_UR10.png", + "isTemplated": "false" + }, + { + "file": "Assets/UR10_pretty/Textures/UR10_Robotic_arm_Height.M_UR10.png", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/hand_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link4_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link1.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/finger_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/hand.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link3_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link2_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link0.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link5_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link6_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link3_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link6.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link2.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link3.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link5.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link2_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/finger.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/finger_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link4.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/hand_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link2.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link7.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link7_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link1_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link0_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link6.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/hand.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/finger.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link4.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link1.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link6_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link1_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link3.dae", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link7_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link5_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link5.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link4_c.stl", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link0.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link0_c.stl.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/UrdfImporter/1440394708_panda/link7.dae.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Gripper_collider.stl", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Gripper.dae", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Textures/Gripper-BaseColor.png", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Textures/Gripper-Specular.png", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Textures/Gripper-Roughness.png", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Textures/Gripper-Metallic.png", + "isTemplated": "false" + }, + { + "file": "Assets/Gripper/Textures/Gripper-Normal.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/ToyBox.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/BoxTriangle.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/BoxCube.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/BoxTriangle.fbx.assetinfo", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/BoxCyllinder.fbx", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Glossiness.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Metallic.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Emissive.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Normal.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Height.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Roughness.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_BaseMap.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/BoxToyPuzzle_MCube_pazzle_Specular.1001.png", + "isTemplated": "false" + }, + { + "file": "Assets/BoxToyPuzzle/texture/Roughness/MCube_pazzle_Roughness.1001.png", + "isTemplated": "false" + }, + { + "file": "Config/shader_global_build_options.json", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/Atom Default Environment_434B3A4E-7927-4EB4-B568-D0D75E72D270_ProbeData_lutrgba16f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/Atom Default Environment_691C813B-A7DA-435B-BE78-904F41AAECDD_Distance_lutrg32f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/Atom Default Environment_9DD87531-9B21-45AC-8169-4B6209456C02_Irradiance_lutrgba16f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/GI_4C638236-E6F7-413A-B1DF-26DA87A6CDC0_ProbeData_lutrgba16f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/GI_9A063636-4E64-4E87-8052-E1427ED3EC2C_Distance_lutrg32f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/GI_C092EE63-F1F9-43CC-93B5-19168F3EEADA_Irradiance_lutrgba16f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/Diffuse_Probe_Grid_1C06FE02-367E-4D6E-B8AE-9A48F2AF5F75_Irradiance_lutrgba16f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/Diffuse_Probe_Grid_4F50E1BF-2C8C-44EB-8183-34101107473C_Distance_lutrg32f.dds", + "isTemplated": false + }, + { + "file": "DiffuseProbeGrids/Diffuse_Probe_Grid_ABC8A956-D89D-4CDB-829B-EF1DD8DE5404_ProbeData_lutrgba16f.dds", + "isTemplated": false + }, + { + "file": "Examples/panda_moveit_config_demo.launch.py", + "isTemplated": false + }, + { + "file": "Examples/panda_moveit_config_demo.rviz", + "isTemplated": false + }, + { + "file": "Gem/${Name}_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/${Name}_shared_files.cmake", + "isTemplated": true + }, + { + "file": "Gem/CMakeLists.txt", + "isTemplated": true + }, + { + "file": "Gem/Include/${Name}/${Name}Bus.h", + "isTemplated": true + }, + { + "file": "Gem/Platform/Linux/${Name}_linux_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Linux/${Name}_shared_linux_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Linux/PAL_linux.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Mac/${Name}_mac_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Mac/${Name}_shared_mac_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Mac/PAL_mac.cmake", + "isTemplated": true + }, + { + "file": "Gem/Platform/Windows/${Name}_shared_windows_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Windows/${Name}_windows_files.cmake", + "isTemplated": false + }, + { + "file": "Gem/Platform/Windows/PAL_windows.cmake", + "isTemplated": true + }, + { + "file": "Gem/Registry/assetprocessor_settings.setreg", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}Module.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.cpp", + "isTemplated": true + }, + { + "file": "Gem/Source/${Name}SystemComponent.h", + "isTemplated": true + }, + { + "file": "Gem/gem.json", + "isTemplated": true + }, + { + "file": "Levels/RoboticPalletization/RoboticPalletization.prefab", + "isTemplated": false + }, + { + "file": "Levels/RoboticManipulation/RoboticManipulation.prefab", + "isTemplated": false + }, + { + "file": "Passes/ContrastAdaptiveSharpening.pass", + "isTemplated": false + }, + { + "file": "Passes/MainRenderPipeline.azasset", + "isTemplated": false + }, + { + "file": "Passes/PostProcessParent.pass", + "isTemplated": false + }, + { + "file": "Passes/SMAAConfiguration.azasset", + "isTemplated": false + }, + { + "file": "Passes/Taa.pass", + "isTemplated": false + }, + { + "file": "Platform/Linux/linux_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Linux/linux_project.json", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Mac/mac_project.json", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.cmake", + "isTemplated": false + }, + { + "file": "Platform/Windows/windows_project.json", + "isTemplated": false + }, + { + "file": "Prefabs/PandaRobot.prefab", + "isTemplated": false + }, + { + "file": "ReflectionProbes/Entity6__8035B0D1-451A-4226-A488-0C8E6949F6F5__iblspecularcm256.dds", + "isTemplated": false + }, + { + "file": "Registry/assetprocessor_settings.setreg", + "isTemplated": false + }, + { + "file": "Registry/awscoreconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxdebugconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxdefaultsceneconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/physxsystemconfiguration.setreg", + "isTemplated": false + }, + { + "file": "Registry/sceneassetimporter.setreg", + "isTemplated": false + }, + { + "file": "Registry/ros2.setreg", + "isTemplated": false + }, + { + "file": "Resources/GameSDK.ico", + "isTemplated": false + }, + { + "file": "Resources/LegacyLogoLauncher.bmp", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_128_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_16_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_256_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_32.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_32_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_512.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/AppIcon.appiconset/icon_512_2x.png", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Images.xcassets/Contents.json", + "isTemplated": false + }, + { + "file": "Resources/Platform/Mac/Info.plist", + "isTemplated": true + }, + { + "file": "ShaderLib/README.md", + "isTemplated": false + }, + { + "file": "ShaderLib/scenesrg.srgi", + "isTemplated": false + }, + { + "file": "ShaderLib/viewsrg.srgi", + "isTemplated": false + }, + { + "file": "cmake/EngineFinder.cmake", + "isTemplated": false + }, + { + "file": "user/Registry/editorpreferences.setreg", + "isTemplated": false + }, + { + "file": "user/Registry/ViewBookmarks/robotic-arm_1671539006337141059.setreg", + "isTemplated": false + }, + { + "file": "user/Registry/ViewBookmarks/RoboticPalletization_1691268770764352914.setreg", + "isTemplated": false + }, + { + "file": "game.cfg", + "isTemplated": false + }, + { + "file": "preview.png", + "isTemplated": false + }, + { + "file": "project.json", + "isTemplated": true + } + ], + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2roboticmanipulationtemplate-2.0.1-template.zip", + "sha256": "a78b0915bbf915c3470c95da234e49a21e6b67236ff66560a6e7ddc942c5ecd1" + }, + { + "version": "2.0.2", "copyFiles": [ { "file": "CMakeLists.txt", @@ -8169,8 +9825,8 @@ "isTemplated": true } ], - "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2roboticmanipulationtemplate-2.0.1-template.zip", - "sha256": "a78b0915bbf915c3470c95da234e49a21e6b67236ff66560a6e7ddc942c5ecd1" + "download_source_uri": "https://github.com/o3de/o3de-extras/releases/download/2.0/ros2roboticmanipulationtemplate-2.0.2-template.zip", + "sha256": "718e6e95914fee3b84ba7bdabbba150672a624f3cc62c1671c1b40b9db5d9178" } ] }