소스 검색

SimulationInterfacesROS2 Gem clean up (#859)

* Service handlers gathered in common container
* Added possibility to delay service response
* Interface file moved to dedicated directory
* Fixed behaviour for delayed service response
* Changes based on tests results
---------

Signed-off-by: Norbert Prokopiuk <[email protected]>
Norbert Prokopiuk 5 달 전
부모
커밋
e75f67b06d
23개의 변경된 파일226개의 추가작업 그리고 337개의 파일을 삭제
  1. 14 37
      Gems/SimulationInterfacesROS2/Code/Source/Clients/SimulationInterfacesROS2SystemComponent.cpp
  2. 1 2
      Gems/SimulationInterfacesROS2/Code/Source/Clients/SimulationInterfacesROS2SystemComponent.h
  3. 24 0
      Gems/SimulationInterfacesROS2/Code/Source/Interfaces/IROS2HandlerBase.h
  4. 8 23
      Gems/SimulationInterfacesROS2/Code/Source/Services/DeleteEntityServiceHandler.cpp
  5. 12 12
      Gems/SimulationInterfacesROS2/Code/Source/Services/DeleteEntityServiceHandler.h
  6. 2 20
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesServiceHandler.cpp
  7. 11 10
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesServiceHandler.h
  8. 2 20
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesStatesServiceHandler.cpp
  9. 11 9
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesStatesServiceHandler.h
  10. 6 25
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntityStateServiceHandler.cpp
  11. 11 10
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntityStateServiceHandler.h
  12. 5 30
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetSimulationFeaturesServiceHandler.cpp
  13. 11 10
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetSimulationFeaturesServiceHandler.h
  14. 2 19
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetSpawnablesServiceHandler.cpp
  15. 11 9
      Gems/SimulationInterfacesROS2/Code/Source/Services/GetSpawnablesServiceHandler.h
  16. 57 3
      Gems/SimulationInterfacesROS2/Code/Source/Services/ROS2HandlerBaseClass.h
  17. 3 19
      Gems/SimulationInterfacesROS2/Code/Source/Services/SetEntityStateServiceHandler.cpp
  18. 11 9
      Gems/SimulationInterfacesROS2/Code/Source/Services/SetEntityStateServiceHandler.h
  19. 12 27
      Gems/SimulationInterfacesROS2/Code/Source/Services/SpawnEntityServiceHandler.cpp
  20. 11 12
      Gems/SimulationInterfacesROS2/Code/Source/Services/SpawnEntityServiceHandler.h
  21. 0 29
      Gems/SimulationInterfacesROS2/Code/Source/Utils/ServicesConfig.h
  22. 0 1
      Gems/SimulationInterfacesROS2/Code/Source/Utils/Utils.h
  23. 1 1
      Gems/SimulationInterfacesROS2/Code/simulationinterfacesros2_private_files.cmake

+ 14 - 37
Gems/SimulationInterfacesROS2/Code/Source/Clients/SimulationInterfacesROS2SystemComponent.cpp

@@ -7,8 +7,8 @@
  */
 
 #include "SimulationInterfacesROS2SystemComponent.h"
+#include "Services/ROS2HandlerBaseClass.h"
 #include "SimulationInterfacesROS2/SimulationInterfacesROS2RequestBus.h"
-#include "Utils/ServicesConfig.h"
 #include <AzCore/std/string/string.h>
 
 #include <ROS2/ROS2Bus.h>
@@ -25,14 +25,12 @@ namespace SimulationInterfacesROS2
     {
         template<typename T>
         void RegisterInterface(
-            AZStd::unordered_map<AZStd::string, AZStd::shared_ptr<ROS2HandlerBase>>& interfacesMap,
-            rclcpp::Node::SharedPtr ros2Node,
-            const AZStd::string& serviceType,
-            const AZStd::string& defaultName)
+            AZStd::unordered_map<AZStd::string, AZStd::shared_ptr<IROS2HandlerBase>>& interfacesMap, rclcpp::Node::SharedPtr ros2Node)
         {
-            // add all known/implemented interfaces
-            auto serviceName = RegistryUtilities::GetServiceName(serviceType);
-            interfacesMap[serviceType] = AZStd::make_shared<T>(ros2Node, serviceName.empty() ? defaultName : serviceName);
+            AZStd::shared_ptr service = AZStd::make_shared<T>();
+            service->CreateService(ros2Node);
+            interfacesMap[service->GetTypeName()] = AZStd::move(service);
+            service.reset();
         };
     } // namespace
 
@@ -79,35 +77,14 @@ namespace SimulationInterfacesROS2
         rclcpp::Node::SharedPtr ros2Node = rclcpp::Node::SharedPtr(ROS2::ROS2Interface::Get()->GetNode());
         AZ_Assert(ros2Node, "ROS2 node is not available.");
 
