浏览代码

Simulation interfaces - part of review suggestions applied (#889)

* Review sugestion based on @norbertprokopiuk comments

Signed-off-by: Norbert Prokopiuk <[email protected]>

* Review sugestion based on part of @adamdbrw comments

Signed-off-by: Norbert Prokopiuk <[email protected]>

* Review sugestion based on part of @PawelLiberadzki comments

Signed-off-by: Norbert Prokopiuk <[email protected]>

* Unififed aliases usage for simulation Interface, dropped const for buses, based on @PawelLiberadzki and @michalpelka comments

Signed-off-by: Norbert Prokopiuk <[email protected]>

* Removed TAG_FILTER enum

Signed-off-by: Norbert Prokopiuk <[email protected]>

---------

Signed-off-by: Norbert Prokopiuk <[email protected]>
Norbert Prokopiuk 3 月之前
父节点
当前提交
f1fbcc87ab
共有 37 个文件被更改,包括 268 次插入305 次删除
  1. 0 0
      Gems/SimulationInterfaces/.gitignore
  2. 4 3
      Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/ROS2SimulationInterfacesRequestBus.h
  3. 6 6
      Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/Result.h
  4. 13 9
      Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/SimulationEntityManagerRequestBus.h
  5. 5 5
      Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h
  6. 5 3
      Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/SimulationMangerRequestBus.h
  7. 1 5
      Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/TagFilter.h
  8. 0 1
      Gems/SimulationInterfaces/Code/Source/Actions/ROS2ActionBase.h
  9. 1 1
      Gems/SimulationInterfaces/Code/Source/Clients/CommonUtilities.cpp
  10. 1 1
      Gems/SimulationInterfaces/Code/Source/Clients/CommonUtilities.h
  11. 26 38
      Gems/SimulationInterfaces/Code/Source/Clients/ConsoleCommands.inl
  12. 57 79
      Gems/SimulationInterfaces/Code/Source/Clients/SimulationEntitiesManager.cpp
  13. 9 11
      Gems/SimulationInterfaces/Code/Source/Clients/SimulationEntitiesManager.h
  14. 4 4
      Gems/SimulationInterfaces/Code/Source/Clients/SimulationFeaturesAggregator.cpp
  15. 5 6
      Gems/SimulationInterfaces/Code/Source/Clients/SimulationFeaturesAggregator.h
  16. 10 10
      Gems/SimulationInterfaces/Code/Source/Clients/SimulationManager.cpp
  17. 1 3
      Gems/SimulationInterfaces/Code/Source/Clients/SimulationManager.h
  18. 2 2
      Gems/SimulationInterfaces/Code/Source/Services/DeleteEntityServiceHandler.cpp
  19. 2 2
      Gems/SimulationInterfaces/Code/Source/Services/GetEntitiesServiceHandler.cpp
  20. 17 29
      Gems/SimulationInterfaces/Code/Source/Services/GetEntitiesStatesServiceHandler.cpp
  21. 5 5
      Gems/SimulationInterfaces/Code/Source/Services/GetEntityStateServiceHandler.cpp
  22. 6 7
      Gems/SimulationInterfaces/Code/Source/Services/GetSimulationFeaturesServiceHandler.cpp
  23. 2 1
      Gems/SimulationInterfaces/Code/Source/Services/GetSimulationFeaturesServiceHandler.h
  24. 0 1
      Gems/SimulationInterfaces/Code/Source/Services/GetSimulationStateServiceHandler.h
  25. 3 5
      Gems/SimulationInterfaces/Code/Source/Services/GetSpawnablesServiceHandler.cpp
  26. 0 1
      Gems/SimulationInterfaces/Code/Source/Services/ROS2ServiceBase.h
  27. 2 2
      Gems/SimulationInterfaces/Code/Source/Services/ResetSimulationServiceHandler.cpp
  28. 0 1
      Gems/SimulationInterfaces/Code/Source/Services/ResetSimulationServiceHandler.h
  29. 4 4
      Gems/SimulationInterfaces/Code/Source/Services/SetEntityStateServiceHandler.cpp
  30. 2 2
      Gems/SimulationInterfaces/Code/Source/Services/SetSimulationStateServiceHandler.cpp
  31. 0 1
      Gems/SimulationInterfaces/Code/Source/Services/SetSimulationStateServiceHandler.h
  32. 8 5
      Gems/SimulationInterfaces/Code/Source/Services/SpawnEntityServiceHandler.cpp
  33. 9 9
      Gems/SimulationInterfaces/Code/Source/Utils/Utils.h
  34. 30 26
      Gems/SimulationInterfaces/Code/Tests/Tools/InterfacesTest.cpp
  35. 3 3
      Gems/SimulationInterfaces/Code/Tests/Tools/Mocks/SimulationFeaturesAggregatorRequestsHandlerMock.h
  36. 5 6
      Gems/SimulationInterfaces/Code/Tests/Tools/SimulationInterfaceTests.cpp
  37. 20 8
      Gems/SimulationInterfaces/Code/Tests/Tools/SimulationIterfaceAppTest.cpp

+ 0 - 0
Gems/SimulationInterfaces/.gitignore


+ 4 - 3
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/ROS2SimulationInterfacesRequestBus.h

@@ -8,7 +8,7 @@
 
 
 #pragma once
 #pragma once
 
 
-#include <SimulationInterfaces/ROS2SimulationInterfacesTypeIds.h>
+#include "ROS2SimulationInterfacesTypeIds.h"
 
 
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/Interface/Interface.h>
 #include <AzCore/Interface/Interface.h>
@@ -16,6 +16,7 @@
 
 
 namespace ROS2SimulationInterfaces
 namespace ROS2SimulationInterfaces
 {
 {
+    using SimulationFeatureType = uint8_t;
     class ROS2SimulationInterfacesRequests
     class ROS2SimulationInterfacesRequests
     {
     {
     public:
     public:
@@ -23,9 +24,9 @@ namespace ROS2SimulationInterfaces
         virtual ~ROS2SimulationInterfacesRequests() = default;
         virtual ~ROS2SimulationInterfacesRequests() = default;
 
 
         //! Returns set of simulation features available in ROS2SimulationInterfaces Gem
         //! Returns set of simulation features available in ROS2SimulationInterfaces Gem
-        //! SimulationFeatures follows definition available at:
+        //! SimulationFeatureType follows definition available at:
         //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
         //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
-        virtual AZStd::unordered_set<AZ::u8> GetSimulationFeatures() = 0;
+        virtual AZStd::unordered_set<SimulationFeatureType> GetSimulationFeatures() = 0;
     };
     };
 
 
     class ROS2SimulationInterfacesRequestBusTraits : public AZ::EBusTraits
     class ROS2SimulationInterfacesRequestBusTraits : public AZ::EBusTraits

+ 6 - 6
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/Result.h

@@ -13,18 +13,18 @@ namespace SimulationInterfaces
 {
 {
     //! Result codes to be used in the Result message
     //! Result codes to be used in the Result message
     //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/Result.msg">Result.msg</a>
     //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/Result.msg">Result.msg</a>
-    using ErrorCodeValue = uint8_t;
+    using ErrorCodeType = uint8_t;
 
 
     //! A message type to represent the result of a failed operation
     //! A message type to represent the result of a failed operation
     struct FailedResult
     struct FailedResult
     {
     {
         FailedResult() = default;
         FailedResult() = default;
-        FailedResult(ErrorCodeValue error_code, const AZStd::string& error_string)
-            : error_code(error_code)
-            , error_string(error_string)
+        FailedResult(ErrorCodeType errorCode, const AZStd::string& errorString)
+            : m_errorCode(errorCode)
+            , m_errorString(errorString)
         {
         {
         }
         }
-        ErrorCodeValue error_code;
-        AZStd::string error_string;
+        ErrorCodeType m_errorCode;
+        AZStd::string m_errorString;
     };
     };
 } // namespace SimulationInterfaces
 } // namespace SimulationInterfaces

+ 13 - 9
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/SimulationEntityManagerRequestBus.h

@@ -8,7 +8,7 @@
 
 
 #pragma once
 #pragma once
 
 
-#include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
+#include "SimulationInterfacesTypeIds.h"
 
 
 #include "Result.h"
 #include "Result.h"
 #include "TagFilter.h"
 #include "TagFilter.h"
@@ -19,30 +19,33 @@
 
 
 namespace SimulationInterfaces
 namespace SimulationInterfaces
 {
 {
-    //! # A set of filters to apply to entity queries. See GetEntities, GetEntitiesStates.
+    //! A set of filters to apply to entity queries. See GetEntities, GetEntitiesStates.
     //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/EntityFilters.msg">EntityFilters.msg</a>
     //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/EntityFilters.msg">EntityFilters.msg</a>
     struct EntityFilters
     struct EntityFilters
     {
     {
-        AZStd::string m_filter; //! A posix regular expression to match against entity names
-        TagFilter m_tags_filter; //! A filter to match against entity tags
+        //! A posix regular expression to match against entity names,
+        //! The regular expression syntax is POSIX Extended,
+        //! @see <a href="https://pubs.opengroup.org/onlinepubs/9799919799">POSIX_Extended</a> definitions
+        AZStd::string m_nameFilter;
+        TagFilter m_tagsFilter; //! A filter to match against entity tags
         AZStd::shared_ptr<Physics::ShapeConfiguration>
         AZStd::shared_ptr<Physics::ShapeConfiguration>
-            m_bounds_shape; //! A shape to use for filtering entities, null means no bounds filtering
-        AZ::Transform m_bounds_pose{ AZ::Transform::CreateIdentity() };
+            m_boundsShape; //! A shape to use for filtering entities, null means no bounds filtering
+        AZ::Transform m_boundsPose{ AZ::Transform::CreateIdentity() };
     };
     };
 
 
     //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/EntityState.msg">EntityState.msg</a>
     //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/EntityState.msg">EntityState.msg</a>
     struct EntityState
     struct EntityState
     {
     {
         AZ::Transform m_pose; //! The pose of the entity
         AZ::Transform m_pose; //! The pose of the entity
-        AZ::Vector3 m_twist_linear; //! The linear velocity of the entity (in the entity frame)
-        AZ::Vector3 m_twist_angular; //! The angular velocity of the entity (in the entity frame)
+        AZ::Vector3 m_twistLinear; //! The linear velocity of the entity (in the entity frame)
+        AZ::Vector3 m_twistAngular; //! The angular velocity of the entity (in the entity frame)
     };
     };
 
 
     struct Spawnable
     struct Spawnable
     {
     {
         AZStd::string m_uri;
         AZStd::string m_uri;
         AZStd::string m_description;
         AZStd::string m_description;
-        AZStd::string m_bounds_sphere;
+        AZStd::string m_boundsSphere;
     };
     };
 
 
     using EntityNameList = AZStd::vector<AZStd::string>;
     using EntityNameList = AZStd::vector<AZStd::string>;
@@ -50,6 +53,7 @@ namespace SimulationInterfaces
     using SpawnableList = AZStd::vector<Spawnable>;
     using SpawnableList = AZStd::vector<Spawnable>;
     using DeletionCompletedCb = AZStd::function<void(const AZ::Outcome<void, FailedResult>&)>;
     using DeletionCompletedCb = AZStd::function<void(const AZ::Outcome<void, FailedResult>&)>;
     using SpawnCompletedCb = AZStd::function<void(const AZ::Outcome<AZStd::string, FailedResult>&)>;
     using SpawnCompletedCb = AZStd::function<void(const AZ::Outcome<AZStd::string, FailedResult>&)>;
+
     class SimulationEntityManagerRequests
     class SimulationEntityManagerRequests
     {
     {
     public:
     public:

+ 5 - 5
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h

@@ -8,7 +8,7 @@
 
 
 #pragma once
 #pragma once
 
 
-#include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
+#include "SimulationInterfacesTypeIds.h"
 
 
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/Interface/Interface.h>
 #include <AzCore/Interface/Interface.h>
@@ -16,7 +16,7 @@
 
 
 namespace SimulationInterfaces
 namespace SimulationInterfaces
 {
 {
-    using SimulationFeatures = uint8_t;
+    using SimulationFeatureType = uint8_t;
 
 
     class SimulationFeaturesAggregatorRequests
     class SimulationFeaturesAggregatorRequests
     {
     {
@@ -25,15 +25,15 @@ namespace SimulationInterfaces
         virtual ~SimulationFeaturesAggregatorRequests() = default;
         virtual ~SimulationFeaturesAggregatorRequests() = default;
 
 
         //! Registers simulation features defined by caller
         //! Registers simulation features defined by caller
-        virtual void AddSimulationFeatures(const AZStd::unordered_set<SimulationFeatures>& features) = 0;
+        virtual void AddSimulationFeatures(const AZStd::unordered_set<SimulationFeatureType>& features) = 0;
 
 
         //! Returns features available in the simulator, list follows definitions at
         //! Returns features available in the simulator, list follows definitions at
         //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
         //! @see https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/SimulatorFeatures.msg
-        virtual const AZStd::unordered_set<SimulationFeatures> GetSimulationFeatures() const = 0;
+        virtual AZStd::unordered_set<SimulationFeatureType> GetSimulationFeatures() = 0;
 
 
         //! Method checks if feature with given id is available in the simulation
         //! Method checks if feature with given id is available in the simulation
         //! Method is extension to standard defined in simulation_interfaces
         //! Method is extension to standard defined in simulation_interfaces
-        virtual bool HasFeature(SimulationFeatures feature) const = 0;
+        virtual bool HasFeature(SimulationFeatureType feature) = 0;
     };
     };
 
 
     class SimulationFeaturesAggregatorRequestBusTraits : public AZ::EBusTraits
     class SimulationFeaturesAggregatorRequestBusTraits : public AZ::EBusTraits

+ 5 - 3
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/SimulationMangerRequestBus.h

@@ -8,25 +8,27 @@
 
 
 #pragma once
 #pragma once
 
 
-#include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
+#include "SimulationInterfacesTypeIds.h"
 
 
+#include "Result.h"
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/Interface/Interface.h>
 #include <AzCore/Interface/Interface.h>
 #include <AzCore/std/smart_ptr/shared_ptr.h>
 #include <AzCore/std/smart_ptr/shared_ptr.h>
 #include <AzFramework/Physics/ShapeConfiguration.h>
 #include <AzFramework/Physics/ShapeConfiguration.h>
-#include <SimulationInterfaces/Result.h>
 
 
 namespace SimulationInterfaces
 namespace SimulationInterfaces
 {
 {
     using SimulationState = uint8_t;
     using SimulationState = uint8_t;
+
     class SimulationManagerRequests
     class SimulationManagerRequests
     {
     {
     public:
     public:
         AZ_RTTI(SimulationManagerRequests, SimulationManagerRequestsTypeId);
         AZ_RTTI(SimulationManagerRequests, SimulationManagerRequestsTypeId);
         virtual ~SimulationManagerRequests() = default;
         virtual ~SimulationManagerRequests() = default;
 
 
-        //! Reload level and removal of all spawned simulation entities.
         using ReloadLevelCallback = AZStd::function<void(void)>;
         using ReloadLevelCallback = AZStd::function<void(void)>;
+
+        //! Reload level and removal of all spawned simulation entities.
         virtual void ReloadLevel(ReloadLevelCallback completionCallback) = 0;
         virtual void ReloadLevel(ReloadLevelCallback completionCallback) = 0;
 
 
         //! Set the simulation to paused or unpaused,
         //! Set the simulation to paused or unpaused,

+ 1 - 5
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/TagFilter.h

@@ -15,14 +15,10 @@ namespace SimulationInterfaces
 {
 {
     //! Structure to design a filter for tags
     //! Structure to design a filter for tags
     //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/TagsFilter.msg">TagsFilter.msg</a>
     //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/TagsFilter.msg">TagsFilter.msg</a>
+    using TagFilterMode = uint8_t;
 
 
     struct TagFilter
     struct TagFilter
     {
     {
-        enum class TagFilterMode
-        {
-            FILTER_MODE_ANY,
-            FILTER_MODE_ALL
-        };
         AZStd::unordered_set<AZStd::string> m_tags;
         AZStd::unordered_set<AZStd::string> m_tags;
         TagFilterMode m_mode;
         TagFilterMode m_mode;
     };
     };

+ 0 - 1
Gems/SimulationInterfaces/Code/Source/Actions/ROS2ActionBase.h

@@ -11,7 +11,6 @@
 #include <AzCore/std/functional.h>
 #include <AzCore/std/functional.h>
 #include <Interfaces/IROS2HandlerBase.h>
 #include <Interfaces/IROS2HandlerBase.h>
 #include <Utils/RegistryUtils.h>
 #include <Utils/RegistryUtils.h>
-#include <rclcpp/rclcpp.hpp>
 #include <rclcpp_action/rclcpp_action.hpp>
 #include <rclcpp_action/rclcpp_action.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 
 

+ 1 - 1
Gems/SimulationInterfaces/Code/Source/Clients/CommonUtilities.cpp

@@ -28,4 +28,4 @@ namespace SimulationInterfaces::Utils
         }
         }
         return {};
         return {};
     }
     }
-} // namespace SimulationInterfaces::Utils
+} // namespace SimulationInterfaces::Utils

+ 1 - 1
Gems/SimulationInterfaces/Code/Source/Clients/CommonUtilities.h

@@ -17,4 +17,4 @@ namespace SimulationInterfaces::Utils
     AZStd::string RelPathToUri(AZStd::string_view relPath);
     AZStd::string RelPathToUri(AZStd::string_view relPath);
     AZStd::string UriToRelPath(AZStd::string_view relPath);
     AZStd::string UriToRelPath(AZStd::string_view relPath);
 
 
-} // namespace SimulationInterfaces::Utils
+} // namespace SimulationInterfaces::Utils

+ 26 - 38
Gems/SimulationInterfaces/Code/Source/Clients/ConsoleCommands.inl

@@ -20,10 +20,11 @@ namespace SimulationInterfacesCommands
     static void simulationinterfaces_GetEntities(const AZ::ConsoleCommandContainer& arguments)
     static void simulationinterfaces_GetEntities(const AZ::ConsoleCommandContainer& arguments)
     {
     {
         AZ::Outcome<EntityNameList, FailedResult> entities;
         AZ::Outcome<EntityNameList, FailedResult> entities;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
         if (!entities.IsSuccess())
         if (!entities.IsSuccess())
         {
         {
-            AZ_Printf("SimulationInterfacesConsole", "Failed to get entities: %s\n", entities.GetError().error_string.c_str());
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get entities: %s\n", entities.GetError().m_errorString.c_str());
             return;
             return;
         }
         }
 
 
@@ -67,13 +68,13 @@ namespace SimulationInterfacesCommands
         AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_GetEntities in radius %f \n", sphereShape);
         AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_GetEntities in radius %f \n", sphereShape);
         AZ_Printf("SimulationInterfacesConsole", "position %f %f %f \n", position.GetX(), position.GetY(), position.GetZ());
         AZ_Printf("SimulationInterfacesConsole", "position %f %f %f \n", position.GetX(), position.GetY(), position.GetZ());
         EntityFilters filter;
         EntityFilters filter;
-        filter.m_bounds_shape = AZStd::make_shared<Physics::SphereShapeConfiguration>(sphereShape);
+        filter.m_boundsShape = AZStd::make_shared<Physics::SphereShapeConfiguration>(sphereShape);
 
 
         AZ::Outcome<EntityNameList, FailedResult> entities;
         AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
         if (!entities.IsSuccess())
         if (!entities.IsSuccess())
         {
         {
-            AZ_Printf("SimulationInterfacesConsole", "Failed to get entities: %s\n", entities.GetError().error_string.c_str());
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get entities: %s\n", entities.GetError().m_errorString.c_str());
             return;
             return;
         }
         }
 
 
@@ -93,33 +94,23 @@ namespace SimulationInterfacesCommands
         const AZStd::string entityName = arguments[0];
         const AZStd::string entityName = arguments[0];
         AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_GetEntityState %s\n", entityName.c_str());
         AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_GetEntityState %s\n", entityName.c_str());
         AZ::Outcome<EntityState, FailedResult> entityStateResult;
         AZ::Outcome<EntityState, FailedResult> entityStateResult;
-        SimulationEntityManagerRequestBus::BroadcastResult(entityStateResult, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entityStateResult, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
         if (!entityStateResult.IsSuccess())
         if (!entityStateResult.IsSuccess())
         {
         {
-            AZ_Printf("SimulationInterfacesConsole", "Failed to get entity state: %s\n", entityStateResult.GetError().error_string.c_str());
+            AZ_Printf(
+                "SimulationInterfacesConsole", "Failed to get entity state: %s\n", entityStateResult.GetError().m_errorString.c_str());
             return;
             return;
         }
         }
-        const auto &entityState = entityStateResult.GetValue();
+        const auto& entityState = entityStateResult.GetValue();
         AZ_Printf("SimulationInterfacesConsole", "Entity %s\n", entityName.c_str());
         AZ_Printf("SimulationInterfacesConsole", "Entity %s\n", entityName.c_str());
-        AZ_Printf(
-            "SimulationInterfacesConsole",
-            "Pose %s\n",
-            AZ::Vector3ToString(entityState.m_pose.GetTranslation()).c_str());
-        AZ_Printf(
-            "SimulationInterfacesConsole",
-            "Rotation %s \n",
-             AZ::QuaternionToString(entityState.m_pose.GetRotation()).c_str());
+        AZ_Printf("SimulationInterfacesConsole", "Pose %s\n", AZ::Vector3ToString(entityState.m_pose.GetTranslation()).c_str());
+        AZ_Printf("SimulationInterfacesConsole", "Rotation %s \n", AZ::QuaternionToString(entityState.m_pose.GetRotation()).c_str());
 
 
         const AZ::Vector3 euler = entityState.m_pose.GetRotation().GetEulerDegrees();
         const AZ::Vector3 euler = entityState.m_pose.GetRotation().GetEulerDegrees();
         AZ_Printf("SimulationInterfacesConsole", "Rotation (euler) %s\n", AZ::Vector3ToString(euler).c_str());
         AZ_Printf("SimulationInterfacesConsole", "Rotation (euler) %s\n", AZ::Vector3ToString(euler).c_str());
-        AZ_Printf(
-            "SimulationInterfacesConsole",
-            "Twist Linear %s\n",
-            AZ::Vector3ToString(entityState.m_twist_linear).c_str());
-        AZ_Printf(
-            "SimulationInterfacesConsole",
-            "Twist Angular %s\n",
-            AZ::Vector3ToString(entityState.m_twist_angular).c_str());
+        AZ_Printf("SimulationInterfacesConsole", "Twist Linear %s\n", AZ::Vector3ToString(entityState.m_twistLinear).c_str());
+        AZ_Printf("SimulationInterfacesConsole", "Twist Angular %s\n", AZ::Vector3ToString(entityState.m_twistAngular).c_str());
     }
     }
 
 
     static void simulationinterfaces_SetStateXYZ(const AZ::ConsoleCommandContainer& arguments)
     static void simulationinterfaces_SetStateXYZ(const AZ::ConsoleCommandContainer& arguments)
@@ -143,11 +134,10 @@ namespace SimulationInterfacesCommands
 
 
         if (!result.IsSuccess())
         if (!result.IsSuccess())
         {
         {
-            AZ_Printf("SimulationInterfacesConsole", "Failed to set entity state: %s\n", result.GetError().error_string.c_str());
+            AZ_Printf("SimulationInterfacesConsole", "Failed to set entity state: %s\n", result.GetError().m_errorString.c_str());
             return;
             return;
         }
         }
         AZ_Printf("SimulationInterfacesConsole", "Entity %s state set\n", entityName.c_str());
         AZ_Printf("SimulationInterfacesConsole", "Entity %s state set\n", entityName.c_str());
-
     }
     }
 
 
     static void simulationinterfaces_DeleteEntity(const AZ::ConsoleCommandContainer& arguments)
     static void simulationinterfaces_DeleteEntity(const AZ::ConsoleCommandContainer& arguments)
@@ -166,11 +156,10 @@ namespace SimulationInterfacesCommands
             }
             }
             else
             else
             {
             {
-                AZ_Printf("SimulationInterfacesConsole", "Failed to delete entity: %s\n", result.GetError().error_string.c_str());
+                AZ_Printf("SimulationInterfacesConsole", "Failed to delete entity: %s\n", result.GetError().m_errorString.c_str());
             }
             }
         };
         };
         SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteEntity, entityName, cb);
         SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteEntity, entityName, cb);
