Explorar el Código

[SimulationIterfaces] Refactor API to use heavily AZ::Outcome and error codes from standard (#850)

* Refactor API to use heavily AZ::Outcome and error codes from standard
* asynhronous despawning
* Adjust to review

--

Signed-off-by: Michał Pełka <[email protected]>
Michał Pełka hace 4 meses
padre
commit
bf040761d0

+ 36 - 0
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/Result.h

@@ -0,0 +1,36 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+
+#pragma once
+#include <AzCore/Outcome/Outcome.h>
+#include <AzCore/std/string/string.h>
+namespace SimulationInterfaces
+{
+    //! 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>
+    enum class ErrorCode
+    {
+        RESULT_FEATURE_UNSUPPORTED = 0,
+        RESULT_NOT_FOUND = 2,
+        RESULT_INCORRECT_STATE = 3,
+        RESULT_OPERATION_FAILED = 4
+    };
+
+    //! A message type to represent the result of a failed operation
+    struct FailedResult
+    {
+        FailedResult() = default;
+        FailedResult(ErrorCode error_code, const AZStd::string& error_string)
+            : error_code(error_code)
+            , error_string(error_string)
+        {
+        }
+        ErrorCode error_code;
+        AZStd::string error_string;
+    };
+} // namespace SimulationInterfaces

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

@@ -10,6 +10,8 @@
 
 #include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
 
+#include "Result.h"
+#include "TagFilter.h"
 #include <AzCore/EBus/EBus.h>
 #include <AzCore/Interface/Interface.h>
 #include <AzCore/std/smart_ptr/shared_ptr.h>
@@ -18,11 +20,11 @@
 namespace SimulationInterfaces
 {
     //! # A set of filters to apply to entity queries. See GetEntities, GetEntitiesStates.
-    //! # The filters are combined with a logical AND.
     //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/msg/EntityFilters.msg">EntityFilters.msg</a>
     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
         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() };
@@ -43,6 +45,11 @@ namespace SimulationInterfaces
         AZStd::string m_bounds_sphere;
     };
 