-        RegisterInterface<DeleteEntityServiceHandler>(
-            m_availableRos2Interface, ros2Node, AZStd::string(DeleteEntityService), AZStd::string(DeleteEntityServiceDefaultName));
-
-        RegisterInterface<GetEntitiesServiceHandler>(
-            m_availableRos2Interface, ros2Node, AZStd::string(GetEntitiesService), AZStd::string(GetEntitiesServiceDefaultName));
-
-        RegisterInterface<GetEntitiesStatesServiceHandler>(
-            m_availableRos2Interface,
-            ros2Node,
-            AZStd::string(GetEntitiesStatesService),
-            AZStd::string(GetEntitiesStatesServiceDefaultName));
-
-        RegisterInterface<GetEntityStateServiceHandler>(
-            m_availableRos2Interface, ros2Node, AZStd::string(GetEntityStateService), AZStd::string(GetEntityStateServiceDefaultName));
-
-        RegisterInterface<GetSpawnablesServiceHandler>(
-            m_availableRos2Interface, ros2Node, AZStd::string(GetSpawnablesService), AZStd::string(GetSpawnablesServiceDefaultName));
-
-        RegisterInterface<SetEntityStateServiceHandler>(
-            m_availableRos2Interface, ros2Node, AZStd::string(SetEntityStateService), AZStd::string(SetEntityStateServiceDefaultName));
-
-        RegisterInterface<SpawnEntityServiceHandler>(
-            m_availableRos2Interface, ros2Node, AZStd::string(SpawnEntityService), AZStd::string(SpawnEntityServiceDefaultName));
-
-        RegisterInterface<GetSimulationFeaturesServiceHandler>(
-            m_availableRos2Interface,
-            ros2Node,
-            AZStd::string(GetSimulationFeaturesService),
-            AZStd::string(GetSimulationFeaturesServiceDefaultName));
+        RegisterInterface<DeleteEntityServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<GetEntitiesServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<GetEntitiesStatesServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<GetEntityStateServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<GetSpawnablesServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<SetEntityStateServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<SpawnEntityServiceHandler>(m_availableRos2Interface, ros2Node);
+        RegisterInterface<GetSimulationFeaturesServiceHandler>(m_availableRos2Interface, ros2Node);
     }
 
     void SimulationInterfacesROS2SystemComponent::Deactivate()

+ 1 - 2
Gems/SimulationInterfacesROS2/Code/Source/Clients/SimulationInterfacesROS2SystemComponent.h

@@ -21,7 +21,6 @@
 #include "Services/SetEntityStateServiceHandler.h"
 #include "Services/SpawnEntityServiceHandler.h"
 #include "SimulationInterfacesROS2/SimulationInterfacesROS2RequestBus.h"
-#include "Utils/ServicesConfig.h"
 #include <AzCore/std/containers/unordered_map.h>
 #include <AzCore/std/optional.h>
 #include <AzCore/std/smart_ptr/shared_ptr.h>
@@ -56,7 +55,7 @@ namespace SimulationInterfacesROS2
         AZStd::unordered_set<AZ::u8> GetSimulationFeatures() override;
 
     private:
-        AZStd::unordered_map<AZStd::string, AZStd::shared_ptr<ROS2HandlerBase>> m_availableRos2Interface;
+        AZStd::unordered_map<AZStd::string, AZStd::shared_ptr<IROS2HandlerBase>> m_availableRos2Interface;
     };
 
 } // namespace SimulationInterfacesROS2

+ 24 - 0
Gems/SimulationInterfacesROS2/Code/Source/Interfaces/IROS2HandlerBase.h

@@ -0,0 +1,24 @@
+/*
+ * 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 <AzCore/std/containers/unordered_set.h>
+#include <AzCore/std/string/string_view.h>
+
+namespace SimulationInterfacesROS2
+{
+    // common interface to store all simulation feature ros2  handlers in common container
+    class IROS2HandlerBase
+    {
+    public:
+        virtual ~IROS2HandlerBase() = default;
+        virtual AZStd::unordered_set<AZ::u8> GetProvidedFeatures() = 0;
+        virtual AZStd::string_view GetTypeName() const = 0;
+        virtual AZStd::string_view GetDefaultName() const = 0;
+    };
+} // namespace SimulationInterfacesROS2

+ 8 - 23
Gems/SimulationInterfacesROS2/Code/Source/Services/DeleteEntityServiceHandler.cpp

@@ -7,43 +7,27 @@
  */
 
 #include "DeleteEntityServiceHandler.h"