-
     }
     }
 
 
     static void simulationinterfaces_GetSpawnables(const AZ::ConsoleCommandContainer& arguments)
     static void simulationinterfaces_GetSpawnables(const AZ::ConsoleCommandContainer& arguments)
@@ -180,7 +169,7 @@ namespace SimulationInterfacesCommands
         SimulationEntityManagerRequestBus::BroadcastResult(spawnables, &SimulationEntityManagerRequestBus::Events::GetSpawnables);
         SimulationEntityManagerRequestBus::BroadcastResult(spawnables, &SimulationEntityManagerRequestBus::Events::GetSpawnables);
         if (!spawnables.IsSuccess())
         if (!spawnables.IsSuccess())
         {
         {
-            AZ_Printf("SimulationInterfacesConsole", "Failed to get spawnables: %s\n", spawnables.GetError().error_string.c_str());
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get spawnables: %s\n", spawnables.GetError().m_errorString.c_str());
             return;
             return;
         }
         }
         for (const auto& spawnable : spawnables.GetValue())
         for (const auto& spawnable : spawnables.GetValue())
@@ -205,24 +194,23 @@ namespace SimulationInterfacesCommands
         AZ::Transform initialPose = AZ::Transform::CreateIdentity();
         AZ::Transform initialPose = AZ::Transform::CreateIdentity();
         if (arguments.size() > 5)
         if (arguments.size() > 5)
         {
         {
-            initialPose.SetTranslation(
-                AZ::Vector3(
-                    AZStd::stof(AZStd::string(arguments[3])),
-                    AZStd::stof(AZStd::string(arguments[4])),
-                    AZStd::stof(AZStd::string(arguments[5]))));
+            initialPose.SetTranslation(AZ::Vector3(
+                AZStd::stof(AZStd::string(arguments[3])),
+                AZStd::stof(AZStd::string(arguments[4])),
+                AZStd::stof(AZStd::string(arguments[5]))));
         }
         }
         SpawnCompletedCb completedCb = [](const AZ::Outcome<AZStd::string, FailedResult>& result)
         SpawnCompletedCb completedCb = [](const AZ::Outcome<AZStd::string, FailedResult>& result)
         {
         {
             if (!result.IsSuccess())
             if (!result.IsSuccess())
             {
             {
-                AZ_Printf("SimulationInterfacesConsole", "Failed to spawn entity: %s\n", result.GetError().error_string.c_str());
+                AZ_Printf("SimulationInterfacesConsole", "Failed to spawn entity: %s\n", result.GetError().m_errorString.c_str());
                 return;
                 return;
             }
             }
             AZ_Printf("SimulationInterfacesConsole", "Entity spawned and registered : %s\n", result.GetValue().c_str());
             AZ_Printf("SimulationInterfacesConsole", "Entity spawned and registered : %s\n", result.GetValue().c_str());
-
         };
         };
         constexpr bool allowRename = true;
         constexpr bool allowRename = true;