+    using EntityNameList = AZStd::vector<AZStd::string>;
+    using MultipleEntitiesStates = AZStd::unordered_map<AZStd::string, EntityState>;
+    using SpawnableList = AZStd::vector<Spawnable>;
+    using DeletionCompletedCb = AZStd::function<void(const AZ::Outcome<void, FailedResult>&)>;
+    using SpawnCompletedCb = AZStd::function<void(const AZ::Outcome<AZStd::string, FailedResult>&)>;
     class SimulationEntityManagerRequests
     {
     public:
@@ -54,29 +61,31 @@ namespace SimulationInterfaces
         //! - name : a posix regular expression to match against entity names
         //! - bounds : a shape to use for filtering entities, null means no bounds filtering
         //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/GetEntities.srv">GetEntities.srv</a>
-        virtual AZStd::vector<AZStd::string> GetEntities(const EntityFilters& filter) = 0;
+        virtual AZ::Outcome<EntityNameList, FailedResult> GetEntities(const EntityFilters& filter) = 0;
 
         //! Get the state of an entity.
         //!  @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/GetEntityState.srv">GetEntityState.srv</a>
-        virtual EntityState GetEntityState(const AZStd::string& name) = 0;
+        virtual AZ::Outcome<EntityState, FailedResult> GetEntityState(const AZStd::string& name) = 0;
 
         //! Get the state of all entities that match the filter.
-        //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/GetEntitiesStates.srv">GetEntitiesStates.srv</a>
-        virtual AZStd::unordered_map<AZStd::string, EntityState> GetEntitiesStates(const EntityFilters& filter) = 0;
+        //! @see <a
+        //! href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/GetEntitiesStates.srv">GetEntitiesStates.srv</a>
+        virtual AZ::Outcome<MultipleEntitiesStates, FailedResult> GetEntitiesStates(const EntityFilters& filter) = 0;
 
         //! Set the state of an entity.
         //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/SetEntityState.srv">SetEntityState.srv</a>
-        virtual bool SetEntityState(const AZStd::string& name, const EntityState& state) = 0;
+        virtual AZ::Outcome<void, FailedResult> SetEntityState(const AZStd::string& name, const EntityState& state) = 0;
 
         //! Remove previously spawned entity from the simulation.
         //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/DeleteEntity.srv">DeleteEntity.srv</a>
-        virtual bool DeleteEntity(const AZStd::string& name) = 0;
+        virtual void DeleteEntity(const AZStd::string& name, DeletionCompletedCb completedCb) = 0;
 
-        virtual AZStd::vector<Spawnable> GetSpawnables() = 0;
+        //! Get a list of spawnable entities.
+        //! @see <a href="https://github.com/ros-simulation/simulation_interfaces/blob/main/srv/GetSpawnables.srv">GetSpawnables.srv</a>
+        virtual AZ::Outcome<SpawnableList, FailedResult> GetSpawnables() = 0;
 
         //! Callback for when an entity has been spawned and registered. The string is the name of the entity in the simulation interface.
         //! Note : The names is empty, if the entity could not be registered (e.g. prefab has no simulated entities)
-        using SpawnCompletedCb = AZStd::function<void(const AZ::Outcome<AZStd::string, AZStd::string>&)>;
 
         virtual void SpawnEntity(
             const AZStd::string& name,

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

@@ -24,9 +24,13 @@ namespace SimulationInterfaces
         AZ_RTTI(SimulationManagerRequests, SimulationManagerRequestsTypeId);
         virtual ~SimulationManagerRequests() = default;
 
+        //! Set the simulation to paused or unpaused,
+        //! expect always to succeed
         virtual void SetSimulationPaused(bool paused) = 0;
-        virtual void StepSimulation(AZ::u32 steps) = 0;
 
+        //! Step the simulation by a number of steps
+        //! expect always to succeed
+        virtual void StepSimulation(AZ::u32 steps) = 0;
     };
 
     class SimulationMangerRequestBusTraits : public AZ::EBusTraits

+ 30 - 0
Gems/SimulationInterfaces/Code/Include/SimulationInterfaces/TagFilter.h

@@ -0,0 +1,30 @@
+/*
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
+
+#pragma once
+
+#include <AzCore/std/containers/unordered_set.h>
+#include <AzCore/std/string/string.h>
+
+namespace SimulationInterfaces
+{
+    //! 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>
+
+    struct TagFilter
+    {
+        enum class TagFilterMode
+        {
+            FILTER_MODE_ANY,
+            FILTER_MODE_ALL
+        };
+        AZStd::unordered_set<AZStd::string> m_tags;
+        TagFilterMode m_mode;
+    };
+
+} // namespace SimulationInterfaces

+ 61 - 41
Gems/SimulationInterfaces/Code/Source/Clients/ConsoleCommands.inl

@@ -19,10 +19,15 @@ namespace SimulationInterfacesCommands
     using namespace SimulationInterfaces;
     static void simulationinterfaces_GetEntities(const AZ::ConsoleCommandContainer& arguments)
     {
-        AZStd::vector<AZStd::string> entities;
+        AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        AZ_Printf("SimulationInterfacesConsole", "Number of simulation entities: %d\n", entities.size());
-        for (const auto& entity : entities)
+        if (!entities.IsSuccess())
+        {
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get entities: %s\n", entities.GetError().error_string.c_str());
+            return;
+        }
+
+        for (const auto& entity : entities.GetValue())
         {
             AZ_Printf("SimulationInterfacesConsole", "      - %s\n", entity.c_str());
         }
@@ -38,7 +43,6 @@ namespace SimulationInterfacesCommands
         SimulationManagerRequestBus::Broadcast(&SimulationManagerRequestBus::Events::SetSimulationPaused, false);
     }
 
-
     static void simulationinterfaces_Step(const AZ::ConsoleCommandContainer& arguments)
     {
         if (arguments.empty())
@@ -51,8 +55,6 @@ namespace SimulationInterfacesCommands
         SimulationManagerRequestBus::Broadcast(&SimulationManagerRequestBus::Events::StepSimulation, steps);
     }
 
-
-
     static void simulationinterfaces_GetEntitiesSphere(const AZ::ConsoleCommandContainer& arguments)
     {
         float sphereShape = 10.f;
@@ -67,10 +69,15 @@ namespace SimulationInterfacesCommands
         EntityFilters filter;
         filter.m_bounds_shape = AZStd::make_shared<Physics::SphereShapeConfiguration>(sphereShape);
 
-        AZStd::vector<AZStd::string> entities;
+        AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
-        AZ_Printf("SimulationInterfacesConsole", "Number of simulation entities: %d\n", entities.size());
-        for (const auto& entity : entities)
+        if (!entities.IsSuccess())
+        {
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get entities: %s\n", entities.GetError().error_string.c_str());
+            return;
+        }
+
+        for (const auto& entity : entities.GetValue())
         {
             AZ_Printf("SimulationInterfacesConsole", "      - %s\n", entity.c_str());
         }
@@ -85,8 +92,14 @@ namespace SimulationInterfacesCommands
         }
         const AZStd::string entityName = arguments[0];
         AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_GetEntityState %s\n", entityName.c_str());
-        EntityState entityState;
-        SimulationEntityManagerRequestBus::BroadcastResult(entityState, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        AZ::Outcome<EntityState, FailedResult> entityStateResult;
+        SimulationEntityManagerRequestBus::BroadcastResult(entityStateResult, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        if (!entityStateResult.IsSuccess())
+        {
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get entity state: %s\n", entityStateResult.GetError().error_string.c_str());
+            return;
+        }
+        const auto &entityState = entityStateResult.GetValue();
         AZ_Printf("SimulationInterfacesConsole", "Entity %s\n", entityName.c_str());
         AZ_Printf(
             "SimulationInterfacesConsole",
@@ -124,17 +137,17 @@ namespace SimulationInterfacesCommands
         EntityState entityState{};
         entityState.m_pose = AZ::Transform::CreateIdentity();
         entityState.m_pose.SetTranslation(position);
-        bool isOk = false;
+        AZ::Outcome<void, FailedResult> result;
         SimulationEntityManagerRequestBus::BroadcastResult(
-            isOk, &SimulationEntityManagerRequestBus::Events::SetEntityState, entityName, entityState);
-        if (isOk)
-        {
-            AZ_Printf("SimulationInterfacesConsole", "Entity %s state set\n", entityName.c_str());
-        }
-        else
+            result, &SimulationEntityManagerRequestBus::Events::SetEntityState, entityName, entityState);
+
+        if (!result.IsSuccess())
         {
-            AZ_Printf("SimulationInterfacesConsole", "Entity %s state NOT set\n", entityName.c_str());
+            AZ_Printf("SimulationInterfacesConsole", "Failed to set entity state: %s\n", result.GetError().error_string.c_str());
+            return;
         }
+        AZ_Printf("SimulationInterfacesConsole", "Entity %s state set\n", entityName.c_str());
+
     }
 
     static void simulationinterfaces_DeleteEntity(const AZ::ConsoleCommandContainer& arguments)
@@ -145,26 +158,32 @@ namespace SimulationInterfacesCommands
             return;
         }
         const AZStd::string entityName = arguments[0];
-        AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_DeleteEntity %s\n", entityName.c_str());
-        bool isOk = false;
-        SimulationEntityManagerRequestBus::BroadcastResult(isOk, &SimulationEntityManagerRequestBus::Events::DeleteEntity, entityName);
-        if (isOk)
-        {
-            AZ_Printf("SimulationInterfacesConsole", "Entity %s deleted\n", entityName.c_str());
-        }
-        else
+        DeletionCompletedCb cb = [](const AZ::Outcome<void, FailedResult>& result)
         {
-            AZ_Printf("SimulationInterfacesConsole", "Entity %s NOT deleted\n", entityName.c_str());
-        }
+            if (result.IsSuccess())
+            {
+                AZ_Printf("SimulationInterfacesConsole", "Entity deleted\n");
+            }
+            else
+            {
+                AZ_Printf("SimulationInterfacesConsole", "Failed to delete entity: %s\n", result.GetError().error_string.c_str());
+            }
+        };
+        SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteEntity, entityName, cb);
+
     }
 
     static void simulationinterfaces_GetSpawnables(const AZ::ConsoleCommandContainer& arguments)
     {
         AZ_Printf("SimulationInterfacesConsole", "simulationinterfaces_GetSpawnables\n");
-        AZStd::vector<Spawnable> spawnables;
+        AZ::Outcome<SpawnableList, FailedResult> spawnables;
         SimulationEntityManagerRequestBus::BroadcastResult(spawnables, &SimulationEntityManagerRequestBus::Events::GetSpawnables);
-        AZ_Printf("SimulationInterfacesConsole", "Number of spawnables: %d\n", spawnables.size());
-        for (const auto& spawnable : spawnables)
+        if (!spawnables.IsSuccess())
+        {
+            AZ_Printf("SimulationInterfacesConsole", "Failed to get spawnables: %s\n", spawnables.GetError().error_string.c_str());
+            return;
+        }
+        for (const auto& spawnable : spawnables.GetValue())
         {
             AZ_Printf("SimulationInterfaces", "      - %s\n", spawnable.m_uri.c_str());
         }
@@ -192,27 +211,28 @@ namespace SimulationInterfacesCommands
                     AZStd::stof(AZStd::string(arguments[4])),
                     AZStd::stof(AZStd::string(arguments[5]))));
         }
-        SimulationEntityManagerRequests::SpawnCompletedCb completedCb = [](const AZ::Outcome<AZStd::string, AZStd::string>& name)
+        SpawnCompletedCb completedCb = [](const AZ::Outcome<AZStd::string, FailedResult>& result)
         {
-            if (name.IsSuccess())
+            if (!result.IsSuccess())
             {
-                AZ_Printf("SimulationInterfacesConsole", "Entity %s spawned and registered\n", name.GetValue().c_str());
-            }
-            else
-            {
-                AZ_Printf("SimulationInterfacesConsole", "Entity NOT spawned. Error : %s\n", name.GetError().c_str());
+                AZ_Printf("SimulationInterfacesConsole", "Failed to spawn entity: %s\n", result.GetError().error_string.c_str());
+                return;
             }
+            AZ_Printf("SimulationInterfacesConsole", "Entity spawned and registered : %s\n", result.GetValue().c_str());
+
         };
         SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::SpawnEntity, name, uri, entityNamespace, initialPose, completedCb);
         AZ_Printf("SimulationInterfacesConsole", "simulationinterface_Spawn %s %s\n", name.c_str(), uri.c_str());
     }
 
+    AZ_CONSOLEFREEFUNC(
+        simulationinterfaces_GetEntities, AZ::ConsoleFunctorFlags::DontReplicate, "Get all simulated entities in the scene.");
+
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Pause, AZ::ConsoleFunctorFlags::DontReplicate, "Pause simulation.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Resume, AZ::ConsoleFunctorFlags::DontReplicate, "Resume simulation.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_Step, AZ::ConsoleFunctorFlags::DontReplicate, "Step simulation.");
 
-    AZ_CONSOLEFREEFUNC(
-        simulationinterfaces_GetEntities, AZ::ConsoleFunctorFlags::DontReplicate, "Get all simulated entities in the scene.");
+
     AZ_CONSOLEFREEFUNC(
         simulationinterfaces_GetEntitiesSphere, AZ::ConsoleFunctorFlags::DontReplicate, "Get all simulated entities in the radius.");
     AZ_CONSOLEFREEFUNC(simulationinterfaces_GetEntityState, AZ::ConsoleFunctorFlags::DontReplicate, "Get state of the entity.");

+ 134 - 88
Gems/SimulationInterfaces/Code/Source/Clients/SimulationEntitiesManager.cpp

@@ -254,8 +254,14 @@ namespace SimulationInterfaces
         }
     }
 
-    AZStd::vector<AZStd::string> SimulationEntitiesManager::GetEntities(const EntityFilters& filter)
+    AZ::Outcome<EntityNameList, FailedResult> SimulationEntitiesManager::GetEntities(const EntityFilters& filter)
     {
+        if (!filter.m_tags_filter.m_tags.empty())
+        {
+            AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
+            return AZ::Failure(FailedResult(ErrorCode::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
+        }
+
         const bool reFilter = !filter.m_filter.empty();
         const bool shapeCastFilter = filter.m_bounds_shape != nullptr;
 
@@ -280,7 +286,7 @@ namespace SimulationInterfaces
 
             if (m_physicsScenesHandle == AzPhysics::InvalidSceneHandle)
             {
-                return entities;
+                return AZ::Failure(FailedResult(ErrorCode::RESULT_OPERATION_FAILED, "Physics scene interface is not available."));
             }
 
             AzPhysics::OverlapRequest request;
@@ -304,103 +310,133 @@ namespace SimulationInterfaces
             const AZStd::vector<AZStd::string> prefilteredEntities = AZStd::move(entities);
             entities.clear();
             const AZStd::regex regex(filter.m_filter);
-            if (regex.Valid())
+            if (!regex.Valid())
             {
-                AZStd::ranges::copy_if(
-                    prefilteredEntities,
-                    AZStd::back_inserter(entities),
-                    [&regex](const AZStd::string& entityName)
-                    {
-                        return AZStd::regex_search(entityName, regex);
-                    });
+                AZ_Warning("SimulationInterfaces", false, "Invalid regex filter");
+                return AZ::Failure(FailedResult(ErrorCode::RESULT_NOT_FOUND, "Invalid regex filter"));
             }
+            AZStd::ranges::copy_if(
+                prefilteredEntities,
+                AZStd::back_inserter(entities),
+                [&regex](const AZStd::string& entityName)
+                {
+                    return AZStd::regex_search(entityName, regex);
+                });
         }
-        return entities;
+        return AZ::Success(entities);
     }
 
-    EntityState SimulationEntitiesManager::GetEntityState(const AZStd::string& name)
+    AZ::Outcome<EntityState, FailedResult> SimulationEntitiesManager::GetEntityState(const AZStd::string& name)
     {
         const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
-        AZ_Error("SimulationInterfaces", findIt != m_simulatedEntityToEntityIdMap.end(), "Entity %s not found", name.c_str());
-        if (findIt != m_simulatedEntityToEntityIdMap.end())
+        if (findIt == m_simulatedEntityToEntityIdMap.end())
         {
-            EntityState entityState{};
-            const AZ::EntityId entityId = findIt->second;
-            AZ_Assert(entityId.IsValid(), "EntityId is not valid");
-            AZ::TransformBus::EventResult(entityState.m_pose, entityId, &AZ::TransformBus::Events::GetWorldTM);
+            AZ_Warning("SimulationInterfaces", findIt != m_simulatedEntityToEntityIdMap.end(), "Entity %s not found", name.c_str());
+            return AZ::Failure(FailedResult(ErrorCode::RESULT_NOT_FOUND, "Entity not found"));
+        }
+        EntityState entityState{};
+        const AZ::EntityId entityId = findIt->second;
+        AZ_Assert(entityId.IsValid(), "EntityId is not valid");
+
+        AZ::TransformBus::EventResult(entityState.m_pose, entityId, &AZ::TransformBus::Events::GetWorldTM);
+
+        AZ::Vector3 linearVelocity = AZ::Vector3::CreateZero();
+        Physics::RigidBodyRequestBus::EventResult(linearVelocity, entityId, &Physics::RigidBodyRequests::GetLinearVelocity);
 
-            AZ::Vector3 linearVelocity = AZ::Vector3::CreateZero();
-            Physics::RigidBodyRequestBus::EventResult(linearVelocity, entityId, &Physics::RigidBodyRequests::GetLinearVelocity);
+        AZ::Vector3 angularVelocity = AZ::Vector3::CreateZero();
+        Physics::RigidBodyRequestBus::EventResult(angularVelocity, entityId, &Physics::RigidBodyRequests::GetAngularVelocity);
 
-            AZ::Vector3 angularVelocity = AZ::Vector3::CreateZero();
-            Physics::RigidBodyRequestBus::EventResult(angularVelocity, entityId, &Physics::RigidBodyRequests::GetAngularVelocity);
+        // transform linear and angular velocities to entity frame
+        const AZ::Transform entityTransformInv = entityState.m_pose.GetInverse();
+        entityState.m_twist_linear = entityTransformInv.TransformVector(linearVelocity);
+        entityState.m_twist_angular = entityTransformInv.TransformVector(angularVelocity);
+        return AZ::Success(entityState);
+    }
 
-            // transform linear and angular velocities to entity frame
-            AZ::Transform entityTransformInv = entityState.m_pose.GetInverse();
-            entityState.m_twist_linear = entityTransformInv.TransformVector(linearVelocity);
-            entityState.m_twist_angular = entityTransformInv.TransformVector(angularVelocity);
-            return entityState;
+    AZ::Outcome<MultipleEntitiesStates, FailedResult> SimulationEntitiesManager::GetEntitiesStates(const EntityFilters& filter)
+    {
+        if (!filter.m_tags_filter.m_tags.empty())
+        {
+            AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
+            return AZ::Failure(FailedResult(ErrorCode::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
+        }
+        MultipleEntitiesStates entitiesStates;
+        const auto& entities = GetEntities(filter);
+        if (!entities.IsSuccess())
+        {
+            return AZ::Failure(entities.GetError());
         }
-        return {};
+        for (const auto& entity : entities.GetValue())
+        {
+            auto state = GetEntityState(entity);
+            if (!state.IsSuccess())
+            {
+                return AZ::Failure(state.GetError());
+            }
+            entitiesStates.emplace(AZStd::make_pair(entity, state.GetValue()));
+        }
+        return entitiesStates;
     }
 
-    bool SimulationEntitiesManager::SetEntityState(const AZStd::string& name, const EntityState& state)
+    AZ::Outcome<void, FailedResult> SimulationEntitiesManager::SetEntityState(const AZStd::string& name, const EntityState& state)
     {
         const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
-        if (findIt != m_simulatedEntityToEntityIdMap.end())
+        if (findIt == m_simulatedEntityToEntityIdMap.end())
         {
-            const AZ::EntityId entityId = findIt->second;
-            AZ_Assert(entityId.IsValid(), "EntityId is not valid");
+            AZ_Warning("SimulationInterfaces", false, "Entity %s not found", name.c_str());
+            return AZ::Failure(FailedResult(ErrorCode::RESULT_NOT_FOUND, "Entity not found"));
+        }
 
-            // get entity and all descendants
-            AZStd::vector<AZ::EntityId> entityAndDescendants;
-            AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
+        const AZ::EntityId entityId = findIt->second;
+        AZ_Assert(entityId.IsValid(), "EntityId is not valid");
+
+        // get entity and all descendants
+        AZStd::vector<AZ::EntityId> entityAndDescendants;
+        AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
 
-            if (state.m_pose.IsOrthogonal())
+        if (state.m_pose.IsOrthogonal())
+        {
+            // disable simulation for all entities
+            AZStd::map<AZ::EntityId, AZ::Transform> entityTransforms;
+            for (const auto& descendant : entityAndDescendants)
             {
-                // disable simulation for all entities
-                AZStd::map<AZ::EntityId, AZ::Transform> entityTransforms;
-                for (const auto& descendant : entityAndDescendants)
-                {
-                    // get name
-                    AZStd::string entityName = "Unknown";
-                    AZ::ComponentApplicationBus::BroadcastResult(entityName, &AZ::ComponentApplicationRequests::GetEntityName, descendant);
-                    AZ_Printf("SimulationInterfaces", "Disable physics for entity %s\n", entityName.c_str());
-                    Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::DisablePhysics);
-                }
+                // get name
+                AZStd::string entityName = "Unknown";
+                AZ::ComponentApplicationBus::BroadcastResult(entityName, &AZ::ComponentApplicationRequests::GetEntityName, descendant);
+                AZ_Printf("SimulationInterfaces", "Disable physics for entity %s\n", entityName.c_str());
+                Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::DisablePhysics);
+            }
 
-                AZ::TransformBus::Event(entityId, &AZ::TransformBus::Events::SetLocalTM, state.m_pose);
+            AZ::TransformBus::Event(entityId, &AZ::TransformBus::Events::SetLocalTM, state.m_pose);
 
-                for (const auto& descendant : entityAndDescendants)
-                {
-                    Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::EnablePhysics);
-                    Physics::RigidBodyRequestBus::Event(
-                        descendant, &Physics::RigidBodyRequests::SetAngularVelocity, AZ::Vector3::CreateZero());
-                    Physics::RigidBodyRequestBus::Event(
-                        descendant, &Physics::RigidBodyRequests::SetLinearVelocity, AZ::Vector3::CreateZero());
-                }
+            for (const auto& descendant : entityAndDescendants)
+            {
+                Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::EnablePhysics);
+                Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::SetAngularVelocity, AZ::Vector3::CreateZero());
+                Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::SetLinearVelocity, AZ::Vector3::CreateZero());
             }
-            if (!state.m_twist_linear.IsZero(AZ::Constants::FloatEpsilon) || !state.m_twist_angular.IsZero(AZ::Constants::FloatEpsilon))
+        }
+
+        if (!state.m_twist_linear.IsZero(AZ::Constants::FloatEpsilon) || !state.m_twist_angular.IsZero(AZ::Constants::FloatEpsilon))
+        {
+            // get rigid body
+            AzPhysics::RigidBody* rigidBody = nullptr;
+            Physics::RigidBodyRequestBus::EventResult(rigidBody, entityId, &Physics::RigidBodyRequests::GetRigidBody);
+            if (rigidBody != nullptr)
             {
-                // get rigid body
-                AzPhysics::RigidBody* rigidBody = nullptr;
-                Physics::RigidBodyRequestBus::EventResult(rigidBody, entityId, &Physics::RigidBodyRequests::GetRigidBody);
-                if (rigidBody != nullptr)
-                {
-                    SetRigidBodyVelocities(rigidBody, state);
-                }
+                SetRigidBodyVelocities(rigidBody, state);
             }
         }
-        return false;
+        return AZ::Success();
     }
 
-    bool SimulationEntitiesManager::DeleteEntity(const AZStd::string& name)
+    void SimulationEntitiesManager::DeleteEntity(const AZStd::string& name, DeletionCompletedCb completedCb)
     {
         const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
 
         if (findIt == m_simulatedEntityToEntityIdMap.end())
         {
-            return false;
+            completedCb(AZ::Failure(FailedResult(ErrorCode::RESULT_NOT_FOUND, "Entity not found")));
         }
 
         const AZ::EntityId entityId = findIt->second;
@@ -414,12 +450,25 @@ namespace SimulationInterfaces
         if (m_spawnedTickets.find(ticketId) != m_spawnedTickets.end())
         {
             // remove the ticket
-            m_spawnedTickets.erase(ticketId);
+            //m_spawnedTickets.erase(ticketId);
+            /// get spawner
+            auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
+            AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
+            // get ticket
+            auto ticket = m_spawnedTickets[ticketId];
+            // remove ticket
+            AzFramework::DespawnAllEntitiesOptionalArgs optionalArgs;
+            optionalArgs.m_completionCallback = [this, completedCb](AzFramework::EntitySpawnTicket::Id ticketId)
+            {
+                m_spawnedTickets.erase(ticketId);
+                completedCb(AZ::Success());
+            };
+            spawner->DespawnAllEntities(ticket, optionalArgs);
         }
         else
         {
-            AZ_Warning("SimulationInterfaces", false, "Entity %s was not spawned by this component, wont delete it", name.c_str());
-            return false;
+            const auto msg = AZStd::string::format("Entity %s was not spawned by this component, wont delete it", name.c_str());
+            completedCb(AZ::Failure(FailedResult(ErrorCode::RESULT_OPERATION_FAILED, msg)));
         }
 #ifdef POTENTIALY_UNSAFE
         if (findIt != m_simulatedEntityToEntityIdMap.end())
@@ -438,21 +487,9 @@ namespace SimulationInterfaces
             return true;
         }
 #endif
-        return false;
-    }
-
-    AZStd::unordered_map<AZStd::string, EntityState> SimulationEntitiesManager::GetEntitiesStates(const EntityFilters& filter)
-    {
-        AZStd::unordered_map<AZStd::string, EntityState> entitiesStates;
-        const auto& entities = GetEntities(filter);
-        for (const auto& entity : entities)
-        {
-            entitiesStates.emplace(AZStd::make_pair(entity, GetEntityState(entity)));
-        }
-        return entitiesStates;
     }
 
-    AZStd::vector<Spawnable> SimulationEntitiesManager::GetSpawnables()
+    AZ::Outcome<SpawnableList, FailedResult> SimulationEntitiesManager::GetSpawnables()
     {
         AZStd::vector<Spawnable> spawnables;
 
@@ -471,7 +508,7 @@ namespace SimulationInterfaces
         };
 
         AZ::Data::AssetCatalogRequestBus::Broadcast(&AZ::Data::AssetCatalogRequests::EnumerateAssets, nullptr, enumCallback, nullptr);
-        return spawnables;
+        return AZ::Success(spawnables);
     }
 
     void SimulationEntitiesManager::SpawnEntity(
@@ -501,7 +538,8 @@ namespace SimulationInterfaces
             AZ::Data::AssetManager::Instance().GetAsset<AzFramework::Spawnable>(assetId, AZ::Data::AssetLoadBehavior::NoLoad);
         if (!spawnableAsset)
         {
-            completedCb(AZ::Failure("Failed to get spawnable asset - incorrect uri"));
+            const auto msg = AZStd::string::format("Spawnable asset %s not found", uri.c_str());
+            completedCb(AZ::Failure(FailedResult(ErrorCode::RESULT_NOT_FOUND, msg)));
             return;
         }
 
@@ -536,18 +574,26 @@ namespace SimulationInterfaces
             }
         };
         optionalArgs.m_completionCallback =
-            [this](AzFramework::EntitySpawnTicket::Id ticketId, AzFramework::SpawnableConstEntityContainerView view)
+            [this, uri](AzFramework::EntitySpawnTicket::Id ticketId, AzFramework::SpawnableConstEntityContainerView view)
         {
             // at this point the entities are spawned and should be registered in simulation interface and callback should be called
-            // if that is not a case, it means that the AZFrameworrk::Pshysics::OnSimulationBodyAdded event was not called.
+            // if that is not a case, it means that the AZFramework::Physics::OnSimulationBodyAdded event was not called.
             // That means the prefab has no physics component or the physics component is not enabled - we need to call the callback here
             // and return the error.
             auto spawnData = m_spawnCompletedCallbacks.find(ticketId);
             if (spawnData != m_spawnCompletedCallbacks.end())
             {
                 // call and remove the callback
-                spawnData->second.m_completedCb(AZ::Failure(
-                    "Entity was not registered in simulation interface - no physics component or physics component is not enabled."));
+                const auto msg = AZStd::string::format(
+                    "Entity %s (uri : %s) was not registered in simulation interface - "
+                    "no physics component or physics component is not enabled in source prefab.\n"
+                    "Entity will be in simulation, but not available in simulation interface.\n"
+                    "Please add some physics component (at least one static rigid body component) to the prefab.\n"
+                    "Technically, it is a memory leak.\n",
+                    spawnData->second.m_userProposedName.c_str(),
+                    uri.c_str());
+                AZ_Error("SimulationInterfaces", false, msg.c_str());
+                spawnData->second.m_completedCb(msg);
                 m_spawnCompletedCallbacks.erase(spawnData);
             }
         };

+ 6 - 6
Gems/SimulationInterfaces/Code/Source/Clients/SimulationEntitiesManager.h

@@ -37,12 +37,12 @@ namespace SimulationInterfaces
 
     protected:
         // SimulationEntityManagerRequestBus interface implementation
-        AZStd::vector<AZStd::string> GetEntities(const EntityFilters& filter) override;
-        EntityState GetEntityState(const AZStd::string& name) override;
-        AZStd::unordered_map<AZStd::string, EntityState> GetEntitiesStates(const EntityFilters& filter) override;
-        bool SetEntityState(const AZStd::string& name, const EntityState& state) override;
-        bool DeleteEntity(const AZStd::string& name) override;
-        AZStd::vector<Spawnable> GetSpawnables() override;
+        AZ::Outcome<EntityNameList, FailedResult> GetEntities(const EntityFilters& filter) override;
+        AZ::Outcome<EntityState, FailedResult> GetEntityState(const AZStd::string& name) override;
+        AZ::Outcome<MultipleEntitiesStates, FailedResult> GetEntitiesStates(const EntityFilters& filter) override;
+        AZ::Outcome<void, FailedResult> SetEntityState(const AZStd::string& name, const EntityState& state) override;
+        void DeleteEntity(const AZStd::string& name, DeletionCompletedCb completedCb) override;
+        AZ::Outcome<SpawnableList, FailedResult> GetSpawnables() override;
         void SpawnEntity(
             const AZStd::string& name,
             const AZStd::string& uri,

+ 0 - 1
Gems/SimulationInterfaces/Code/Source/Clients/SimulationManager.cpp

@@ -121,7 +121,6 @@ namespace SimulationInterfaces
         // install handler
         scene->RegisterSceneSimulationFinishHandler(m_simulationFinishEvent);
         SetSimulationPaused(false);
-
     }
 
 } // namespace SimulationInterfaces

+ 5 - 5
Gems/SimulationInterfaces/Code/Source/Clients/SimulationManager.h

@@ -18,9 +18,9 @@
 #include <SimulationInterfaces/SimulationMangerRequestBus.h>
 namespace SimulationInterfaces
 {
-    class SimulationManager :
-        public AZ::Component,
-        protected SimulationManagerRequestBus::Handler
+    class SimulationManager
+        : public AZ::Component
+        , protected SimulationManagerRequestBus::Handler
     {
     public:
         AZ_COMPONENT_DECL(SimulationManager);
@@ -39,11 +39,11 @@ namespace SimulationInterfaces
         void Init() override;
         void Activate() override;
         void Deactivate() override;
+
     protected:
         void SetSimulationPaused(bool paused) override;
         void StepSimulation(AZ::u32 steps) override;
         uint32_t m_numberOfPhysicsSteps = 0;
         AzPhysics::SceneEvents::OnSceneSimulationFinishHandler m_simulationFinishEvent;
-
     };
-} // namespace SimulationInterfaces
+} // namespace SimulationInterfaces

+ 1 - 1
Gems/SimulationInterfaces/Code/Source/SimulationInterfacesModuleInterface.cpp

@@ -11,8 +11,8 @@
 
 #include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
 
+#include <Clients/SimulationManager.h>
 #include <Clients/SimulationEntitiesManager.h>
-#include "Clients/SimulationManager.h"
 
 namespace SimulationInterfaces
 {

+ 3 - 8
Gems/SimulationInterfaces/Code/Source/Tools/SimulationEntitiesManagerEditor.cpp

@@ -14,10 +14,7 @@
 namespace SimulationInterfaces
 {
     AZ_COMPONENT_IMPL(
-        SimulationEntitiesManagerEditor,
-        "SimulationEntitiesManagerEditor",
-        SimulationEntitiesManagerEditorTypeId,
-        BaseSystemComponent);
+        SimulationEntitiesManagerEditor, "SimulationEntitiesManagerEditor", SimulationEntitiesManagerEditorTypeId, BaseSystemComponent);
 
     void SimulationEntitiesManagerEditor::Reflect(AZ::ReflectContext* context)
     {
@@ -43,14 +40,12 @@ namespace SimulationInterfaces
         incompatible.push_back(AZ_CRC_CE("SimulationInterfacesEditorService"));
     }
 
-    void SimulationEntitiesManagerEditor::GetRequiredServices(
-        [[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& required)
+    void SimulationEntitiesManagerEditor::GetRequiredServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& required)
     {
         BaseSystemComponent::GetRequiredServices(required);
     }
 
-    void SimulationEntitiesManagerEditor::GetDependentServices(
-        [[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& dependent)
+    void SimulationEntitiesManagerEditor::GetDependentServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& dependent)
     {
         BaseSystemComponent::GetDependentServices(dependent);
     }

+ 32 - 32
Gems/SimulationInterfaces/Code/Source/Tools/SimulationManagerEditor.h

@@ -1,10 +1,10 @@
 /*
-* Copyright (c) Contributors to the Open 3D Engine Project.
-* For complete copyright and license terms please see the LICENSE at the root of this distribution.
-*
-* SPDX-License-Identifier: Apache-2.0 OR MIT
-*
-*/
+ * Copyright (c) Contributors to the Open 3D Engine Project.
+ * For complete copyright and license terms please see the LICENSE at the root of this distribution.
+ *
+ * SPDX-License-Identifier: Apache-2.0 OR MIT
+ *
+ */
 
 #pragma once
 
@@ -14,30 +14,30 @@
 
 namespace SimulationInterfaces
 {
-   /// System component for SimulationInterfaces editor
-   class SimulationManagerEditor
-       : public SimulationManager
-       , protected AzToolsFramework::EditorEvents::Bus::Handler
-   {
-       using BaseSystemComponent = SimulationManager;
-
-   public:
-       AZ_COMPONENT_DECL(SimulationManagerEditor);
-
-       static void Reflect(AZ::ReflectContext* context);
-
-       SimulationManagerEditor();
-       ~SimulationManagerEditor();
-
-   private:
-       static void GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided);
-       static void GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible);
-       static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required);
-       static void GetDependentServices(AZ::ComponentDescriptor::DependencyArrayType& dependent);
-
-       // AZ::Component
-       void Init() override;
-       void Activate() override;
-       void Deactivate() override;
-   };
+    /// System component for SimulationInterfaces editor
+    class SimulationManagerEditor
+        : public SimulationManager
+        , protected AzToolsFramework::EditorEvents::Bus::Handler
+    {
+        using BaseSystemComponent = SimulationManager;
+
+    public:
+        AZ_COMPONENT_DECL(SimulationManagerEditor);
+
+        static void Reflect(AZ::ReflectContext* context);
+
+        SimulationManagerEditor();
+        ~SimulationManagerEditor();
+
+    private:
+        static void GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided);
+        static void GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible);
+        static void GetRequiredServices(AZ::ComponentDescriptor::DependencyArrayType& required);
+        static void GetDependentServices(AZ::ComponentDescriptor::DependencyArrayType& dependent);
+
+        // AZ::Component
+        void Init() override;
+        void Activate() override;
+        void Deactivate() override;
+    };
 } // namespace SimulationInterfaces