+#include <AzCore/std/optional.h>
 #include <AzCore/std/string/string.h>
 #include <SimulationInterfaces/SimulationEntityManagerRequestBus.h>
 
 namespace SimulationInterfacesROS2
 {
-    DeleteEntityServiceHandler::DeleteEntityServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_deleteEntityService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](
-                const ServiceHandle service_handle, const std::shared_ptr<rmw_request_id_t> header, const std::shared_ptr<Request> request)
-            {
-                HandleServiceRequest(service_handle, header, request);
-            });
-    }
 
-    DeleteEntityServiceHandler::~DeleteEntityServiceHandler()
-    {
-        if (m_deleteEntityService)
-        {
-            m_deleteEntityService.reset();
-        }
-    }
     AZStd::unordered_set<AZ::u8> DeleteEntityServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::DELETING };
     }
 
-    void DeleteEntityServiceHandler::HandleServiceRequest(
-        const ServiceHandle service_handle, const std::shared_ptr<rmw_request_id_t> header, const std::shared_ptr<Request> request)
+    AZStd::optional<DeleteEntityServiceHandler::Response> DeleteEntityServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
-        AZStd::string entityName = request->entity.c_str();
+        AZStd::string entityName = request.entity.c_str();
+
         SimulationInterfaces::SimulationEntityManagerRequestBus::Broadcast(
             &SimulationInterfaces::SimulationEntityManagerRequests::DeleteEntity,
             entityName,
-            [service_handle, header](const AZ::Outcome<void, SimulationInterfaces::FailedResult>& outcome)
+            [this](const AZ::Outcome<void, SimulationInterfaces::FailedResult>& outcome)
             {
                 Response response;
                 if (outcome.IsSuccess())
@@ -56,7 +40,8 @@ namespace SimulationInterfacesROS2
                     response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
                     response.result.error_message = failedResult.error_string.c_str();
                 }
-                service_handle->send_response(*header, response);
+                SendResponse(response);
             });
+        return AZStd::nullopt;
     }
 } // namespace SimulationInterfacesROS2

+ 12 - 12
Gems/SimulationInterfacesROS2/Code/Source/Services/DeleteEntityServiceHandler.h

@@ -16,23 +16,23 @@
 namespace SimulationInterfacesROS2
 {
 
-    class DeleteEntityServiceHandler : public ROS2HandlerBase
+    class DeleteEntityServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::DeleteEntity>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::DeleteEntity;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
-        using ServiceHandle = std::shared_ptr<rclcpp::Service<ServiceType>>;
-
-        DeleteEntityServiceHandler() = delete;
-        DeleteEntityServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~DeleteEntityServiceHandler();
+        AZStd::string_view GetTypeName() const override
+        {
+            return "DeleteEntity";
+        }
+
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "delete_entity";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        void HandleServiceRequest(
-            const ServiceHandle service_handle, const std::shared_ptr<rmw_request_id_t> header, const std::shared_ptr<Request> request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_deleteEntityService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 2 - 20
Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesServiceHandler.cpp

@@ -13,25 +13,6 @@
 
 namespace SimulationInterfacesROS2
 {
-    GetEntitiesServiceHandler::GetEntitiesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_getEntitiesService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](const Request::SharedPtr request, Response::SharedPtr response)
-            {
-                *response = HandleServiceRequest(*request);
-            });
-    }
-
-    GetEntitiesServiceHandler::~GetEntitiesServiceHandler()
-    {
-        if (m_getEntitiesService)
-        {
-            m_getEntitiesService.reset();
-        }
-    }
-
     AZStd::unordered_set<AZ::u8> GetEntitiesServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::ENTITY_TAGS,
@@ -40,7 +21,8 @@ namespace SimulationInterfacesROS2
                                              SimulationFeatures::ENTITY_CATEGORIES };
     }
 
-    GetEntitiesServiceHandler::Response GetEntitiesServiceHandler::HandleServiceRequest(const Request& request)
+    AZStd::optional<GetEntitiesServiceHandler::Response> GetEntitiesServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
         AZ::Outcome<SimulationInterfaces::EntityNameList, SimulationInterfaces::FailedResult> outcome;
 

+ 11 - 10
Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesServiceHandler.h

@@ -15,22 +15,23 @@
 
 namespace SimulationInterfacesROS2
 {
-
-    class GetEntitiesServiceHandler : public ROS2HandlerBase
+    class GetEntitiesServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::GetEntities>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::GetEntities;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "GetEntities";
+        }
 