-        SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::SpawnEntity, name, uri, entityNamespace, initialPose, allowRename, completedCb);
+        SimulationEntityManagerRequestBus::Broadcast(
+            &SimulationEntityManagerRequestBus::Events::SpawnEntity, name, uri, entityNamespace, initialPose, allowRename, completedCb);
         AZ_Printf("SimulationInterfacesConsole", "simulationinterface_Spawn %s %s\n", name.c_str(), uri.c_str());
         AZ_Printf("SimulationInterfacesConsole", "simulationinterface_Spawn %s %s\n", name.c_str(), uri.c_str());
     }
     }
 
 
@@ -245,7 +233,8 @@ namespace SimulationInterfacesCommands
             }
             }
             else
             else
             {
             {
-                AZ_Printf("SimulationInterfacesConsole", "Failed to delete all spawned entities: %s\n", result.GetError().error_string.c_str());
+                AZ_Printf(
+                    "SimulationInterfacesConsole", "Failed to delete all spawned entities: %s\n", result.GetError().m_errorString.c_str());
             }
             }
         };
         };
         SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteAllEntities, cb);
         SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteAllEntities, cb);
@@ -258,7 +247,6 @@ namespace SimulationInterfacesCommands
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Resume, AZ::ConsoleFunctorFlags::DontReplicate, "Resume simulation.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Resume, AZ::ConsoleFunctorFlags::DontReplicate, "Resume simulation.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Step, AZ::ConsoleFunctorFlags::DontReplicate, "Step simulation.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Step, AZ::ConsoleFunctorFlags::DontReplicate, "Step simulation.");
 
 
-
     AZ_CONSOLEFREEFUNC(
     AZ_CONSOLEFREEFUNC(
         simulationinterfaces_GetEntitiesSphere, AZ::ConsoleFunctorFlags::DontReplicate, "Get all simulated entities in the radius.");
         simulationinterfaces_GetEntitiesSphere, AZ::ConsoleFunctorFlags::DontReplicate, "Get all simulated entities in the radius.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_GetEntityState, AZ::ConsoleFunctorFlags::DontReplicate, "Get state of the entity.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_GetEntityState, AZ::ConsoleFunctorFlags::DontReplicate, "Get state of the entity.");

+ 57 - 79
Gems/SimulationInterfaces/Code/Source/Clients/SimulationEntitiesManager.cpp

@@ -20,6 +20,7 @@
 #include <AzCore/Component/TransformBus.h>
 #include <AzCore/Component/TransformBus.h>
 #include <AzCore/Console/IConsole.h>
 #include <AzCore/Console/IConsole.h>
 #include <AzCore/Serialization/SerializeContext.h>
 #include <AzCore/Serialization/SerializeContext.h>
+#include <AzCore/Settings/SettingsRegistry.h>
 #include <AzCore/std/containers/vector.h>
 #include <AzCore/std/containers/vector.h>
 #include <AzCore/std/string/regex.h>
 #include <AzCore/std/string/regex.h>
 #include <AzFramework/Components/TransformComponent.h>
 #include <AzFramework/Components/TransformComponent.h>
@@ -28,7 +29,6 @@
 #include <AzFramework/Physics/SimulatedBodies/RigidBody.h>
 #include <AzFramework/Physics/SimulatedBodies/RigidBody.h>
 #include <AzFramework/Spawnable/Spawnable.h>
 #include <AzFramework/Spawnable/Spawnable.h>
 #include <AzFramework/Spawnable/SpawnableEntitiesInterface.h>
 #include <AzFramework/Spawnable/SpawnableEntitiesInterface.h>
-#include <AzCore/Settings/SettingsRegistry.h>
 
 
 #include <ROS2/Frame/ROS2FrameComponent.h>
 #include <ROS2/Frame/ROS2FrameComponent.h>
 #include <simulation_interfaces/msg/result.hpp>
 #include <simulation_interfaces/msg/result.hpp>