+ 49 - 29
Gems/SimulationInterfaces/Code/Tests/Tools/SimulationInterfaceTests.cpp

@@ -15,9 +15,11 @@ namespace UnitTest
     TEST_F(SimulationInterfaceTestFixture, EmptyScene)
     {
         using namespace SimulationInterfaces;
-        AZStd::vector<AZStd::string> entities;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        EXPECT_EQ(entities.size(), 0);
+        AZ::Outcome<EntityNameList, FailedResult> entities;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entities.IsSuccess());
+        EXPECT_EQ(entities.GetValue().size(), 0);
     }
 
     TEST_F(SimulationInterfaceTestFixture, AddSimulatedEntityThenRemove)
@@ -26,19 +28,25 @@ namespace UnitTest
         const AZ::EntityId entityId1 = CreateEntityWithStaticBodyComponent("Foo", AZ::Transform::CreateIdentity());
         const AZ::EntityId entityId2 = CreateEntityWithStaticBodyComponent("Bar", AZ::Transform::CreateIdentity());
 
-        AZStd::vector<AZStd::string> entities;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        ASSERT_EQ(entities.size(), 2);
+        AZ::Outcome<EntityNameList, FailedResult> entities;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entities.IsSuccess());
+        ASSERT_EQ(entities.GetValue().size(), 2);
         DeleteEntity(entityId1);
 