-        GetEntitiesServiceHandler() = delete;
-        GetEntitiesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~GetEntitiesServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "get_entities";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        Response HandleServiceRequest(const Request& request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_getEntitiesService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 2 - 20
Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesStatesServiceHandler.cpp

@@ -15,25 +15,6 @@
 
 namespace SimulationInterfacesROS2
 {
-    GetEntitiesStatesServiceHandler::GetEntitiesStatesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_getEntitiesStatesService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](const Request::SharedPtr request, Response::SharedPtr response)
-            {
-                *response = HandleServiceRequest(*request);
-            });
-    }
-
-    GetEntitiesStatesServiceHandler::~GetEntitiesStatesServiceHandler()
-    {
-        if (m_getEntitiesStatesService)
-        {
-            m_getEntitiesStatesService.reset();
-        }
-    }
-
     AZStd::unordered_set<AZ::u8> GetEntitiesStatesServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::ENTITY_TAGS,
@@ -43,7 +24,8 @@ namespace SimulationInterfacesROS2
                                              SimulationFeatures::ENTITY_STATE_GETTING };
     }
 
-    GetEntitiesStatesServiceHandler::Response GetEntitiesStatesServiceHandler::HandleServiceRequest(const Request& request)
+    AZStd::optional<GetEntitiesStatesServiceHandler::Response> GetEntitiesStatesServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
         AZ::Outcome<SimulationInterfaces::MultipleEntitiesStates, SimulationInterfaces::FailedResult> outcome;
 

+ 11 - 9
Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntitiesStatesServiceHandler.h

@@ -16,21 +16,23 @@
 namespace SimulationInterfacesROS2
 {
 
-    class GetEntitiesStatesServiceHandler : public ROS2HandlerBase
+    class GetEntitiesStatesServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::GetEntitiesStates>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::GetEntitiesStates;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "GetEntitiesStates";
+        }
 
-        GetEntitiesStatesServiceHandler() = delete;
-        GetEntitiesStatesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~GetEntitiesStatesServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "get_entities_states";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        Response HandleServiceRequest(const Request& request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_getEntitiesStatesService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 6 - 25
Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntityStateServiceHandler.cpp

@@ -7,39 +7,21 @@
  */
 
 #include "GetEntityStateServiceHandler.h"
+#include <AzCore/std/optional.h>
 #include <ROS2/ROS2Bus.h>
 #include <ROS2/Utilities/ROS2Conversions.h>
 #include <SimulationInterfaces/SimulationEntityManagerRequestBus.h>
-#include <std_msgs/msg/header.hpp>
 
 namespace SimulationInterfacesROS2
 {
 
-    GetEntityStateServiceHandler::GetEntityStateServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_getEntityStateService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](const Request::SharedPtr request, Response::SharedPtr response)
-            {
-                *response = HandleServiceRequest(*request);
-            });
-    }
-
-    GetEntityStateServiceHandler::~GetEntityStateServiceHandler()
-    {
-        if (m_getEntityStateService)
-        {
-            m_getEntityStateService.reset();
-        }
-    }
-
     AZStd::unordered_set<AZ::u8> GetEntityStateServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::ENTITY_STATE_GETTING };
     }
 
-    GetEntityStateServiceHandler::Response GetEntityStateServiceHandler::HandleServiceRequest(const Request& request)
+    AZStd::optional<GetEntityStateServiceHandler::Response> GetEntityStateServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
         AZStd::string entityName = request.entity.c_str();
         AZ::Outcome<SimulationInterfaces::EntityState, SimulationInterfaces::FailedResult> outcome;
@@ -59,10 +41,8 @@ namespace SimulationInterfacesROS2
 
         const auto& entityState = outcome.GetValue();
         simulation_interfaces::msg::EntityState entityStateMsg;
-        std_msgs::msg::Header header;
-        header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
-        header.frame_id = ROS2::ROS2Interface::Get()->GetNode()->get_name();
-        entityStateMsg.header = header;
+        entityStateMsg.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
+        entityStateMsg.header.frame_id = ROS2::ROS2Interface::Get()->GetNode()->get_name();
         entityStateMsg.pose = ROS2::ROS2Conversions::ToROS2Pose(entityState.m_pose);
         entityStateMsg.twist.linear = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twist_linear);
         entityStateMsg.twist.angular = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twist_angular);
@@ -71,4 +51,5 @@ namespace SimulationInterfacesROS2
         response.state = entityStateMsg;
         return response;
     }
+
 } // namespace SimulationInterfacesROS2

+ 11 - 10
Gems/SimulationInterfacesROS2/Code/Source/Services/GetEntityStateServiceHandler.h

@@ -16,21 +16,22 @@
 namespace SimulationInterfacesROS2
 {
 
-    class GetEntityStateServiceHandler : public ROS2HandlerBase
+    class GetEntityStateServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::GetEntityState>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::GetEntityState;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "GetEntityState";
+        }
 