@@ -37,22 +37,34 @@
 
 
 namespace SimulationInterfaces
 namespace SimulationInterfaces
 {
 {
-    void SetRigidBodyVelocities(AzPhysics::RigidBody* rigidBody, const EntityState& state)
+    namespace
     {
     {
-        if (!state.m_twist_angular.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
+        void SetRigidBodyVelocities(AzPhysics::RigidBody* rigidBody, const EntityState& state)
         {
         {
-            // get transform
-            AZ::Vector3 angularVelWorld = rigidBody->GetTransform().TransformVector(state.m_twist_angular);
-            rigidBody->SetAngularVelocity(angularVelWorld);
+            if (!state.m_twistAngular.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
+            {
+                // get transform
+                AZ::Vector3 angularVelWorld = rigidBody->GetTransform().TransformVector(state.m_twistAngular);
+                rigidBody->SetAngularVelocity(angularVelWorld);
+            }
+
+            if (!state.m_twistLinear.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
+            {
+                // get transform
+                AZ::Vector3 linearVelWorld = rigidBody->GetTransform().TransformVector(state.m_twistLinear);
+                rigidBody->SetLinearVelocity(linearVelWorld);
+            }
         }
         }
 
 
-        if (!state.m_twist_linear.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
+        AzPhysics::Scene* GetSceneHelper(AzPhysics::SceneHandle sceneHandle)
         {
         {
-            // get transform
-            AZ::Vector3 linearVelWorld = rigidBody->GetTransform().TransformVector(state.m_twist_linear);
-            rigidBody->SetLinearVelocity(linearVelWorld);
+            AzPhysics::SystemInterface* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
+            AZ_Assert(physicsSystem, "Physics system is not available.");
+            AzPhysics::Scene* scene = physicsSystem->GetScene(sceneHandle);
+            return scene;
         }
         }
-    }
+
+    } // namespace
 
 
     AZ_COMPONENT_IMPL(SimulationEntitiesManager, "SimulationEntitiesManager", SimulationEntitiesManagerTypeId);
     AZ_COMPONENT_IMPL(SimulationEntitiesManager, "SimulationEntitiesManager", SimulationEntitiesManagerTypeId);
 
 
@@ -106,15 +118,6 @@ namespace SimulationInterfaces
     {
     {
     }
     }
 
 
-    AzPhysics::Scene* GetSceneHelper(AzPhysics::SceneHandle sceneHandle)
-    {
-        AzPhysics::SystemInterface* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
-        AZ_Assert(physicsSystem, "Physics system is not available.");
-        AzPhysics::Scene* scene = physicsSystem->GetScene(sceneHandle);
-        return scene;
-    }
-
-
     bool SimulationEntitiesManager::RegisterNewSimulatedBody(AzPhysics::SceneHandle sceneHandle, AzPhysics::SimulatedBodyHandle bodyHandle)
     bool SimulationEntitiesManager::RegisterNewSimulatedBody(AzPhysics::SceneHandle sceneHandle, AzPhysics::SimulatedBodyHandle bodyHandle)
     {
     {
         auto* scene = GetSceneHelper(sceneHandle);
         auto* scene = GetSceneHelper(sceneHandle);
@@ -158,8 +161,7 @@ namespace SimulationInterfaces
         auto spawnDataIt = m_spawnCompletedCallbacks.find(ticketId);
         auto spawnDataIt = m_spawnCompletedCallbacks.find(ticketId);
         const bool wasSpawned = spawnDataIt != m_spawnCompletedCallbacks.end();
         const bool wasSpawned = spawnDataIt != m_spawnCompletedCallbacks.end();
 
 
-        const AZStd::string proposedName =
-            wasSpawned ? spawnDataIt->second.m_userProposedName : entity->GetName();
+        const AZStd::string proposedName = wasSpawned ? spawnDataIt->second.m_userProposedName : entity->GetName();
 
 
         // register entity
         // register entity
         const AZStd::string registeredName = this->AddSimulatedEntity(entityId, proposedName);
         const AZStd::string registeredName = this->AddSimulatedEntity(entityId, proposedName);
@@ -176,8 +178,8 @@ namespace SimulationInterfaces
         initialState.m_pose = entity->GetTransform()->GetWorldTM();
         initialState.m_pose = entity->GetTransform()->GetWorldTM();
         if (rigidBody)
         if (rigidBody)
         {
         {
-            initialState.m_twist_linear = rigidBody->GetLinearVelocity();
-            initialState.m_twist_angular = rigidBody->GetAngularVelocity();
+            initialState.m_twistLinear = rigidBody->GetLinearVelocity();
+            initialState.m_twistAngular = rigidBody->GetAngularVelocity();
         }
         }
         m_entityIdToInitialState[entityId] = initialState;
         m_entityIdToInitialState[entityId] = initialState;
         AZ_Info("SimulationInterfaces", "Registered entity %s\n", registeredName.c_str());
         AZ_Info("SimulationInterfaces", "Registered entity %s\n", registeredName.c_str());
@@ -224,7 +226,10 @@ namespace SimulationInterfaces
         m_sceneAddedHandler = AzPhysics::SystemEvents::OnSceneAddedEvent::Handler(
         m_sceneAddedHandler = AzPhysics::SystemEvents::OnSceneAddedEvent::Handler(
             [this](AzPhysics::SceneHandle sceneHandle)
             [this](AzPhysics::SceneHandle sceneHandle)
             {
             {
-                AZ_Warning("SimulationInterfaces", m_physicsScenesHandle == AzPhysics::InvalidSceneHandle, "Hmm, we already have a scene");
+                AZ_Warning(
+                    "SimulationInterfaces",
+                    m_physicsScenesHandle == AzPhysics::InvalidSceneHandle,
+                    "SimulationInterfaces already gathered physics scene");
                 auto* scene = GetSceneHelper(sceneHandle);
                 auto* scene = GetSceneHelper(sceneHandle);
                 AZ_Assert(scene, "Scene is not available.");
                 AZ_Assert(scene, "Scene is not available.");
                 if (scene == nullptr)
                 if (scene == nullptr)
@@ -259,15 +264,15 @@ namespace SimulationInterfaces
 
 
         SimulationFeaturesAggregatorRequestBus::Broadcast(
         SimulationFeaturesAggregatorRequestBus::Broadcast(
             &SimulationFeaturesAggregatorRequests::AddSimulationFeatures,
             &SimulationFeaturesAggregatorRequests::AddSimulationFeatures,
-            AZStd::unordered_set<SimulationFeatures>{ // simulation_interfaces::msg::SimulatorFeatures::ENTITY_TAGS,
-                                                      simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_BOX,
-                                                      // simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_CONVEX,
-                                                      // simulation_interfaces::msg::SimulatorFeatures::ENTITY_CATEGORIES,
-                                                      simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_GETTING,
-                                                      simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_SETTING,
-                                                      simulation_interfaces::msg::SimulatorFeatures::DELETING,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SPAWNABLES,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SPAWNING });
+            AZStd::unordered_set<SimulationFeatureType>{ // simulation_interfaces::msg::SimulatorFeatures::ENTITY_TAGS,
+                                                         simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_BOX,
+                                                         // simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_CONVEX,
+                                                         // simulation_interfaces::msg::SimulatorFeatures::ENTITY_CATEGORIES,
+                                                         simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_GETTING,
+                                                         simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_SETTING,
+                                                         simulation_interfaces::msg::SimulatorFeatures::DELETING,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SPAWNABLES,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SPAWNING });
         AZ::TickBus::Handler::BusConnect();
         AZ::TickBus::Handler::BusConnect();
     }
     }
 
 
@@ -275,28 +280,18 @@ namespace SimulationInterfaces
     {
     {
         AZ::TickBus::Handler::BusDisconnect();
         AZ::TickBus::Handler::BusDisconnect();
         SimulationEntityManagerRequestBus::Handler::BusDisconnect();
         SimulationEntityManagerRequestBus::Handler::BusDisconnect();
-        if (m_simulationBodyAddedHandler.IsConnected())
-        {
-            m_simulationBodyAddedHandler.Disconnect();
-        }
-        if (m_simulationBodyRemovedHandler.IsConnected())
-        {
-            m_simulationBodyRemovedHandler.Disconnect();
-        }
+
+        m_simulationBodyAddedHandler.Disconnect();
+        m_simulationBodyRemovedHandler.Disconnect();
+
         m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
         m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
-        if (m_sceneAddedHandler.IsConnected())
-        {
-            m_sceneAddedHandler.Disconnect();
-        }
-        if (m_sceneAddedHandler.IsConnected())
-        {
-            m_sceneAddedHandler.Disconnect();
-        }
+
+        m_sceneAddedHandler.Disconnect();
+        m_sceneAddedHandler.Disconnect();
     }
     }
 
 
     AZStd::string SimulationEntitiesManager::AddSimulatedEntity(AZ::EntityId entityId, const AZStd::string& userProposedName)
     AZStd::string SimulationEntitiesManager::AddSimulatedEntity(AZ::EntityId entityId, const AZStd::string& userProposedName)
     {
     {
-
         if (!entityId.IsValid())
         if (!entityId.IsValid())
         {
         {
             return "";
             return "";
@@ -332,15 +327,15 @@ namespace SimulationInterfaces
 
 
     AZ::Outcome<EntityNameList, FailedResult> SimulationEntitiesManager::GetEntities(const EntityFilters& filter)
     AZ::Outcome<EntityNameList, FailedResult> SimulationEntitiesManager::GetEntities(const EntityFilters& filter)
     {
     {
-        if (!filter.m_tags_filter.m_tags.empty())
+        if (!filter.m_tagsFilter.m_tags.empty())
         {
         {
             AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
             AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
             return AZ::Failure(
             return AZ::Failure(
                 FailedResult(simulation_interfaces::msg::Result::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
                 FailedResult(simulation_interfaces::msg::Result::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
         }
         }
 
 
-        const bool reFilter = !filter.m_filter.empty();
-        const bool shapeCastFilter = filter.m_bounds_shape != nullptr;
+        const bool reFilter = !filter.m_nameFilter.empty();
+        const bool shapeCastFilter = filter.m_boundsShape != nullptr;
 
 
         AZStd::vector<AZStd::string> entities;
         AZStd::vector<AZStd::string> entities;
         if (!shapeCastFilter)
         if (!shapeCastFilter)
@@ -368,8 +363,8 @@ namespace SimulationInterfaces
             }
             }
 
 
             AzPhysics::OverlapRequest request;
             AzPhysics::OverlapRequest request;
-            request.m_shapeConfiguration = filter.m_bounds_shape;
-            request.m_pose = filter.m_bounds_pose;
+            request.m_shapeConfiguration = filter.m_boundsShape;
+            request.m_pose = filter.m_boundsPose;
             request.m_maxResults = AZStd::numeric_limits<AZ::u32>::max();
             request.m_maxResults = AZStd::numeric_limits<AZ::u32>::max();
 
 
             AzPhysics::SceneQueryHits result = sceneInterface->QueryScene(m_physicsScenesHandle, &request);
             AzPhysics::SceneQueryHits result = sceneInterface->QueryScene(m_physicsScenesHandle, &request);
@@ -387,7 +382,7 @@ namespace SimulationInterfaces
         {
         {
             const AZStd::vector<AZStd::string> prefilteredEntities = AZStd::move(entities);
             const AZStd::vector<AZStd::string> prefilteredEntities = AZStd::move(entities);
             entities.clear();
             entities.clear();
-            const AZStd::regex regex(filter.m_filter);
+            const AZStd::regex regex(filter.m_nameFilter);
             if (!regex.Valid())
             if (!regex.Valid())
             {
             {
                 AZ_Warning("SimulationInterfaces", false, "Invalid regex filter");
                 AZ_Warning("SimulationInterfaces", false, "Invalid regex filter");
@@ -426,14 +421,14 @@ namespace SimulationInterfaces
 
 
         // transform linear and angular velocities to entity frame
         // transform linear and angular velocities to entity frame
         const AZ::Transform entityTransformInv = entityState.m_pose.GetInverse();
         const AZ::Transform entityTransformInv = entityState.m_pose.GetInverse();
-        entityState.m_twist_linear = entityTransformInv.TransformVector(linearVelocity);
-        entityState.m_twist_angular = entityTransformInv.TransformVector(angularVelocity);
+        entityState.m_twistLinear = entityTransformInv.TransformVector(linearVelocity);
+        entityState.m_twistAngular = entityTransformInv.TransformVector(angularVelocity);
         return AZ::Success(entityState);
         return AZ::Success(entityState);
     }
     }
 
 
     AZ::Outcome<MultipleEntitiesStates, FailedResult> SimulationEntitiesManager::GetEntitiesStates(const EntityFilters& filter)
     AZ::Outcome<MultipleEntitiesStates, FailedResult> SimulationEntitiesManager::GetEntitiesStates(const EntityFilters& filter)
     {
     {
-        if (!filter.m_tags_filter.m_tags.empty())
+        if (!filter.m_tagsFilter.m_tags.empty())
         {
         {
             AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
             AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
             return AZ::Failure(
             return AZ::Failure(
@@ -514,7 +509,7 @@ namespace SimulationInterfaces
             }
             }
         }
         }
 
 
-        if (!state.m_twist_linear.IsZero(AZ::Constants::FloatEpsilon) || !state.m_twist_angular.IsZero(AZ::Constants::FloatEpsilon))
+        if (!state.m_twistLinear.IsZero(AZ::Constants::FloatEpsilon) || !state.m_twistAngular.IsZero(AZ::Constants::FloatEpsilon))
         {
         {
             // get rigid body
             // get rigid body
             AzPhysics::RigidBody* rigidBody = nullptr;
             AzPhysics::RigidBody* rigidBody = nullptr;
@@ -571,23 +566,6 @@ namespace SimulationInterfaces
             const auto msg = AZStd::string::format("Entity %s was not spawned by this component, wont delete it", name.c_str());
             const auto msg = AZStd::string::format("Entity %s was not spawned by this component, wont delete it", name.c_str());
             completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg)));
             completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg)));
         }
         }
-#ifdef POTENTIALY_UNSAFE
-        if (findIt != m_simulatedEntityToEntityIdMap.end())
-        {
-            const AZ::EntityId entityId = findIt->second;
-            AZ_Assert(entityId.IsValid(), "EntityId is not valid");
-            // get all descendants
-            AZStd::vector<AZ::EntityId> entityAndDescendants;
-            AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
-            for (const auto& descendant : entityAndDescendants)
-            {
-                // I am not sure if this is the safe way to delete an entity
-                AZ::ComponentApplicationBus::Broadcast(&AZ::ComponentApplicationRequests::DeleteEntity, descendant);
-            }
-
-            return true;
-        }
-#endif
     }
     }
 
 
     void SimulationEntitiesManager::DeleteAllEntities(DeletionCompletedCb completedCb)
     void SimulationEntitiesManager::DeleteAllEntities(DeletionCompletedCb completedCb)
@@ -790,7 +768,7 @@ namespace SimulationInterfaces
         }
         }
 
 
         // check if name is still not unique, if not, add EntityId to name
         // check if name is still not unique, if not, add EntityId to name
-        if(m_simulatedEntityToEntityIdMap.contains(newName))
+        if (m_simulatedEntityToEntityIdMap.contains(newName))
         {
         {
             newName = AZStd::string::format("%s_%s", newName.c_str(), entityId.ToString().c_str());
             newName = AZStd::string::format("%s_%s", newName.c_str(), entityId.ToString().c_str());
         }
         }

+ 9 - 11
Gems/SimulationInterfaces/Code/Source/Clients/SimulationEntitiesManager.h

@@ -35,8 +35,12 @@ namespace SimulationInterfaces
 
 
         SimulationEntitiesManager();
         SimulationEntitiesManager();
         ~SimulationEntitiesManager();
         ~SimulationEntitiesManager();
+        // AZ::Component interface implementation
+        void Init() override;
+        void Activate() override;
+        void Deactivate() override;
 
 
-    protected:
+    private:
         // SimulationEntityManagerRequestBus interface implementation
         // SimulationEntityManagerRequestBus interface implementation
         AZ::Outcome<EntityNameList, FailedResult> GetEntities(const EntityFilters& filter) override;
         AZ::Outcome<EntityNameList, FailedResult> GetEntities(const EntityFilters& filter) override;
         AZ::Outcome<EntityState, FailedResult> GetEntityState(const AZStd::string& name) override;
         AZ::Outcome<EntityState, FailedResult> GetEntityState(const AZStd::string& name) override;
@@ -54,16 +58,9 @@ namespace SimulationInterfaces
             SpawnCompletedCb completedCb) override;
             SpawnCompletedCb completedCb) override;
         void ResetAllEntitiesToInitialState() override;
         void ResetAllEntitiesToInitialState() override;
 
 
-        // AZ::Component interface implementation
-        void Init() override;
-        void Activate() override;
-        void Deactivate() override;
-
         // AZ::TickBus::Handler interface implementation
         // AZ::TickBus::Handler interface implementation
         void OnTick(float deltaTime, AZ::ScriptTimePoint time) override;
         void OnTick(float deltaTime, AZ::ScriptTimePoint time) override;
 
 
-    private:
-
         //! Registers a new simulated body to the simulation interface.
         //! Registers a new simulated body to the simulation interface.
         //! Note that the body handle will be registered under unique name
         //! Note that the body handle will be registered under unique name
         //! Note that body need to be configured to be registered
         //! Note that body need to be configured to be registered
@@ -73,7 +70,8 @@ namespace SimulationInterfaces
 
 
         //! Registers a new simulated body to the simulation interface.
         //! Registers a new simulated body to the simulation interface.
         //! Returns the list of handles that were not registered
         //! Returns the list of handles that were not registered
-        AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>> RegisterNewSimulatedBodies(const AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>>& handles);
+        AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>> RegisterNewSimulatedBodies(
+            const AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>>& handles);
 
 
         //! Registers simulated entity to entity id mapping.
         //! Registers simulated entity to entity id mapping.
         //! Note that the entityId will be registered under unique name.
         //! Note that the entityId will be registered under unique name.
@@ -91,7 +89,6 @@ namespace SimulationInterfaces
         //! Set the state of the entity and their descendants.
         //! Set the state of the entity and their descendants.
         void SetEntitiesState(const AZStd::vector<AZ::EntityId>& entityAndDescendants, const EntityState& state);
         void SetEntitiesState(const AZStd::vector<AZ::EntityId>& entityAndDescendants, const EntityState& state);
 
 
-
         AzPhysics::SceneEvents::OnSimulationBodyAdded::Handler m_simulationBodyAddedHandler;
         AzPhysics::SceneEvents::OnSimulationBodyAdded::Handler m_simulationBodyAddedHandler;
         AzPhysics::SceneEvents::OnSimulationBodyRemoved::Handler m_simulationBodyRemovedHandler;
         AzPhysics::SceneEvents::OnSimulationBodyRemoved::Handler m_simulationBodyRemovedHandler;
 
 
@@ -99,7 +96,8 @@ namespace SimulationInterfaces
         AzPhysics::SystemEvents::OnSceneRemovedEvent::Handler m_sceneRemovedHandler;
         AzPhysics::SystemEvents::OnSceneRemovedEvent::Handler m_sceneRemovedHandler;
         AzPhysics::SceneHandle m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
         AzPhysics::SceneHandle m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
 
 
-        AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>> m_unconfiguredScenesHandles; //! Set of yet-invalid scenes handles, that are waiting for configuration
+        AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>>
+            m_unconfiguredScenesHandles; //! Set of yet-invalid scenes handles, that are waiting for configuration
         AZStd::unordered_map<AZStd::string, AZ::EntityId> m_simulatedEntityToEntityIdMap;
         AZStd::unordered_map<AZStd::string, AZ::EntityId> m_simulatedEntityToEntityIdMap;
         AZStd::unordered_map<AZ::EntityId, AZStd::string> m_entityIdToSimulatedEntityMap;
         AZStd::unordered_map<AZ::EntityId, AZStd::string> m_entityIdToSimulatedEntityMap;
         AZStd::unordered_map<AZ::EntityId, EntityState> m_entityIdToInitialState;
         AZStd::unordered_map<AZ::EntityId, EntityState> m_entityIdToInitialState;

+ 4 - 4
Gems/SimulationInterfaces/Code/Source/Clients/SimulationFeaturesAggregator.cpp

@@ -74,17 +74,17 @@ namespace SimulationInterfaces
         SimulationFeaturesAggregatorRequestBus::Handler::BusDisconnect();
         SimulationFeaturesAggregatorRequestBus::Handler::BusDisconnect();
     }
     }
 
 
-    void SimulationFeaturesAggregator::AddSimulationFeatures(const AZStd::unordered_set<SimulationFeatures>& features)
+    void SimulationFeaturesAggregator::AddSimulationFeatures(const AZStd::unordered_set<SimulationFeatureType>& features)
     {
     {
         m_registeredFeatures.insert(features.begin(), features.end());
         m_registeredFeatures.insert(features.begin(), features.end());
     }
     }
-    
-    const AZStd::unordered_set<SimulationFeatures> SimulationFeaturesAggregator::GetSimulationFeatures() const
+
+    AZStd::unordered_set<SimulationFeatureType> SimulationFeaturesAggregator::GetSimulationFeatures()
     {
     {
         return m_registeredFeatures;
         return m_registeredFeatures;
     }
     }
 
 
-    bool SimulationFeaturesAggregator::HasFeature(SimulationFeatures feature) const
+    bool SimulationFeaturesAggregator::HasFeature(SimulationFeatureType feature)
     {
     {
         return m_registeredFeatures.contains(feature);
         return m_registeredFeatures.contains(feature);
     }
     }

+ 5 - 6
Gems/SimulationInterfaces/Code/Source/Clients/SimulationFeaturesAggregator.h

@@ -42,13 +42,12 @@ namespace SimulationInterfaces
         void Activate() override;
         void Activate() override;
         void Deactivate() override;
         void Deactivate() override;
 
 
-    protected:
+    private:
         // SimulationFeaturesAggregatorRequestBus overrides
         // SimulationFeaturesAggregatorRequestBus overrides
-        void AddSimulationFeatures(const AZStd::unordered_set<SimulationFeatures>& features) override;
-        const AZStd::unordered_set<SimulationFeatures> GetSimulationFeatures() const override;
-        bool HasFeature(SimulationFeatures feature) const override;
+        void AddSimulationFeatures(const AZStd::unordered_set<SimulationFeatureType>& features) override;
+        AZStd::unordered_set<SimulationFeatureType> GetSimulationFeatures() override;
+        bool HasFeature(SimulationFeatureType feature) override;
 
 
-    private:
-        AZStd::unordered_set<SimulationFeatures> m_registeredFeatures;
+        AZStd::unordered_set<SimulationFeatureType> m_registeredFeatures;
     };
     };
 } // namespace SimulationInterfaces
 } // namespace SimulationInterfaces

+ 10 - 10
Gems/SimulationInterfaces/Code/Source/Clients/SimulationManager.cpp

@@ -105,16 +105,16 @@ namespace SimulationInterfaces
         SimulationManagerRequestBus::Handler::BusConnect();
         SimulationManagerRequestBus::Handler::BusConnect();
         SimulationFeaturesAggregatorRequestBus::Broadcast(
         SimulationFeaturesAggregatorRequestBus::Broadcast(
             &SimulationFeaturesAggregatorRequests::AddSimulationFeatures,
             &SimulationFeaturesAggregatorRequests::AddSimulationFeatures,
-            AZStd::unordered_set<SimulationFeatures>{ simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET_TIME,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET_STATE,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET_SPAWNED,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SIMULATION_STATE_PAUSE,
-                                                      simulation_interfaces::msg::SimulatorFeatures::STEP_SIMULATION_SINGLE,
-                                                      simulation_interfaces::msg::SimulatorFeatures::STEP_SIMULATION_MULTIPLE,
-                                                      simulation_interfaces::msg::SimulatorFeatures::STEP_SIMULATION_ACTION,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SIMULATION_STATE_SETTING,
-                                                      simulation_interfaces::msg::SimulatorFeatures::SIMULATION_STATE_GETTING });
+            AZStd::unordered_set<SimulationFeatureType>{ simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET_TIME,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET_STATE,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SIMULATION_RESET_SPAWNED,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SIMULATION_STATE_PAUSE,
+                                                         simulation_interfaces::msg::SimulatorFeatures::STEP_SIMULATION_SINGLE,
+                                                         simulation_interfaces::msg::SimulatorFeatures::STEP_SIMULATION_MULTIPLE,
+                                                         simulation_interfaces::msg::SimulatorFeatures::STEP_SIMULATION_ACTION,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SIMULATION_STATE_SETTING,
+                                                         simulation_interfaces::msg::SimulatorFeatures::SIMULATION_STATE_GETTING });
         AZ::SystemTickBus::QueueFunction(
         AZ::SystemTickBus::QueueFunction(
             [this]()
             [this]()
             {
             {

+ 1 - 3
Gems/SimulationInterfaces/Code/Source/Clients/SimulationManager.h

@@ -46,7 +46,7 @@ namespace SimulationInterfaces
         void Activate() override;
         void Activate() override;
         void Deactivate() override;
         void Deactivate() override;
 
 
-    protected:
+    private:
         // SimulationManagerRequestBus interface implementation
         // SimulationManagerRequestBus interface implementation
         void SetSimulationPaused(bool paused) override;
         void SetSimulationPaused(bool paused) override;
         void StepSimulation(AZ::u64 steps) override;
         void StepSimulation(AZ::u64 steps) override;
@@ -60,7 +60,6 @@ namespace SimulationInterfaces
         // LevelSystemLifecycleNotificationBus interface implementation
         // LevelSystemLifecycleNotificationBus interface implementation
         void OnLoadingComplete(const char* levelName) override;
         void OnLoadingComplete(const char* levelName) override;
 
 
-    private:
         bool m_isSimulationPaused = false;
         bool m_isSimulationPaused = false;
         uint64_t m_numberOfPhysicsSteps = 0;
         uint64_t m_numberOfPhysicsSteps = 0;
         AzPhysics::SceneEvents::OnSceneSimulationFinishHandler m_simulationFinishEvent;
         AzPhysics::SceneEvents::OnSceneSimulationFinishHandler m_simulationFinishEvent;
@@ -70,7 +69,6 @@ namespace SimulationInterfaces
         }; // default simulation state based on standard
         }; // default simulation state based on standard
         void InitializeSimulationState();
         void InitializeSimulationState();
 
 
-    private:
         bool IsTransitionForbidden(SimulationState requestedState);
         bool IsTransitionForbidden(SimulationState requestedState);
         // forbidden transition between state, first is current state, second is desire state
         // forbidden transition between state, first is current state, second is desire state
         const AZStd::array<AZStd::pair<SimulationState, SimulationState>, 4> m_forbiddenStatesTransitions{ {
         const AZStd::array<AZStd::pair<SimulationState, SimulationState>, 4> m_forbiddenStatesTransitions{ {

+ 2 - 2
Gems/SimulationInterfaces/Code/Source/Services/DeleteEntityServiceHandler.cpp

@@ -36,8 +36,8 @@ namespace ROS2SimulationInterfaces
                 else
                 else
                 {
                 {
                     const auto& failedResult = outcome.GetError();
                     const auto& failedResult = outcome.GetError();
-                    response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-                    response.result.error_message = failedResult.error_string.c_str();
+                    response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+                    response.result.error_message = failedResult.m_errorString.c_str();
                 }
                 }
                 SendResponse(response);
                 SendResponse(response);
             });
             });

+ 2 - 2
Gems/SimulationInterfaces/Code/Source/Services/GetEntitiesServiceHandler.cpp

@@ -43,8 +43,8 @@ namespace ROS2SimulationInterfaces
         if (!outcome.IsSuccess())
         if (!outcome.IsSuccess())
         {
         {
             const auto& failedResult = outcome.GetError();
             const auto& failedResult = outcome.GetError();
-            response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-            response.result.error_message = failedResult.error_string.c_str();
+            response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+            response.result.error_message = failedResult.m_errorString.c_str();
             return response;
             return response;
         }
         }
 
 

+ 17 - 29
Gems/SimulationInterfaces/Code/Source/Services/GetEntitiesStatesServiceHandler.cpp

@@ -45,40 +45,28 @@ namespace ROS2SimulationInterfaces
         if (!outcome.IsSuccess())
         if (!outcome.IsSuccess())
         {
         {
             const auto& failedResult = outcome.GetError();
             const auto& failedResult = outcome.GetError();
-            response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-            response.result.error_message = failedResult.error_string.c_str();
+            response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+            response.result.error_message = failedResult.m_errorString.c_str();
             return response;
             return response;
         }
         }
 
 
         const auto& multipleEntitiesStates = outcome.GetValue();
         const auto& multipleEntitiesStates = outcome.GetValue();
-        std::vector<std::string> stdEntities;
-        std::vector<simulation_interfaces::msg::EntityState> stdEntityStates;
 
 
-        AZStd::transform(
-            multipleEntitiesStates.begin(),
-            multipleEntitiesStates.end(),
-            std::back_inserter(stdEntities),
-            [](const auto& pair)
-            {
-                return pair.first.c_str();
-            });
-        AZStd::transform(
-            multipleEntitiesStates.begin(),
-            multipleEntitiesStates.end(),
-            std::back_inserter(stdEntityStates),
-            [](const auto& pair)
-            {
-                const SimulationInterfaces::EntityState& entityState = pair.second;
-                simulation_interfaces::msg::EntityState simulationInterfacesEntityState;
-                simulationInterfacesEntityState.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
-                simulationInterfacesEntityState.header.frame_id = ROS2::ROS2Interface::Get()->GetNode()->get_name();
-                simulationInterfacesEntityState.pose = ROS2::ROS2Conversions::ToROS2Pose(entityState.m_pose);
-                simulationInterfacesEntityState.twist.linear = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twist_linear);
-                simulationInterfacesEntityState.twist.angular = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twist_angular);
-                return simulationInterfacesEntityState;
-            });
-        response.entities = stdEntities;
-        response.states = stdEntityStates;
+        response.entities.reserve(multipleEntitiesStates.size());
+        response.states.reserve(multipleEntitiesStates.size());
+        for (auto& [entityName, entityState] : multipleEntitiesStates)
+        {
+            // entity name
+            response.entities.push_back(entityName.c_str());
+            // entity state
+            simulation_interfaces::msg::EntityState simulationInterfacesEntityState;
+            simulationInterfacesEntityState.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
+            simulationInterfacesEntityState.header.frame_id = "";
+            simulationInterfacesEntityState.pose = ROS2::ROS2Conversions::ToROS2Pose(entityState.m_pose);
+            simulationInterfacesEntityState.twist.linear = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twistLinear);
+            simulationInterfacesEntityState.twist.angular = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twistAngular);
+            response.states.push_back(simulationInterfacesEntityState);
+        }
 
 
         return response;
         return response;
     }
     }