-        AZStd::vector<AZStd::string> entities2;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities2, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        EXPECT_EQ(entities2.size(), 1);
+        AZ::Outcome<EntityNameList, FailedResult> entities2;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entities2, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entities2.IsSuccess());
+        EXPECT_EQ(entities2.GetValue().size(), 1);
 
         DeleteEntity(entityId2);
-        AZStd::vector<AZStd::string> entities3;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities3, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        EXPECT_EQ(entities3.size(), 0);
+        AZ::Outcome<EntityNameList, FailedResult> entities3;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entities3, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entities3.IsSuccess());
+        EXPECT_EQ(entities3.GetValue().size(), 0);
     }
 
     TEST_F(SimulationInterfaceTestFixture, AddEntitiesWithDupName)
@@ -47,11 +55,14 @@ namespace UnitTest
 
         const AZ::EntityId entityId1 = CreateEntityWithStaticBodyComponent("Bar1", AZ::Transform::CreateIdentity());
         const AZ::EntityId entityId2 = CreateEntityWithStaticBodyComponent("Bar1", AZ::Transform::CreateIdentity());
-        AZStd::vector<AZStd::string> entities;
 
-        SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        EXPECT_EQ(entities.size(), 2);
-        EXPECT_NE(entities[0], entities[1]);
+        AZ::Outcome<EntityNameList, FailedResult> entities;
+
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entities.IsSuccess());
+        EXPECT_EQ(entities.GetValue().size(), 2);
+        EXPECT_NE(entities.GetValue()[0], entities.GetValue()[1]);
         DeleteEntity(entityId1);
         DeleteEntity(entityId2);
     }