-        GetEntityStateServiceHandler() = delete;
-        GetEntityStateServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~GetEntityStateServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "get_entity_state";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        Response HandleServiceRequest(const Request& request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_getEntityStateService;
     };
-
 } // namespace SimulationInterfacesROS2

+ 5 - 30
Gems/SimulationInterfacesROS2/Code/Source/Services/GetSimulationFeaturesServiceHandler.cpp

@@ -16,32 +16,14 @@
 namespace SimulationInterfacesROS2
 {
 
-    GetSimulationFeaturesServiceHandler::GetSimulationFeaturesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_getSimulationFeaturesService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](const Request::SharedPtr request, Response::SharedPtr response)
-            {
-                *response = HandleServiceRequest(*request);
-            });
-    }
-
-    GetSimulationFeaturesServiceHandler::~GetSimulationFeaturesServiceHandler()
-    {
-        if (m_getSimulationFeaturesService)
-        {
-            m_getSimulationFeaturesService.reset();
-        }
-    }
-
     AZStd::unordered_set<AZ::u8> GetSimulationFeaturesServiceHandler::GetProvidedFeatures()
     {
         // standard doesn't define specific feature id for this service
         return AZStd::unordered_set<AZ::u8>{};
     }
 
-    GetSimulationFeaturesServiceHandler::Response GetSimulationFeaturesServiceHandler::HandleServiceRequest(const Request& request)
+    AZStd::optional<GetSimulationFeaturesServiceHandler::Response> GetSimulationFeaturesServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
         // call bus to get simulation features in SimulationInterfacesROS2 Gem side
         AZStd::unordered_set<AZ::u8> ros2Interfaces;
@@ -58,22 +40,15 @@ namespace SimulationInterfacesROS2
         {
             commonFeatures.insert(static_cast<AZ::u8>(id));
         }
-
-        AZStd::vector<AZ::u8> idToRemove;
+        Response response;
         for (auto id : commonFeatures)
         {
-            if (!(ros2Interfaces.contains(id) && o3deInterfaces.contains(SimulationInterfaces::SimulationFeatures(id))))
+            if (ros2Interfaces.contains(id) && o3deInterfaces.contains(SimulationInterfaces::SimulationFeatures(id)))
             {
-                idToRemove.push_back(id);
+                response.features.features.emplace_back(id);
             }
         }
-        for (auto id : idToRemove)
-        {
-            commonFeatures.erase(id);
-        }
 
-        Response response;
-        response.features.features.insert(response.features.features.end(), commonFeatures.begin(), commonFeatures.end());
         return response;
     }
 } // namespace SimulationInterfacesROS2

+ 11 - 10
Gems/SimulationInterfacesROS2/Code/Source/Services/GetSimulationFeaturesServiceHandler.h

@@ -16,22 +16,23 @@
 namespace SimulationInterfacesROS2
 {
 
-    class GetSimulationFeaturesServiceHandler : public ROS2HandlerBase
+    class GetSimulationFeaturesServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::GetSimulatorFeatures>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::GetSimulatorFeatures;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
-        using ServiceHandle = std::shared_ptr<rclcpp::Service<ServiceType>>;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "GetSimulationFeatures";
+        }
 
-        GetSimulationFeaturesServiceHandler() = delete;
-        GetSimulationFeaturesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~GetSimulationFeaturesServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "get_simulation_features";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        Response HandleServiceRequest(const Request& request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_getSimulationFeaturesService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 2 - 19
Gems/SimulationInterfacesROS2/Code/Source/Services/GetSpawnablesServiceHandler.cpp

@@ -11,31 +11,14 @@
 
 namespace SimulationInterfacesROS2
 {
-    GetSpawnablesServiceHandler::GetSpawnablesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_getSpawnablesService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](const Request::SharedPtr request, Response::SharedPtr response)
-            {
-                *response = HandleServiceRequest(*request);
-            });
-    }
-
-    GetSpawnablesServiceHandler::~GetSpawnablesServiceHandler()
-    {
-        if (m_getSpawnablesService)
-        {
-            m_getSpawnablesService.reset();
-        }
-    }
 
     AZStd::unordered_set<AZ::u8> GetSpawnablesServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::SPAWNABLES };
     }
 