+ 5 - 5
Gems/SimulationInterfaces/Code/Source/Services/GetEntityStateServiceHandler.cpp

@@ -33,18 +33,18 @@ namespace ROS2SimulationInterfaces
         if (!outcome.IsSuccess())
         if (!outcome.IsSuccess())
         {
         {
             const auto& failedResult = outcome.GetError();
             const auto& failedResult = outcome.GetError();
-            response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-            response.result.error_message = failedResult.error_string.c_str();
+            response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+            response.result.error_message = failedResult.m_errorString.c_str();
             return response;
             return response;
         }
         }
 
 
         const auto& entityState = outcome.GetValue();
         const auto& entityState = outcome.GetValue();
         simulation_interfaces::msg::EntityState entityStateMsg;
         simulation_interfaces::msg::EntityState entityStateMsg;
         entityStateMsg.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
         entityStateMsg.header.stamp = ROS2::ROS2Interface::Get()->GetROSTimestamp();
-        entityStateMsg.header.frame_id = ROS2::ROS2Interface::Get()->GetNode()->get_name();
+        entityStateMsg.header.frame_id = "";
         entityStateMsg.pose = ROS2::ROS2Conversions::ToROS2Pose(entityState.m_pose);
         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);
+        entityStateMsg.twist.linear = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twistLinear);
+        entityStateMsg.twist.angular = ROS2::ROS2Conversions::ToROS2Vector3(entityState.m_twistAngular);
 
 
         response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
         response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
         response.state = entityStateMsg;
         response.state = entityStateMsg;

+ 6 - 7
Gems/SimulationInterfaces/Code/Source/Services/GetSimulationFeaturesServiceHandler.cpp

@@ -10,37 +10,36 @@
 #include <AzCore/base.h>
 #include <AzCore/base.h>
 #include <AzCore/std/containers/unordered_set.h>
 #include <AzCore/std/containers/unordered_set.h>
 #include <SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h>
 #include <SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h>