@@ -60,7 +71,7 @@ namespace UnitTest
     {
         // This test is disabled since due to some issue outside to this gem, the rigid body is created without the collider shape
         // and the filter is not applied. This test will be enabled once the issue is resolved.
-        GTEST_SKIP()<<"Need to fix the issue with the collider shape creation.";
+        GTEST_SKIP() << "Need to fix the issue with the collider shape creation.";
         using namespace SimulationInterfaces;
         const AZ::EntityId entityId1 =
             CreateEntityWithStaticBodyComponent("Inside", AZ::Transform::CreateTranslation(AZ::Vector3(0.0f, 0.0f, 0.0f)));
@@ -70,13 +81,14 @@ namespace UnitTest
         EntityFilters filter;
         filter.m_bounds_shape = AZStd::make_shared<Physics::SphereShapeConfiguration>(2.0f);
 
-        AZStd::vector<AZStd::string> entities;
+        AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
         auto* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
         physicsSystem->Simulate(1.0f / 60.0f);
 
-        ASSERT_EQ(entities.size(), 1);
-        EXPECT_EQ(entities.front(), "Inside");
+        ASSERT_TRUE(entities.IsSuccess());
+        ASSERT_EQ(entities.GetValue().size(), 1);
+        EXPECT_EQ(entities.GetValue().front(), "Inside");
 
         DeleteEntity(entityId1);
         DeleteEntity(entityId2);
@@ -93,11 +105,12 @@ namespace UnitTest
         EntityFilters filter;
         filter.m_filter = "Will.*";
 
-        AZStd::vector<AZStd::string> entities;
+        AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
 
-        ASSERT_EQ(entities.size(), 1);
-        EXPECT_EQ(entities.front(), "WillMatch");
+        ASSERT_TRUE(entities.IsSuccess());
+        ASSERT_EQ(entities.GetValue().size(), 1);
+        EXPECT_EQ(entities.GetValue().front(), "WillMatch");
 
         DeleteEntity(entityId1);
         DeleteEntity(entityId2);
@@ -115,10 +128,11 @@ namespace UnitTest
         EntityFilters filter;
         filter.m_filter = "[a-z";
 
-        AZStd::vector<AZStd::string> entities;
+        AZ::Outcome<EntityNameList, FailedResult> entities;
         SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
 
-        EXPECT_EQ(entities.size(), 0);
+        EXPECT_FALSE(entities.IsSuccess());
+
         DeleteEntity(entityId1);
         DeleteEntity(entityId2);
     }