-    GetSpawnablesServiceHandler::Response GetSpawnablesServiceHandler::HandleServiceRequest(const Request& request)
+    AZStd::optional<GetSpawnablesServiceHandler::Response> GetSpawnablesServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
         AZ::Outcome<SimulationInterfaces::SpawnableList, SimulationInterfaces::FailedResult> outcome;
         SimulationInterfaces::SimulationEntityManagerRequestBus::BroadcastResult(

+ 11 - 9
Gems/SimulationInterfacesROS2/Code/Source/Services/GetSpawnablesServiceHandler.h

@@ -16,21 +16,23 @@
 namespace SimulationInterfacesROS2
 {
 
-    class GetSpawnablesServiceHandler : public ROS2HandlerBase
+    class GetSpawnablesServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::GetSpawnables>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::GetSpawnables;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "GetSpawnables";
+        }
 
-        GetSpawnablesServiceHandler() = delete;
-        GetSpawnablesServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~GetSpawnablesServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "get_spawnables";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        Response HandleServiceRequest(const Request& request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_getSpawnablesService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 57 - 3
Gems/SimulationInterfacesROS2/Code/Source/Services/ROS2HandlerBaseClass.h

@@ -8,24 +8,78 @@
 
 #pragma once
 
+#include "Interfaces/IROS2HandlerBase.h"
+#include "Utils/RegistryUtils.h"
 #include <AzCore/std/containers/unordered_set.h>
+#include <AzCore/std/optional.h>
+#include <rclcpp/rclcpp.hpp>
+#include <rclcpp/service.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 namespace SimulationInterfacesROS2
 {
-    //! base for each ros2 handler, forces declaration of features provided by the handler
+    //! base for each ros2 service handler, forces declaration of features provided by the handler
     //! combined informations along all ROS 2 handlers gives information about simulation features
     //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
     using SimulationFeatures = simulation_interfaces::msg::SimulatorFeatures;
-    class ROS2HandlerBase
+    template<typename RosServiceType>
+    class ROS2HandlerBase : public virtual IROS2HandlerBase
     {
     public:
+        using Request = typename RosServiceType::Request;
+        using Response = typename RosServiceType::Response;
+        using ServiceHandle = std::shared_ptr<rclcpp::Service<RosServiceType>>;
         virtual ~ROS2HandlerBase() = default;
+        void CreateService(rclcpp::Node::SharedPtr& node)
+        {
+            // get the service name from the type name
+            AZStd::string serviceName = RegistryUtilities::GetServiceName(GetTypeName());
+
+            if (serviceName.empty())
+            {
+                // if the service name is empty, use the default name
+                serviceName = GetDefaultName();
+            }
+
+            const std::string serviceNameStr{ serviceName.c_str(), serviceName.size() };
+            m_serviceHandle = node->create_service<RosServiceType>(
+                serviceNameStr,
+                [this](
+                    const ServiceHandle service_handle,
+                    const std::shared_ptr<rmw_request_id_t> header,
+                    const std::shared_ptr<Request> request)
+                {
+                    m_lastRequestHeader = header;
+                    auto response = HandleServiceRequest(header, *request);
+                    // if no response passed it means, that handleServiceRequest will send response in defined callback after time consuming
+                    // task, header needs to be cached
+                    if (response.has_value())
+                    {
+                        service_handle->send_response(*header, response.value());
+                    }
+                });
+        }
+
+        void SendResponse(Response response)
+        {
+            AZ_Assert(m_serviceHandle, "Failed to get m_serviceHandle");
+            AZ_Assert(m_lastRequestHeader, "Failed to get last request header ptr");
+            m_serviceHandle->send_response(*m_lastRequestHeader, response);
+        }
+
+    protected:
+        //! This function is called when a service request is received.
+        virtual AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) = 0;
 
         //! return features id defined by the handler, ids must follow the definition inside standard:
         //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
-        virtual AZStd::unordered_set<AZ::u8> GetProvidedFeatures()
+        AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override
         {
             return {};
         };
+
+    private:
+        std::shared_ptr<rmw_request_id_t> m_lastRequestHeader = nullptr;
+        ServiceHandle m_serviceHandle;
     };
+
 } // namespace SimulationInterfacesROS2

+ 3 - 19
Gems/SimulationInterfacesROS2/Code/Source/Services/SetEntityStateServiceHandler.cpp

@@ -7,36 +7,20 @@
  */
 
 #include "SetEntityStateServiceHandler.h"
+#include <AzCore/std/optional.h>
 #include <ROS2/Utilities/ROS2Conversions.h>
 #include <SimulationInterfaces/SimulationEntityManagerRequestBus.h>
 
 namespace SimulationInterfacesROS2
 {
-    SetEntityStateServiceHandler::SetEntityStateServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_setEntityStateService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](const Request::SharedPtr request, Response::SharedPtr response)
-            {
-                *response = HandleServiceRequest(*request);
-            });
-    }
-
-    SetEntityStateServiceHandler::~SetEntityStateServiceHandler()
-    {
-        if (m_setEntityStateService)
-        {
-            m_setEntityStateService.reset();
-        }
-    }
 
     AZStd::unordered_set<AZ::u8> SetEntityStateServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::ENTITY_STATE_SETTING };
     }
 