-#include <SimulationInterfaces/ROS2SimulationInterfacesRequestBus.h>
 
 
 namespace ROS2SimulationInterfaces
 namespace ROS2SimulationInterfaces
 {
 {
 
 
-    AZStd::unordered_set<AZ::u8> GetSimulationFeaturesServiceHandler::GetProvidedFeatures()
+    AZStd::unordered_set<SimulationFeatureType> GetSimulationFeaturesServiceHandler::GetProvidedFeatures()
     {
     {
         // standard doesn't define specific feature id for this service
         // standard doesn't define specific feature id for this service
-        return AZStd::unordered_set<AZ::u8>{};
+        return AZStd::unordered_set<SimulationFeatureType>{};
     }
     }
 
 
     AZStd::optional<GetSimulationFeaturesServiceHandler::Response> GetSimulationFeaturesServiceHandler::HandleServiceRequest(
     AZStd::optional<GetSimulationFeaturesServiceHandler::Response> GetSimulationFeaturesServiceHandler::HandleServiceRequest(
         const std::shared_ptr<rmw_request_id_t> header, const Request& request)
         const std::shared_ptr<rmw_request_id_t> header, const Request& request)
     {
     {
         // call bus to get simulation features in ROS2SimulationInterfaces Gem side
         // call bus to get simulation features in ROS2SimulationInterfaces Gem side
-        AZStd::unordered_set<AZ::u8> ros2Interfaces;
+        AZStd::unordered_set<SimulationFeatureType> ros2Interfaces;
         ROS2SimulationInterfacesRequestBus::BroadcastResult(ros2Interfaces, &ROS2SimulationInterfacesRequests::GetSimulationFeatures);
         ROS2SimulationInterfacesRequestBus::BroadcastResult(ros2Interfaces, &ROS2SimulationInterfacesRequests::GetSimulationFeatures);
         // call bus to get simulation features on SimulationInterfaces Gem  side
         // call bus to get simulation features on SimulationInterfaces Gem  side
-        AZStd::unordered_set<SimulationInterfaces::SimulationFeatures> o3deInterfaces;
+        AZStd::unordered_set<SimulationInterfaces::SimulationFeatureType> o3deInterfaces;
         SimulationInterfaces::SimulationFeaturesAggregatorRequestBus::BroadcastResult(
         SimulationInterfaces::SimulationFeaturesAggregatorRequestBus::BroadcastResult(
             o3deInterfaces, &SimulationInterfaces::SimulationFeaturesAggregatorRequests::GetSimulationFeatures);
             o3deInterfaces, &SimulationInterfaces::SimulationFeaturesAggregatorRequests::GetSimulationFeatures);
         // create common features and return it;
         // create common features and return it;
         // common features are logical AND between two sets
         // common features are logical AND between two sets
-        AZStd::unordered_set<AZ::u8> commonFeatures;
+        AZStd::unordered_set<SimulationFeatureType> commonFeatures;
         commonFeatures.insert(ros2Interfaces.begin(), ros2Interfaces.end());
         commonFeatures.insert(ros2Interfaces.begin(), ros2Interfaces.end());
         commonFeatures.insert(o3deInterfaces.begin(), o3deInterfaces.end());
         commonFeatures.insert(o3deInterfaces.begin(), o3deInterfaces.end());
 
 
         Response response;
         Response response;
         for (auto id : commonFeatures)
         for (auto id : commonFeatures)
         {
         {
-            if (ros2Interfaces.contains(id) && o3deInterfaces.contains(SimulationInterfaces::SimulationFeatures(id)))
+            if (ros2Interfaces.contains(id) && o3deInterfaces.contains(SimulationInterfaces::SimulationFeatureType(id)))
             {
             {
                 response.features.features.emplace_back(id);
                 response.features.features.emplace_back(id);
             }
             }

+ 2 - 1
Gems/SimulationInterfaces/Code/Source/Services/GetSimulationFeaturesServiceHandler.h

@@ -10,6 +10,7 @@
 
 
 #include "ROS2ServiceBase.h"
 #include "ROS2ServiceBase.h"
 #include <AzCore/std/string/string_view.h>
 #include <AzCore/std/string/string_view.h>
+#include <SimulationInterfaces/ROS2SimulationInterfacesRequestBus.h>
 #include <simulation_interfaces/srv/get_simulator_features.hpp>
 #include <simulation_interfaces/srv/get_simulator_features.hpp>
 
 
 namespace ROS2SimulationInterfaces
 namespace ROS2SimulationInterfaces
@@ -27,7 +28,7 @@ namespace ROS2SimulationInterfaces
         {
         {
             return "get_simulation_features";
             return "get_simulation_features";
         }
         }
-        AZStd::unordered_set<AZ::u8> GetProvidedFeatures() override;
+        AZStd::unordered_set<SimulationFeatureType> GetProvidedFeatures() override;
 
 
         AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
         AZStd::optional<Response> HandleServiceRequest(const std::shared_ptr<rmw_request_id_t> header, const Request& request) override;
 
 

+ 0 - 1
Gems/SimulationInterfaces/Code/Source/Services/GetSimulationStateServiceHandler.h

@@ -10,7 +10,6 @@
 
 
 #include "Services/ROS2ServiceBase.h"
 #include "Services/ROS2ServiceBase.h"
 #include <AzCore/std/string/string_view.h>
 #include <AzCore/std/string/string_view.h>
-#include <rclcpp/rclcpp.hpp>
 #include <simulation_interfaces/srv/get_simulation_state.hpp>
 #include <simulation_interfaces/srv/get_simulation_state.hpp>
 
 
 namespace ROS2SimulationInterfaces
 namespace ROS2SimulationInterfaces

+ 3 - 5
Gems/SimulationInterfaces/Code/Source/Services/GetSpawnablesServiceHandler.cpp

@@ -28,17 +28,16 @@ namespace ROS2SimulationInterfaces
         if (!outcome.IsSuccess())
         if (!outcome.IsSuccess())
         {
         {
             const auto& failedResult = outcome.GetError();
             const auto& failedResult = outcome.GetError();
-            response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-            response.result.error_message = failedResult.error_string.c_str();
+            response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+            response.result.error_message = failedResult.m_errorString.c_str();
             return response;
             return response;
         }
         }
 
 
         const auto& spawnableList = outcome.GetValue();
         const auto& spawnableList = outcome.GetValue();
-        std::vector<simulation_interfaces::msg::Spawnable> simSpawnables;
         AZStd::transform(
         AZStd::transform(
             spawnableList.begin(),
             spawnableList.begin(),
             spawnableList.end(),
             spawnableList.end(),
-            AZStd::back_inserter(simSpawnables),
+            AZStd::back_inserter(response.spawnables),
             [](const SimulationInterfaces::Spawnable& spawnable)
             [](const SimulationInterfaces::Spawnable& spawnable)
             {
             {
                 simulation_interfaces::msg::Spawnable simSpawnable;
                 simulation_interfaces::msg::Spawnable simSpawnable;
@@ -47,7 +46,6 @@ namespace ROS2SimulationInterfaces
                 return simSpawnable;
                 return simSpawnable;
             });
             });
         response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
         response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
-        response.spawnables = simSpawnables;
 
 
         return response;
         return response;
     }
     }

+ 0 - 1
Gems/SimulationInterfaces/Code/Source/Services/ROS2ServiceBase.h

@@ -12,7 +12,6 @@
 #include <AzCore/std/optional.h>
 #include <AzCore/std/optional.h>
 #include <Interfaces/IROS2HandlerBase.h>
 #include <Interfaces/IROS2HandlerBase.h>
 #include <Utils/RegistryUtils.h>
 #include <Utils/RegistryUtils.h>
-#include <rclcpp/rclcpp.hpp>
 #include <rclcpp/service.hpp>
 #include <rclcpp/service.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 
 

+ 2 - 2
Gems/SimulationInterfaces/Code/Source/Services/ResetSimulationServiceHandler.cpp

@@ -52,8 +52,8 @@ namespace ROS2SimulationInterfaces
                 else
                 else
                 {
                 {
                     const auto& failedResult = outcome.GetError();
                     const auto& failedResult = outcome.GetError();
-                    response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-                    response.result.error_message = failedResult.error_string.c_str();
+                    response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+                    response.result.error_message = failedResult.m_errorString.c_str();
                 }
                 }
                 SendResponse(response);
                 SendResponse(response);
             };
             };

+ 0 - 1
Gems/SimulationInterfaces/Code/Source/Services/ResetSimulationServiceHandler.h

@@ -10,7 +10,6 @@
 
 
 #include "ROS2ServiceBase.h"
 #include "ROS2ServiceBase.h"
 #include <AzCore/std/string/string_view.h>
 #include <AzCore/std/string/string_view.h>
-#include <rclcpp/rclcpp.hpp>
 #include <simulation_interfaces/srv/reset_simulation.hpp>
 #include <simulation_interfaces/srv/reset_simulation.hpp>
 
 
 namespace ROS2SimulationInterfaces
 namespace ROS2SimulationInterfaces

+ 4 - 4
Gems/SimulationInterfaces/Code/Source/Services/SetEntityStateServiceHandler.cpp

@@ -25,8 +25,8 @@ namespace ROS2SimulationInterfaces
         AZStd::string entityName = request.entity.c_str();
         AZStd::string entityName = request.entity.c_str();
         SimulationInterfaces::EntityState entityState;
         SimulationInterfaces::EntityState entityState;
         entityState.m_pose = ROS2::ROS2Conversions::FromROS2Pose(request.state.pose);
         entityState.m_pose = ROS2::ROS2Conversions::FromROS2Pose(request.state.pose);
-        entityState.m_twist_angular = ROS2::ROS2Conversions::FromROS2Vector3(request.state.twist.angular);
-        entityState.m_twist_linear = ROS2::ROS2Conversions::FromROS2Vector3(request.state.twist.linear);
+        entityState.m_twistAngular = ROS2::ROS2Conversions::FromROS2Vector3(request.state.twist.angular);
+        entityState.m_twistLinear = ROS2::ROS2Conversions::FromROS2Vector3(request.state.twist.linear);
 
 
         SimulationInterfaces::SimulationEntityManagerRequestBus::BroadcastResult(
         SimulationInterfaces::SimulationEntityManagerRequestBus::BroadcastResult(
             outcome, &SimulationInterfaces::SimulationEntityManagerRequests::SetEntityState, entityName, entityState);
             outcome, &SimulationInterfaces::SimulationEntityManagerRequests::SetEntityState, entityName, entityState);
@@ -36,8 +36,8 @@ namespace ROS2SimulationInterfaces
         if (!outcome.IsSuccess())
         if (!outcome.IsSuccess())
         {
         {
             const auto& failedResult = outcome.GetError();
             const auto& failedResult = outcome.GetError();
-            response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-            response.result.error_message = failedResult.error_string.c_str();
+            response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+            response.result.error_message = failedResult.m_errorString.c_str();
         }
         }
 
 
         return response;
         return response;

+ 2 - 2
Gems/SimulationInterfaces/Code/Source/Services/SetSimulationStateServiceHandler.cpp

@@ -33,8 +33,8 @@ namespace ROS2SimulationInterfaces
         }
         }
         else
         else
         {
         {
-            response.result.result = static_cast<AZ::u8>(transitionResult.GetError().error_code);
-            response.result.error_message = transitionResult.GetError().error_string.c_str();
+            response.result.result = static_cast<AZ::u8>(transitionResult.GetError().m_errorCode);
+            response.result.error_message = transitionResult.GetError().m_errorString.c_str();
         }
         }
         return response;
         return response;
     }
     }

+ 0 - 1
Gems/SimulationInterfaces/Code/Source/Services/SetSimulationStateServiceHandler.h

@@ -10,7 +10,6 @@
 
 
 #include "Services/ROS2ServiceBase.h"
 #include "Services/ROS2ServiceBase.h"
 #include <AzCore/std/string/string_view.h>
 #include <AzCore/std/string/string_view.h>
-#include <rclcpp/rclcpp.hpp>
 #include <simulation_interfaces/srv/set_simulation_state.hpp>
 #include <simulation_interfaces/srv/set_simulation_state.hpp>
 
 
 namespace ROS2SimulationInterfaces
 namespace ROS2SimulationInterfaces

+ 8 - 5
Gems/SimulationInterfaces/Code/Source/Services/SpawnEntityServiceHandler.cpp

@@ -28,7 +28,7 @@ namespace ROS2SimulationInterfaces
         const AZStd::string_view entityNamespace{ request.entity_namespace.c_str(), request.entity_namespace.size() };
         const AZStd::string_view entityNamespace{ request.entity_namespace.c_str(), request.entity_namespace.size() };
 
 
         // Validate entity name
         // Validate entity name
-        if (!ValidateEntityName(name))
+        if (!name.empty() && !ValidateEntityName(name))
         {
         {
             Response response;
             Response response;
             response.result.result = simulation_interfaces::srv::SpawnEntity::Response::NAME_INVALID;
             response.result.result = simulation_interfaces::srv::SpawnEntity::Response::NAME_INVALID;
@@ -42,7 +42,8 @@ namespace ROS2SimulationInterfaces
         {
         {
             Response response;
             Response response;
             response.result.result = simulation_interfaces::srv::SpawnEntity::Response::NAMESPACE_INVALID;
             response.result.result = simulation_interfaces::srv::SpawnEntity::Response::NAMESPACE_INVALID;
-            response.result.error_message = "Invalid entity namespace. Entity namespaces can only contain alphanumeric characters and forward slashes.";
+            response.result.error_message =
+                "Invalid entity namespace. Entity namespaces can only contain alphanumeric characters and forward slashes.";
             SendResponse(response);
             SendResponse(response);
             return AZStd::nullopt;
             return AZStd::nullopt;
         }
         }
@@ -66,8 +67,8 @@ namespace ROS2SimulationInterfaces
                 else
                 else
                 {
                 {
                     const auto& failedResult = outcome.GetError();
                     const auto& failedResult = outcome.GetError();
-                    response.result.result = aznumeric_cast<uint8_t>(failedResult.error_code);
-                    response.result.error_message = failedResult.error_string.c_str();
+                    response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
+                    response.result.error_message = failedResult.m_errorString.c_str();
                 }
                 }
                 SendResponse(response);
                 SendResponse(response);
             });
             });