@@ -132,16 +146,22 @@ namespace UnitTest
             CreateEntityWithStaticBodyComponent(entityName, AZ::Transform::CreateTranslation(AZ::Vector3(2.0f, 0.0f, 10.0f)));
 
         EntityFilters filter;
-        EntityState stateBefore;
-        SimulationEntityManagerRequestBus::BroadcastResult(stateBefore, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        AZ::Outcome<EntityState, FailedResult> stateBeforeResult;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            stateBeforeResult, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        EXPECT_TRUE(stateBeforeResult.IsSuccess());
+        const auto& stateBefore = stateBeforeResult.GetValue();
         EXPECT_EQ(stateBefore.m_pose.GetTranslation(), AZ::Vector3(2.0f, 0.0f, 10.0f));
         for (int i = 0; i < 10; i++)
         {
             auto* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
             physicsSystem->Simulate(1.0f / 60.0f);
         }
-        EntityState stateAfter;
-        SimulationEntityManagerRequestBus::BroadcastResult(stateAfter, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        AZ::Outcome<EntityState, FailedResult> stateAfterResult;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            stateAfterResult, &SimulationEntityManagerRequestBus::Events::GetEntityState, entityName);
+        EXPECT_TRUE(stateAfterResult.IsSuccess());
+        const auto& stateAfter = stateAfterResult.GetValue();
         AZ::Vector3 deltaPos = stateAfter.m_pose.GetTranslation() - stateBefore.m_pose.GetTranslation();
 
         // check if the entity moved

+ 33 - 16
Gems/SimulationInterfaces/Code/Tests/Tools/SimulationIterfaceAppTest.cpp

@@ -49,7 +49,6 @@ namespace UnitTest
         AZ_Assert(assetId.IsValid(), "Failed to get asset id for %s", TestSpawnable.c_str());
     }
 