-    SetEntityStateServiceHandler::Response SetEntityStateServiceHandler::HandleServiceRequest(const Request& request)
+    AZStd::optional<SetEntityStateServiceHandler::Response> SetEntityStateServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
         AZ::Outcome<void, SimulationInterfaces::FailedResult> outcome;
         AZStd::string entityName = request.entity.c_str();

+ 11 - 9
Gems/SimulationInterfacesROS2/Code/Source/Services/SetEntityStateServiceHandler.h

@@ -16,21 +16,23 @@
 namespace SimulationInterfacesROS2
 {
 
-    class SetEntityStateServiceHandler : public ROS2HandlerBase
+    class SetEntityStateServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::SetEntityState>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::SetEntityState;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "SetEntityState";
+        }
 
-        SetEntityStateServiceHandler() = delete;
-        SetEntityStateServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~SetEntityStateServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "set_entity_state";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        Response HandleServiceRequest(const Request& request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_setEntityStateService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 12 - 27
Gems/SimulationInterfacesROS2/Code/Source/Services/SpawnEntityServiceHandler.cpp

@@ -7,6 +7,8 @@
  */
 
 #include "SpawnEntityServiceHandler.h"
+#include "Services/ROS2HandlerBaseClass.h"
+#include <AzCore/std/optional.h>
 #include <AzFramework/Physics/ShapeConfiguration.h>
 #include <ROS2/ROS2Bus.h>
 #include <ROS2/Utilities/ROS2Conversions.h>
@@ -14,45 +16,27 @@
 
 namespace SimulationInterfacesROS2
 {
-    SpawnEntityServiceHandler::SpawnEntityServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName)
-    {
-        const std::string serviceNameStr(std::string_view(serviceName.data(), serviceName.size()));
-        m_spawnEntityService = node->create_service<ServiceType>(
-            serviceNameStr,
-            [this](
-                const ServiceHandle service_handle, const std::shared_ptr<rmw_request_id_t> header, const std::shared_ptr<Request> request)
-            {
-                HandleServiceRequest(service_handle, header, request);
-            });
-    }
-
-    SpawnEntityServiceHandler::~SpawnEntityServiceHandler()
-    {
-        if (m_spawnEntityService)
-        {
-            m_spawnEntityService.reset();
-        }
-    }
 
     AZStd::unordered_set<AZ::u8> SpawnEntityServiceHandler::GetProvidedFeatures()
     {
         return AZStd::unordered_set<AZ::u8>{ SimulationFeatures::SPAWNING };
     }
 
-    void SpawnEntityServiceHandler::HandleServiceRequest(
-        const ServiceHandle service_handle, const std::shared_ptr<rmw_request_id_t> header, const std::shared_ptr<Request> request)
+    AZStd::optional<SpawnEntityServiceHandler::Response> SpawnEntityServiceHandler::HandleServiceRequest(
+        const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
-        const AZStd::string_view name {request->name.c_str(), request->name.size()};
-        const AZStd::string_view uri {request->uri.c_str(), request->uri.size()};
-        const AZStd::string_view entityNamespace {request->entity_namespace.c_str(), request->entity_namespace.size()};
-        const AZ::Transform initialPose = ROS2::ROS2Conversions::FromROS2Pose(request->initial_pose.pose);
+        const AZStd::string_view name{ request.name.c_str(), request.name.size() };
+        const AZStd::string_view uri{ request.uri.c_str(), request.uri.size() };
+        const AZStd::string_view entityNamespace{ request.entity_namespace.c_str(), request.entity_namespace.size() };
+        const AZ::Transform initialPose = ROS2::ROS2Conversions::FromROS2Pose(request.initial_pose.pose);
+
         SimulationInterfaces::SimulationEntityManagerRequestBus::Broadcast(
             &SimulationInterfaces::SimulationEntityManagerRequests::SpawnEntity,
             name,
             uri,
             entityNamespace,
             initialPose,
-            [service_handle, header](const AZ::Outcome<AZStd::string, SimulationInterfaces::FailedResult>& outcome)
+            [this](const AZ::Outcome<AZStd::string, SimulationInterfaces::FailedResult>& outcome)
             {
                 Response response;
                 if (outcome.IsSuccess())
@@ -66,8 +50,9 @@ namespace SimulationInterfacesROS2
                     response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
                     response.result.error_message = failedResult.error_string.c_str();
                 }
-                service_handle->send_response(*header, response);
+                SendResponse(response);
             });
+        return AZStd::nullopt;
     }
 
 } // namespace SimulationInterfacesROS2