@@ -82,7 +83,9 @@ namespace ROS2SimulationInterfaces
 
 
     bool SpawnEntityServiceHandler::ValidateFrameName(const AZStd::string& frameName)
     bool SpawnEntityServiceHandler::ValidateFrameName(const AZStd::string& frameName)
     {
     {
-        const AZStd::regex frameRegex{ R"(^[a-zA-Z0-9_/]+$)" }; // Entity names can only contain alphanumeric characters and underscores and forward slashes
+        const AZStd::regex frameRegex{
+            R"(^[a-zA-Z0-9_/]+$)"
+        }; // Entity names can only contain alphanumeric characters and underscores and forward slashes
         return AZStd::regex_match(frameName, frameRegex);
         return AZStd::regex_match(frameName, frameRegex);
     }
     }
 
 

+ 9 - 9
Gems/SimulationInterfaces/Code/Source/Utils/Utils.h

@@ -19,7 +19,7 @@ namespace ROS2SimulationInterfaces::Utils
     AZ::Outcome<SimulationInterfaces::EntityFilters, AZStd::string> GetEntityFiltersFromRequest(const RequestType& request)
     AZ::Outcome<SimulationInterfaces::EntityFilters, AZStd::string> GetEntityFiltersFromRequest(const RequestType& request)
     {
     {
         SimulationInterfaces::EntityFilters filter;
         SimulationInterfaces::EntityFilters filter;
-        filter.m_filter = request.filters.filter.c_str();
+        filter.m_nameFilter = request.filters.filter.c_str();
         uint8_t type = request.filters.bounds.type;
         uint8_t type = request.filters.bounds.type;
         if (type == simulation_interfaces::msg::Bounds::TYPE_BOX)
         if (type == simulation_interfaces::msg::Bounds::TYPE_BOX)
         {
         {
@@ -27,8 +27,8 @@ namespace ROS2SimulationInterfaces::Utils
             {
             {
                 return AZ::Failure("Invalid number of points! Type 'TYPE_BOX' should have exactly 2 points.");
                 return AZ::Failure("Invalid number of points! Type 'TYPE_BOX' should have exactly 2 points.");
             }
             }
-            const auto &p1 = request.filters.bounds.points.front();
-            const auto &p2 = request.filters.bounds.points.back();
+            const auto& p1 = request.filters.bounds.points.front();
+            const auto& p2 = request.filters.bounds.points.back();
             if (p1.x > p2.x || p1.y > p2.y || p1.z > p2.z)
             if (p1.x > p2.x || p1.y > p2.y || p1.z > p2.z)
             {
             {
                 return AZ::Failure("Invalid points! The first point should be lower than the second point.");
                 return AZ::Failure("Invalid points! The first point should be lower than the second point.");
@@ -36,7 +36,7 @@ namespace ROS2SimulationInterfaces::Utils
             const auto upperRight = ROS2::ROS2Conversions::FromROS2Vector3(p2);
             const auto upperRight = ROS2::ROS2Conversions::FromROS2Vector3(p2);
             const auto lowerLeft = ROS2::ROS2Conversions::FromROS2Vector3(p1);
             const auto lowerLeft = ROS2::ROS2Conversions::FromROS2Vector3(p1);
             const AZ::Aabb aabb = AZ::Aabb::CreateFromMinMax(lowerLeft, upperRight);
             const AZ::Aabb aabb = AZ::Aabb::CreateFromMinMax(lowerLeft, upperRight);
-            filter.m_bounds_shape = AZStd::make_shared<Physics::BoxShapeConfiguration>(aabb.GetExtents());
+            filter.m_boundsShape = AZStd::make_shared<Physics::BoxShapeConfiguration>(aabb.GetExtents());
         }
         }
         else if (type == simulation_interfaces::msg::Bounds::TYPE_CONVEX_HULL) // TYPE_CONVEX_HULL
         else if (type == simulation_interfaces::msg::Bounds::TYPE_CONVEX_HULL) // TYPE_CONVEX_HULL
         {
         {
@@ -44,7 +44,7 @@ namespace ROS2SimulationInterfaces::Utils
             {
             {
                 return AZ::Failure("Invalid number of points! Type 'TYPE_CONVEX_HULL' should have at least 3 points.");
                 return AZ::Failure("Invalid number of points! Type 'TYPE_CONVEX_HULL' should have at least 3 points.");
             }
             }
-            filter.m_bounds_shape = AZStd::make_shared<Physics::ConvexHullShapeConfiguration>();
+            filter.m_boundsShape = AZStd::make_shared<Physics::ConvexHullShapeConfiguration>();
         }
         }
         else if (type == simulation_interfaces::msg::Bounds::TYPE_SPHERE) // TYPE_SPHERE
         else if (type == simulation_interfaces::msg::Bounds::TYPE_SPHERE) // TYPE_SPHERE
         {
         {
@@ -52,10 +52,10 @@ namespace ROS2SimulationInterfaces::Utils
             {
             {
                 return AZ::Failure("Invalid number of points! Type 'TYPE_SPHERE' should have exactly 2 points.");
                 return AZ::Failure("Invalid number of points! Type 'TYPE_SPHERE' should have exactly 2 points.");
             }
             }
-            filter.m_bounds_shape = AZStd::make_shared<Physics::SphereShapeConfiguration>(request.filters.bounds.points.back().x);
-            filter.m_bounds_pose = { ROS2::ROS2Conversions::FromROS2Vector3(request.filters.bounds.points.front()),
-                                     AZ::Quaternion::CreateIdentity(),
-                                     1.0f };
+            filter.m_boundsShape = AZStd::make_shared<Physics::SphereShapeConfiguration>(request.filters.bounds.points.back().x);
+            filter.m_boundsPose = { ROS2::ROS2Conversions::FromROS2Vector3(request.filters.bounds.points.front()),
+                                    AZ::Quaternion::CreateIdentity(),
+                                    1.0f };
         }
         }
         return AZ::Success(AZStd::move(filter));
         return AZ::Success(AZStd::move(filter));
     }
     }

+ 30 - 26
Gems/SimulationInterfaces/Code/Tests/Tools/InterfacesTest.cpp

@@ -34,12 +34,12 @@
 #include <rclcpp/publisher.hpp>
 #include <rclcpp/publisher.hpp>
 #include <rclcpp/rclcpp.hpp>
 #include <rclcpp/rclcpp.hpp>
 #include <rclcpp_action/create_client.hpp>
 #include <rclcpp_action/create_client.hpp>
+#include <simulation_interfaces/action/simulate_steps.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 #include <simulation_interfaces/msg/simulator_features.hpp>
 #include <std_msgs/msg/string.hpp>
 #include <std_msgs/msg/string.hpp>
 #include <string>
 #include <string>
 #include <string_view>
 #include <string_view>
 #include <vector>
 #include <vector>
-#include <simulation_interfaces/action/simulate_steps.hpp>
 
 
 namespace UnitTest
 namespace UnitTest
 {
 {
@@ -146,7 +146,6 @@ namespace UnitTest
         EXPECT_NE(services.find("/spawn_entity"), services.end());
         EXPECT_NE(services.find("/spawn_entity"), services.end());
         EXPECT_NE(services.find("/get_simulation_features"), services.end());
         EXPECT_NE(services.find("/get_simulation_features"), services.end());
         EXPECT_NE(services.find("/step_simulation"), services.end());
         EXPECT_NE(services.find("/step_simulation"), services.end());
-
     }
     }
 
 
     //! Test if the service call succeeds when the entity is found
     //! Test if the service call succeeds when the entity is found
@@ -195,8 +194,8 @@ namespace UnitTest
                 {
                 {
                     EXPECT_EQ(name, "test_entity");
                     EXPECT_EQ(name, "test_entity");
                     FailedResult failedResult;
                     FailedResult failedResult;
-                    failedResult.error_code = simulation_interfaces::msg::Result::RESULT_NOT_FOUND,
-                    failedResult.error_string = "FooBar not found.";
+                    failedResult.m_errorCode = simulation_interfaces::msg::Result::RESULT_NOT_FOUND,
+                    failedResult.m_errorString = "FooBar not found.";
                     completedCb(AZ::Failure(failedResult));
                     completedCb(AZ::Failure(failedResult));
                 }));
                 }));
 
 
@@ -230,21 +229,21 @@ namespace UnitTest
             .WillOnce(::testing::Invoke(
             .WillOnce(::testing::Invoke(
                 [=](const EntityFilters& filter)
                 [=](const EntityFilters& filter)
                 {
                 {
-                    EXPECT_NE(filter.m_bounds_shape, nullptr);
-                    if (filter.m_bounds_shape)
+                    EXPECT_NE(filter.m_boundsShape, nullptr);
+                    if (filter.m_boundsShape)
                     {
                     {
-                        EXPECT_EQ(filter.m_bounds_shape->GetShapeType(), Physics::ShapeType::Sphere);
+                        EXPECT_EQ(filter.m_boundsShape->GetShapeType(), Physics::ShapeType::Sphere);
                         Physics::SphereShapeConfiguration* sphereShape =
                         Physics::SphereShapeConfiguration* sphereShape =
-                            azdynamic_cast<Physics::SphereShapeConfiguration*>(filter.m_bounds_shape.get());
+                            azdynamic_cast<Physics::SphereShapeConfiguration*>(filter.m_boundsShape.get());
                         EXPECT_EQ(sphereShape->m_radius, 99.0f);
                         EXPECT_EQ(sphereShape->m_radius, 99.0f);
                         EXPECT_EQ(sphereShape->m_scale, AZ::Vector3(1.0f));
                         EXPECT_EQ(sphereShape->m_scale, AZ::Vector3(1.0f));
                     }
                     }
-                    auto loc = filter.m_bounds_pose.GetTranslation();
+                    auto loc = filter.m_boundsPose.GetTranslation();
                     EXPECT_EQ(loc.GetX(), point1.GetX());
                     EXPECT_EQ(loc.GetX(), point1.GetX());
                     EXPECT_EQ(loc.GetY(), point1.GetY());
                     EXPECT_EQ(loc.GetY(), point1.GetY());
                     EXPECT_EQ(loc.GetZ(), point1.GetZ());
                     EXPECT_EQ(loc.GetZ(), point1.GetZ());
 
 
-                    EXPECT_EQ(filter.m_filter, "FooBarFilter");
+                    EXPECT_EQ(filter.m_nameFilter, "FooBarFilter");
                     return AZ::Success(EntityNameList{ "FooBar" });
                     return AZ::Success(EntityNameList{ "FooBar" });
                 }));
                 }));
 
 
@@ -300,17 +299,17 @@ namespace UnitTest
             .WillOnce(::testing::Invoke(
             .WillOnce(::testing::Invoke(
                 [=](const EntityFilters& filter)
                 [=](const EntityFilters& filter)
                 {
                 {
-                    EXPECT_NE(filter.m_bounds_shape, nullptr);
-                    if (filter.m_bounds_shape)
+                    EXPECT_NE(filter.m_boundsShape, nullptr);
+                    if (filter.m_boundsShape)
                     {
                     {
-                        EXPECT_EQ(filter.m_bounds_shape->GetShapeType(), Physics::ShapeType::Box);
+                        EXPECT_EQ(filter.m_boundsShape->GetShapeType(), Physics::ShapeType::Box);
                         Physics::BoxShapeConfiguration* boxShape =
                         Physics::BoxShapeConfiguration* boxShape =
-                            azdynamic_cast<Physics::BoxShapeConfiguration*>(filter.m_bounds_shape.get());
+                            azdynamic_cast<Physics::BoxShapeConfiguration*>(filter.m_boundsShape.get());
                         EXPECT_EQ(boxShape->m_dimensions.GetX(), dims.GetX());
                         EXPECT_EQ(boxShape->m_dimensions.GetX(), dims.GetX());
                         EXPECT_EQ(boxShape->m_dimensions.GetY(), dims.GetY());
                         EXPECT_EQ(boxShape->m_dimensions.GetY(), dims.GetY());
                         EXPECT_EQ(boxShape->m_dimensions.GetZ(), dims.GetZ());
                         EXPECT_EQ(boxShape->m_dimensions.GetZ(), dims.GetZ());
                     }
                     }
-                    auto loc = filter.m_bounds_pose.GetTranslation();
+                    auto loc = filter.m_boundsPose.GetTranslation();
                     EXPECT_EQ(loc, AZ::Vector3::CreateZero());
                     EXPECT_EQ(loc, AZ::Vector3::CreateZero());
                     return AZ::Success(EntityNameList{ "FooBar" });
                     return AZ::Success(EntityNameList{ "FooBar" });
                 }));
                 }));
@@ -374,10 +373,10 @@ namespace UnitTest
         SimulationFeaturesAggregatorRequestsMockedHandler mockAggregator;
         SimulationFeaturesAggregatorRequestsMockedHandler mockAggregator;
         using ::testing::_;
         using ::testing::_;
         auto node = GetRos2Node();
         auto node = GetRos2Node();