-
     TEST_F(SimulationInterfaceTestFixture, SpawnAppTest)
     {
         // This is an integration test that runs the test application with the SimulationInterfaces gem enabled.
@@ -61,7 +60,7 @@ namespace UnitTest
         constexpr AZStd::string_view uri = "product_asset:///sampleasset/testsimulationentity.spawnable";
         constexpr AZStd::string_view entityNamespace = "";
         AZStd::atomic_bool completed = false;
-        SimulationEntityManagerRequests::SpawnCompletedCb completedCb = [&](const AZ::Outcome<AZStd::string, AZStd::string>& result)
+        SpawnCompletedCb completedCb = [&](const AZ::Outcome<AZStd::string, FailedResult>& result)
         {
             EXPECT_TRUE(result.IsSuccess());
             completed = true;
@@ -75,11 +74,14 @@ namespace UnitTest
         EXPECT_TRUE(completed);
 
         // list simulation entities
-        AZStd::vector<AZStd::string> entities;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        AZ::Outcome<EntityNameList, FailedResult> entitiesResult;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entitiesResult, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entitiesResult.IsSuccess());
+        const auto& entities = entitiesResult.GetValue();
         EXPECT_EQ(entities.size(), 1);
 
-        ASSERT_FALSE(entities.empty())<< "Simulated Entities Empty";
+        ASSERT_FALSE(entities.empty()) << "Simulated Entities Empty";
         const AZStd::string spawnedEntityName = entities.front();
         printf("Spawned entity name %s\n", spawnedEntityName.c_str());
 
@@ -87,9 +89,12 @@ namespace UnitTest
         StepPhysics(100);
 
         // Get entity state,
-        AZStd::unordered_map<AZStd::string, EntityState> entityStates;
+        AZ::Outcome<MultipleEntitiesStates, FailedResult> entityStatesResult;
         SimulationEntityManagerRequestBus::BroadcastResult(
-            entityStates, &SimulationEntityManagerRequestBus::Events::GetEntitiesStates, EntityFilters());
+            entityStatesResult, &SimulationEntityManagerRequestBus::Events::GetEntitiesStates, EntityFilters());
+        ASSERT_TRUE(entityStatesResult.IsSuccess());
+
+        const auto& entityStates = entityStatesResult.GetValue();
         auto entityState = entityStates.find(spawnedEntityName);
         ASSERT_NE(entityState, entityStates.end());
         EXPECT_EQ(entityState->first, spawnedEntityName);