+ 11 - 12
Gems/SimulationInterfacesROS2/Code/Source/Services/SpawnEntityServiceHandler.h

@@ -15,24 +15,23 @@
 
 namespace SimulationInterfacesROS2
 {
-
-    class SpawnEntityServiceHandler : public ROS2HandlerBase
+    class SpawnEntityServiceHandler : public ROS2HandlerBase<simulation_interfaces::srv::SpawnEntity>
     {
     public:
-        using ServiceType = simulation_interfaces::srv::SpawnEntity;
-        using Request = ServiceType::Request;
-        using Response = ServiceType::Response;
-        using ServiceHandle = std::shared_ptr<rclcpp::Service<ServiceType>>;
+        AZStd::string_view GetTypeName() const override
+        {
+            return "SpawnEntity";
+        }
 
-        SpawnEntityServiceHandler() = delete;
-        SpawnEntityServiceHandler(rclcpp::Node::SharedPtr& node, AZStd::string_view serviceName);
-        ~SpawnEntityServiceHandler();
+        AZStd::string_view GetDefaultName() const override
+        {
+            return "spawn_entity";
+        }
         AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
-        void HandleServiceRequest(
-            const ServiceHandle service_handle, const std::shared_ptr<rmw_request_id_t> header, const std::shared_ptr<Request> request);
+
+        AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
     private:
-        rclcpp::Service<ServiceType>::SharedPtr m_spawnEntityService;
     };
 
 } // namespace SimulationInterfacesROS2

+ 0 - 29
Gems/SimulationInterfacesROS2/Code/Source/Utils/ServicesConfig.h

@@ -1,29 +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
- *
- */
-
-#pragma once
-
-namespace SimulationInterfacesROS2
-{
-    inline constexpr const char* DeleteEntityService = "DeleteEntity";
-    inline constexpr const char* DeleteEntityServiceDefaultName = "delete_entity";
-    inline constexpr const char* GetEntitiesService = "GetEntities";
-    inline constexpr const char* GetEntitiesServiceDefaultName = "get_entities";
-    inline constexpr const char* GetEntitiesStatesService = "GetEntitiesStates";
-    inline constexpr const char* GetEntitiesStatesServiceDefaultName = "get_entities_states";
-    inline constexpr const char* GetEntityStateService = "GetEntity";
-    inline constexpr const char* GetEntityStateServiceDefaultName = "get_entity_state";
-    inline constexpr const char* GetSpawnablesService = "GetSpawnables";
-    inline constexpr const char* GetSpawnablesServiceDefaultName = "get_spawnables";
-    inline constexpr const char* SetEntityStateService = "SetEntityState";
-    inline constexpr const char* SetEntityStateServiceDefaultName = "set_entity_state";
-    inline constexpr const char* SpawnEntityService = "SpawnEntity";
-    inline constexpr const char* SpawnEntityServiceDefaultName = "spawn_entity";
-    inline constexpr const char* GetSimulationFeaturesService = "GetSimulationFeatures";
-    inline constexpr const char* GetSimulationFeaturesServiceDefaultName = "get_simulation_features";
-} // namespace SimulationInterfacesROS2

+ 0 - 1
Gems/SimulationInterfacesROS2/Code/Source/Utils/Utils.h

@@ -8,7 +8,6 @@
 
 #pragma once
 
-#include "Services/GetEntityStateServiceHandler.h"
 #include <AzCore/std/smart_ptr/make_shared.h>
 #include <ROS2/Utilities/ROS2Conversions.h>
 #include <SimulationInterfaces/SimulationEntityManagerRequestBus.h>

+ 1 - 1
Gems/SimulationInterfacesROS2/Code/simulationinterfacesros2_private_files.cmake

@@ -4,6 +4,7 @@ set(FILES
     Source/SimulationInterfacesROS2ModuleInterface.h
     Source/Clients/SimulationInterfacesROS2SystemComponent.cpp
     Source/Clients/SimulationInterfacesROS2SystemComponent.h
+    Source/Interfaces/IROS2HandlerBase.h
     Source/Services/ROS2HandlerBaseClass.h
     Source/Services/GetEntitiesServiceHandler.cpp
     Source/Services/GetEntitiesServiceHandler.h
@@ -27,6 +28,5 @@ set(FILES
     Source/Services/GetSimulationFeaturesServiceHandler.h
     Source/Utils/RegistryUtils.cpp
     Source/Utils/RegistryUtils.h
-    Source/Utils/ServicesConfig.h
     Source/Utils/Utils.h    
 )