-        AZStd::unordered_set<SimulationFeatures> features{
+        AZStd::unordered_set<SimulationFeatureType> features{
             simulation_interfaces::msg::SimulatorFeatures::SPAWNING,
             simulation_interfaces::msg::SimulatorFeatures::SPAWNING,
-            static_cast<SimulationFeatures>(0xFE), // invalid feature, should be ignored
-            static_cast<SimulationFeatures>(0xFF), // invalid feature, should be ignored
+            static_cast<SimulationFeatureType>(0xFE), // invalid feature, should be ignored
+            static_cast<SimulationFeatureType>(0xFF), // invalid feature, should be ignored
         };
         };
         EXPECT_CALL(mockAggregator, GetSimulationFeatures())
         EXPECT_CALL(mockAggregator, GetSimulationFeatures())
             .WillOnce(::testing::Invoke(
             .WillOnce(::testing::Invoke(
@@ -412,17 +411,21 @@ namespace UnitTest
         request->allow_renaming = true;
         request->allow_renaming = true;
 
 
         auto future = client->async_send_request(request);
         auto future = client->async_send_request(request);
-        EXPECT_CALL(mock, SpawnEntity(_, _, _, _, _, _)).WillOnce(
-                ::testing::Invoke(
-                [](const AZStd::string& name, const AZStd::string& uri, const AZStd::string& entityNamespace, const AZ::Transform& initialPose, const bool allowRename, SpawnCompletedCb completedCb)
+        EXPECT_CALL(mock, SpawnEntity(_, _, _, _, _, _))
+            .WillOnce(::testing::Invoke(
+                [](const AZStd::string& name,
+                   const AZStd::string& uri,
+                   const AZStd::string& entityNamespace,
+                   const AZ::Transform& initialPose,
+                   const bool allowRename,
+                   SpawnCompletedCb completedCb)
                 {
                 {
                     EXPECT_EQ(name, "valid_name");
                     EXPECT_EQ(name, "valid_name");
                     EXPECT_EQ(uri, "test_uri");
                     EXPECT_EQ(uri, "test_uri");
                     EXPECT_EQ(entityNamespace, "test_namespace");
                     EXPECT_EQ(entityNamespace, "test_namespace");
                     EXPECT_TRUE(allowRename);
                     EXPECT_TRUE(allowRename);
                     completedCb(AZ::Success("valid_name"));
                     completedCb(AZ::Success("valid_name"));
-                })
-            );
+                }));
         SpinAppSome();
         SpinAppSome();
 
 
         ASSERT_TRUE(future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) << "Service call timed out.";
         ASSERT_TRUE(future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) << "Service call timed out.";
@@ -448,8 +451,8 @@ namespace UnitTest
 
 
         ASSERT_TRUE(future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) << "Service call timed out.";
         ASSERT_TRUE(future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) << "Service call timed out.";
         auto response = future.get();
         auto response = future.get();
-        EXPECT_EQ(response->result.result, simulation_interfaces::srv::SpawnEntity::Response::NAME_INVALID) << "Service call should fail with invalid name.";
-
+        EXPECT_EQ(response->result.result, simulation_interfaces::srv::SpawnEntity::Response::NAME_INVALID)
+            << "Service call should fail with invalid name.";
     }
     }
 
 
     //! Check if service fails when the namespace is invalid
     //! Check if service fails when the namespace is invalid
@@ -470,7 +473,8 @@ namespace UnitTest
 
 
         ASSERT_TRUE(future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) << "Service call timed out.";
         ASSERT_TRUE(future.wait_for(std::chrono::seconds(0)) == std::future_status::ready) << "Service call timed out.";
         auto response = future.get();
         auto response = future.get();
-        EXPECT_EQ(response->result.result, simulation_interfaces::srv::SpawnEntity::Response::NAMESPACE_INVALID) << "Service call should fail with invalid name.";
+        EXPECT_EQ(response->result.result, simulation_interfaces::srv::SpawnEntity::Response::NAMESPACE_INVALID)
+            << "Service call should fail with invalid name.";
     }
     }
 
 
     TEST_F(SimulationInterfaceROS2TestFixture, SimulationStepsSuccess)
     TEST_F(SimulationInterfaceROS2TestFixture, SimulationStepsSuccess)

+ 3 - 3
Gems/SimulationInterfaces/Code/Tests/Tools/Mocks/SimulationFeaturesAggregatorRequestsHandlerMock.h

@@ -17,8 +17,8 @@ namespace UnitTest
             SimulationInterfaces::SimulationFeaturesAggregatorRequestBus::Handler::BusDisconnect();
             SimulationInterfaces::SimulationFeaturesAggregatorRequestBus::Handler::BusDisconnect();
         }
         }
 
 
-        MOCK_METHOD(void, AddSimulationFeatures, (const AZStd::unordered_set<SimulationFeatures>& features), (override));
-        MOCK_METHOD(const AZStd::unordered_set<SimulationFeatures>, GetSimulationFeatures, (), (const, override));
-        MOCK_METHOD(bool, HasFeature, (SimulationFeatures feature), (const, override));
+        MOCK_METHOD(void, AddSimulationFeatures, (const AZStd::unordered_set<SimulationFeatureType>& features), (override));
+        MOCK_METHOD(AZStd::unordered_set<SimulationFeatureType>, GetSimulationFeatures, (), (override));
+        MOCK_METHOD(bool, HasFeature, (SimulationFeatureType feature), (override));
     };
     };
 } // namespace UnitTest
 } // namespace UnitTest

+ 5 - 6
Gems/SimulationInterfaces/Code/Tests/Tools/SimulationInterfaceTests.cpp

@@ -79,7 +79,7 @@ namespace UnitTest
             CreateEntityWithStaticBodyComponent("Outside", AZ::Transform::CreateTranslation(AZ::Vector3(10.0f, 0.0f, 0.0f)));
             CreateEntityWithStaticBodyComponent("Outside", AZ::Transform::CreateTranslation(AZ::Vector3(10.0f, 0.0f, 0.0f)));
 
 
         EntityFilters filter;
         EntityFilters filter;
-        filter.m_bounds_shape = AZStd::make_shared<Physics::SphereShapeConfiguration>(2.0f);
+        filter.m_boundsShape = AZStd::make_shared<Physics::SphereShapeConfiguration>(2.0f);
 
 
         AZ::Outcome<EntityNameList, FailedResult> entities;
         AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
@@ -103,7 +103,7 @@ namespace UnitTest
             CreateEntityWithStaticBodyComponent("WontMatch", AZ::Transform::CreateTranslation(AZ::Vector3(10.0f, 0.0f, 0.0f)));
             CreateEntityWithStaticBodyComponent("WontMatch", AZ::Transform::CreateTranslation(AZ::Vector3(10.0f, 0.0f, 0.0f)));
 
 
         EntityFilters filter;
         EntityFilters filter;
-        filter.m_filter = "Will.*";
+        filter.m_nameFilter = "Will.*";
 
 
         AZ::Outcome<EntityNameList, FailedResult> entities;
         AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
@@ -126,7 +126,7 @@ namespace UnitTest
             CreateEntityWithStaticBodyComponent("WontMatch", AZ::Transform::CreateTranslation(AZ::Vector3(10.0f, 0.0f, 0.0f)));
             CreateEntityWithStaticBodyComponent("WontMatch", AZ::Transform::CreateTranslation(AZ::Vector3(10.0f, 0.0f, 0.0f)));
 
 
         EntityFilters filter;
         EntityFilters filter;
-        filter.m_filter = "[a-z";
+        filter.m_nameFilter = "[a-z";
 
 
         AZ::Outcome<EntityNameList, FailedResult> entities;
         AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
@@ -168,7 +168,7 @@ namespace UnitTest
         EXPECT_GT(deltaPos.GetLength(), 0.0f);
         EXPECT_GT(deltaPos.GetLength(), 0.0f);
 
 
         // check if entity has velocity
         // check if entity has velocity
-        EXPECT_GT(stateAfter.m_twist_linear.GetLength(), 0.0f);
+        EXPECT_GT(stateAfter.m_twistLinear.GetLength(), 0.0f);
 
 
         DeleteEntity(entityId1);
         DeleteEntity(entityId1);
     }
     }
@@ -182,8 +182,7 @@ namespace UnitTest
             deletionWasCompleted = true;
             deletionWasCompleted = true;
             EXPECT_TRUE(result.IsSuccess());
             EXPECT_TRUE(result.IsSuccess());
         };
         };
-        SimulationEntityManagerRequestBus::Broadcast(
-            &SimulationEntityManagerRequestBus::Events::DeleteAllEntities, deleteAllCompletion);
+        SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteAllEntities, deleteAllCompletion);
 
 
         TickApp(100);
         TickApp(100);
         EXPECT_TRUE(deletionWasCompleted);
         EXPECT_TRUE(deletionWasCompleted);

+ 20 - 8
Gems/SimulationInterfaces/Code/Tests/Tools/SimulationIterfaceAppTest.cpp

@@ -78,7 +78,13 @@ namespace UnitTest
 
 
         constexpr bool allowRename = false;
         constexpr bool allowRename = false;
         SimulationEntityManagerRequestBus::Broadcast(
         SimulationEntityManagerRequestBus::Broadcast(
-            &SimulationEntityManagerRequestBus::Events::SpawnEntity, entityName, uri, entityNamespace, initialPose, allowRename, completedCb);
+            &SimulationEntityManagerRequestBus::Events::SpawnEntity,
+            entityName,
+            uri,
+            entityNamespace,
+            initialPose,
+            allowRename,
+            completedCb);
 
 
         // entities are spawned asynchronously, so we need to tick the app to let the entity be spawned
         // entities are spawned asynchronously, so we need to tick the app to let the entity be spawned
         TickApp(100);
         TickApp(100);
@@ -92,7 +98,13 @@ namespace UnitTest
             completed2 = true;
             completed2 = true;
         };
         };
         SimulationEntityManagerRequestBus::Broadcast(
         SimulationEntityManagerRequestBus::Broadcast(
-            &SimulationEntityManagerRequestBus::Events::SpawnEntity, entityName, uri, entityNamespace, initialPose, allowRename, failedSpawnCompletedCb);
+            &SimulationEntityManagerRequestBus::Events::SpawnEntity,
+            entityName,
+            uri,
+            entityNamespace,
+            initialPose,
+            allowRename,
+            failedSpawnCompletedCb);
         EXPECT_TRUE(completed2);
         EXPECT_TRUE(completed2);
 
 
         // list simulation entities
         // list simulation entities
@@ -136,8 +148,8 @@ namespace UnitTest
 
 
         // Check if entity was teleported by setting the new state, we use a filter to check if the entity is at the new position
         // Check if entity was teleported by setting the new state, we use a filter to check if the entity is at the new position
         EntityFilters filter;
         EntityFilters filter;
-        filter.m_bounds_shape = AZStd::make_shared<Physics::SphereShapeConfiguration>(2.0f);
-        filter.m_bounds_pose = AZ::Transform::CreateTranslation(AZ::Vector3(1000.0f, 0.0f, 0.0f));
+        filter.m_boundsShape = AZStd::make_shared<Physics::SphereShapeConfiguration>(2.0f);
+        filter.m_boundsPose = AZ::Transform::CreateTranslation(AZ::Vector3(1000.0f, 0.0f, 0.0f));
         AZ::Outcome<EntityNameList, FailedResult> entitiesFiltered;
         AZ::Outcome<EntityNameList, FailedResult> entitiesFiltered;
         SimulationEntityManagerRequestBus::BroadcastResult(
         SimulationEntityManagerRequestBus::BroadcastResult(
             entitiesFiltered, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
             entitiesFiltered, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
@@ -157,7 +169,9 @@ namespace UnitTest
         EXPECT_EQ(getNumberOfEntities(), 0);
         EXPECT_EQ(getNumberOfEntities(), 0);
 
 
         // spawn 3 entities of entities and despawn all of them
         // spawn 3 entities of entities and despawn all of them
-        SpawnCompletedCb cb = [&](const AZ::Outcome<AZStd::string, FailedResult>& result){};
+        SpawnCompletedCb cb = [&](const AZ::Outcome<AZStd::string, FailedResult>& result)
+        {
+        };
         SimulationEntityManagerRequestBus::Broadcast(
         SimulationEntityManagerRequestBus::Broadcast(
             &SimulationEntityManagerRequestBus::Events::SpawnEntity, "entity1", uri, entityNamespace, initialPose, false, cb);
             &SimulationEntityManagerRequestBus::Events::SpawnEntity, "entity1", uri, entityNamespace, initialPose, false, cb);
         SimulationEntityManagerRequestBus::Broadcast(
         SimulationEntityManagerRequestBus::Broadcast(
@@ -174,13 +188,11 @@ namespace UnitTest
             deletionWasCompleted = true;
             deletionWasCompleted = true;
             EXPECT_TRUE(result.IsSuccess());
             EXPECT_TRUE(result.IsSuccess());
         };
         };
-        SimulationEntityManagerRequestBus::Broadcast(
-            &SimulationEntityManagerRequestBus::Events::DeleteAllEntities, deleteAllCompletion);
+        SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteAllEntities, deleteAllCompletion);
 
 
         TickApp(100);
         TickApp(100);
         EXPECT_TRUE(deletionWasCompleted);
         EXPECT_TRUE(deletionWasCompleted);
         EXPECT_EQ(getNumberOfEntities(), 0);
         EXPECT_EQ(getNumberOfEntities(), 0);
-
     }
     }
 
 
 } // namespace UnitTest
 } // namespace UnitTest