@@ -99,8 +104,11 @@ namespace UnitTest
 
         // set new entity state - move the entity to X=1000 meters
         const AZ::Vector3 newPosition = AZ::Vector3(1000.0f, 0.0f, 0.0f);
-        const EntityState newState = { AZ::Transform::CreateTranslation(newPosition), AZ::Vector3::CreateZero(), AZ::Vector3::CreateZero() };
-        SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::SetEntityState, spawnedEntityName, newState);
+        const EntityState newState = { AZ::Transform::CreateTranslation(newPosition),
+                                       AZ::Vector3::CreateZero(),
+                                       AZ::Vector3::CreateZero() };
+        SimulationEntityManagerRequestBus::Broadcast(
+            &SimulationEntityManagerRequestBus::Events::SetEntityState, spawnedEntityName, newState);
 
         StepPhysics();
 
@@ -108,18 +116,27 @@ namespace UnitTest
         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));
-        AZStd::vector<AZStd::string> entitiesFiltered;
-        SimulationEntityManagerRequestBus::BroadcastResult(entitiesFiltered, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
-        EXPECT_EQ(entitiesFiltered.size(), 1);
+        AZ::Outcome<EntityNameList, FailedResult> entitiesFiltered;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entitiesFiltered, &SimulationEntityManagerRequestBus::Events::GetEntities, filter);
+        ASSERT_TRUE(entitiesFiltered.IsSuccess());
+        EXPECT_EQ(entitiesFiltered.GetValue().size(), 1);
 
         // delete entity using its name
-        SimulationEntityManagerRequestBus::Broadcast(&SimulationEntityManagerRequestBus::Events::DeleteEntity, entityName);
+        DeletionCompletedCb deletionCompletedCb = [](const AZ::Outcome<void, FailedResult>& result)
+        {
+            EXPECT_TRUE(result.IsSuccess());
+        };
+        SimulationEntityManagerRequestBus::Broadcast(
+            &SimulationEntityManagerRequestBus::Events::DeleteEntity, entityName, deletionCompletedCb);
         TickApp(100);
 
         // list simulation entities after deletion, expect no simulation entities
-        AZStd::vector<AZStd::string> entities2;
-        SimulationEntityManagerRequestBus::BroadcastResult(entities2, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
-        EXPECT_EQ(entities2.size(), 0);
+        AZ::Outcome<EntityNameList, FailedResult> entitiesAfterDeletion;
+        SimulationEntityManagerRequestBus::BroadcastResult(
+            entitiesAfterDeletion, &SimulationEntityManagerRequestBus::Events::GetEntities, EntityFilters());
+        ASSERT_TRUE(entitiesAfterDeletion.IsSuccess());
+        EXPECT_EQ(entitiesAfterDeletion.GetValue().size(), 0);
     }
 
 } // namespace UnitTest

+ 0 - 1
Gems/SimulationInterfaces/Code/Tests/Tools/TestFixture.cpp

@@ -134,7 +134,6 @@ namespace UnitTest
             auto* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
             physicsSystem->Simulate(1.0f / 60.0f);
         }
-
     }
 
     void SimulationInterfaceTestFixture::TickApp(int numTicks)

+ 4 - 2
Gems/SimulationInterfaces/Code/simulationinterfaces_api_files.cmake

@@ -5,7 +5,9 @@
 #
 
 set(FILES
-        Include/SimulationInterfaces/SimulationEntityManagerRequestBus.h
-    Include/SimulationInterfaces/SimulationMangerRequestBus.h
+    Include/SimulationInterfaces/Result.h
+    Include/SimulationInterfaces/TagFilter.h
+    Include/SimulationInterfaces/SimulationEntityManagerRequestBus.h
     Include/SimulationInterfaces/SimulationInterfacesTypeIds.h
+    Include/SimulationInterfaces/SimulationMangerRequestBus.h
 )