SimulationEntitiesManager.cpp 46 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056
  1. /*
  2. * Copyright (c) Contributors to the Open 3D Engine Project.
  3. * For complete copyright and license terms please see the LICENSE at the root of this distribution.
  4. *
  5. * SPDX-License-Identifier: Apache-2.0 OR MIT
  6. *
  7. */
  8. #include "SimulationEntitiesManager.h"
  9. #include "CommonUtilities.h"
  10. #include <AzCore/Asset/AssetManager.h>
  11. #include <AzCore/Asset/AssetManagerBus.h>
  12. #include <AzCore/Component/ComponentApplicationBus.h>
  13. #include <AzCore/Component/EntityId.h>
  14. #include <AzCore/Component/TransformBus.h>
  15. #include <AzCore/Console/IConsole.h>
  16. #include <AzCore/Math/Obb.h>
  17. #include <AzCore/Outcome/Outcome.h>
  18. #include <AzCore/RTTI/RTTIMacros.h>
  19. #include <AzCore/Serialization/SerializeContext.h>
  20. #include <AzCore/Settings/SettingsRegistry.h>
  21. #include <AzCore/std/algorithm.h>
  22. #include <AzCore/std/containers/vector.h>
  23. #include <AzCore/std/ranges/elements_view.h>
  24. #include <AzCore/std/ranges/ranges_algorithm.h>
  25. #include <AzCore/std/string/regex.h>
  26. #include <AzCore/std/string/string.h>
  27. #include <AzFramework/Components/TransformComponent.h>
  28. #include <AzFramework/Physics/Common/PhysicsSceneQueries.h>
  29. #include <AzFramework/Physics/Common/PhysicsSimulatedBody.h>
  30. #include <AzFramework/Physics/PhysicsSystem.h>
  31. #include <AzFramework/Physics/RigidBodyBus.h>
  32. #include <AzFramework/Physics/SimulatedBodies/RigidBody.h>
  33. #include <AzFramework/Spawnable/Spawnable.h>
  34. #include <AzFramework/Spawnable/SpawnableEntitiesInterface.h>
  35. #include <AzFramework/Entity/EntityContextBus.h>
  36. #include <AzFramework/Entity/GameEntityContextBus.h>
  37. #include <ROS2/Frame/ROS2FrameComponent.h>
  38. #include <SimulationInterfaces/Bounds.h>
  39. #include <SimulationInterfaces/Result.h>
  40. #include <SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h>
  41. #include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
  42. #include <SimulationInterfaces/SimulationMangerRequestBus.h>
  43. #include <simulation_interfaces/msg/result.hpp>
  44. #include <simulation_interfaces/msg/simulator_features.hpp>
  45. #include <simulation_interfaces/srv/spawn_entity.hpp>
  46. namespace SimulationInterfaces
  47. {
  48. namespace
  49. {
  50. // copied from PhysX Gem to prevent adding dependency to PhysX (Gems/PhysX/Core/Code/Include/PhysX/NativeTypeIdentifiers.h)
  51. static const AZ::Crc32 RigidBody = AZ_CRC_CE("PhysXRigidBody");
  52. static const AZ::Crc32 RigidBodyStatic = AZ_CRC_CE("PhysXRigidBodyStatic");
  53. static const AZ::Crc32 ArticulationLink = AZ_CRC_CE("PhysXArticulationLink");
  54. void SetRigidBodyVelocities(AzPhysics::RigidBody* rigidBody, const EntityState& state)
  55. {
  56. if (!state.m_twistAngular.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
  57. {
  58. // get transform
  59. AZ::Vector3 angularVelWorld = rigidBody->GetTransform().TransformVector(state.m_twistAngular);
  60. rigidBody->SetAngularVelocity(angularVelWorld);
  61. }
  62. if (!state.m_twistLinear.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
  63. {
  64. // get transform
  65. AZ::Vector3 linearVelWorld = rigidBody->GetTransform().TransformVector(state.m_twistLinear);
  66. rigidBody->SetLinearVelocity(linearVelWorld);
  67. }
  68. }
  69. } // namespace
  70. AZ_COMPONENT_IMPL(SimulationEntitiesManager, "SimulationEntitiesManager", SimulationEntitiesManagerTypeId);
  71. void SimulationEntitiesManager::Reflect(AZ::ReflectContext* context)
  72. {
  73. if (auto serializeContext = azrtti_cast<AZ::SerializeContext*>(context))
  74. {
  75. serializeContext->Class<SimulationEntitiesManager, AZ::Component>()->Version(0);
  76. }
  77. }
  78. void SimulationEntitiesManager::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
  79. {
  80. provided.push_back(AZ_CRC_CE("SimulationInterfacesService"));
  81. }
  82. void SimulationEntitiesManager::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  83. {
  84. incompatible.push_back(AZ_CRC_CE("SimulationInterfacesService"));
  85. }
  86. void SimulationEntitiesManager::GetRequiredServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& required)
  87. {
  88. required.push_back(AZ_CRC_CE("AssetCatalogService"));
  89. required.push_back(AZ_CRC_CE("SimulationManagerService"));
  90. required.push_back(AZ_CRC_CE("SimulationFeaturesAggregator"));
  91. }
  92. void SimulationEntitiesManager::GetDependentServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& dependent)
  93. {
  94. dependent.push_back(AZ_CRC_CE("PhysicsService"));
  95. dependent.push_back(AZ_CRC_CE("SimulationManagerService"));
  96. dependent.push_back(AZ_CRC_CE("SimulationFeaturesAggregator"));
  97. }
  98. SimulationEntitiesManager::SimulationEntitiesManager()
  99. {
  100. if (SimulationEntityManagerInterface::Get() == nullptr)
  101. {
  102. SimulationEntityManagerInterface::Register(this);
  103. }
  104. }
  105. SimulationEntitiesManager::~SimulationEntitiesManager()
  106. {
  107. if (SimulationEntityManagerInterface::Get() == this)
  108. {
  109. SimulationEntityManagerInterface::Unregister(this);
  110. }
  111. }
  112. AZ::Outcome<AZStd::string, FailedResult> SimulationEntitiesManager::RegisterNewSimulatedBody(
  113. const AZStd::string& proposedName, const AZ::EntityId& entityId)
  114. {
  115. if (!entityId.IsValid())
  116. {
  117. constexpr const char* msg = "EntityId is not valid";
  118. AZ_Trace("SimulationInterfaces", msg);
  119. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg));
  120. }
  121. AZ::Entity* entity = nullptr;
  122. AZ::ComponentApplicationBus::BroadcastResult(entity, &AZ::ComponentApplicationRequests::FindEntity, entityId);
  123. if (entity == nullptr)
  124. {
  125. constexpr const char* msg = "Entity pointer is not valid";
  126. AZ_Trace("SimulationInterfaces", msg);
  127. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg));
  128. }
  129. // register entity
  130. const AZStd::string registeredName = this->AddSimulatedEntity(entityId, proposedName);
  131. // cache the initial state - for simulator reset with SCOPE_STATE.
  132. EntityState initialState{};
  133. initialState.m_pose = entity->GetTransform()->GetWorldTM();
  134. auto simulatedBody = Utils::GetSimulatedBody(entityId);
  135. if (simulatedBody.IsSuccess())
  136. {
  137. if (auto* rigidBody = azdynamic_cast<AzPhysics::RigidBody*>(simulatedBody.GetValue()))
  138. {
  139. initialState.m_twistLinear = rigidBody->GetLinearVelocity();
  140. initialState.m_twistAngular = rigidBody->GetAngularVelocity();
  141. }
  142. }
  143. m_entityIdToInitialState[entityId] = initialState;
  144. AZ_Info("SimulationInterfaces", "Registered entity %s\n", registeredName.c_str());
  145. return AZ::Success(registeredName);
  146. }
  147. void SimulationEntitiesManager::Activate()
  148. {
  149. m_sceneAddedHandler = AzPhysics::SystemEvents::OnSceneAddedEvent::Handler(
  150. [this](AzPhysics::SceneHandle sceneHandle)
  151. {
  152. AZ_Warning(
  153. "SimulationInterfaces",
  154. m_physicsScenesHandle == AzPhysics::InvalidSceneHandle,
  155. "SimulationInterfaces already gathered physics scene");
  156. m_physicsScenesHandle = sceneHandle;
  157. });
  158. m_sceneRemovedHandler = AzPhysics::SystemEvents::OnSceneRemovedEvent::Handler(
  159. [this](AzPhysics::SceneHandle sceneHandle)
  160. {
  161. if (m_physicsScenesHandle == sceneHandle)
  162. {
  163. AZ_Info("SimulationInterfaces", "Physics scene handler removed");
  164. m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
  165. }
  166. });
  167. AzPhysics::SystemInterface* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
  168. if (physicsSystem)
  169. {
  170. physicsSystem->RegisterSceneAddedEvent(m_sceneAddedHandler);
  171. physicsSystem->RegisterSceneRemovedEvent(m_sceneRemovedHandler);
  172. }
  173. SimulationEntityManagerRequestBus::Handler::BusConnect();
  174. SimulationFeaturesAggregatorRequestBus::Broadcast(
  175. &SimulationFeaturesAggregatorRequests::AddSimulationFeatures,
  176. AZStd::unordered_set<SimulationFeatureType>{
  177. simulation_interfaces::msg::SimulatorFeatures::ENTITY_TAGS,
  178. simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_BOX,
  179. // not implemented: simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_CONVEX,
  180. simulation_interfaces::msg::SimulatorFeatures::ENTITY_CATEGORIES,
  181. simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_GETTING,
  182. simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_SETTING,
  183. simulation_interfaces::msg::SimulatorFeatures::ENTITY_INFO_GETTING,
  184. simulation_interfaces::msg::SimulatorFeatures::ENTITY_INFO_SETTING,
  185. simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS,
  186. simulation_interfaces::msg::SimulatorFeatures::DELETING,
  187. simulation_interfaces::msg::SimulatorFeatures::SPAWNABLES,
  188. simulation_interfaces::msg::SimulatorFeatures::SPAWNING });
  189. }
  190. void SimulationEntitiesManager::Deactivate()
  191. {
  192. SimulationEntityManagerRequestBus::Handler::BusDisconnect();
  193. m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
  194. m_sceneAddedHandler.Disconnect();
  195. m_sceneRemovedHandler.Disconnect();
  196. m_entityIdToSimulatedEntityMap.clear();
  197. m_simulatedEntityToEntityIdMap.clear();
  198. m_simulatedEntityToPrefabRoot.clear();
  199. m_entityIdToInitialState.clear();
  200. m_spawnedTickets.clear();
  201. }
  202. AZStd::string SimulationEntitiesManager::AddSimulatedEntity(AZ::EntityId entityId, const AZStd::string& userProposedName)
  203. {
  204. if (!entityId.IsValid())
  205. {
  206. return "";
  207. }
  208. // check if entity is already registered
  209. auto findIt = m_entityIdToSimulatedEntityMap.find(entityId);
  210. if (findIt != m_entityIdToSimulatedEntityMap.end())
  211. {
  212. return findIt->second;
  213. }
  214. // register entity under unique name
  215. AZStd::string simulatedEntityName = GetSimulatedEntityName(entityId, userProposedName);
  216. m_simulatedEntityToEntityIdMap[simulatedEntityName] = entityId;
  217. m_entityIdToSimulatedEntityMap[entityId] = simulatedEntityName;
  218. return simulatedEntityName;
  219. }
  220. AZ::Outcome<void, FailedResult> SimulationEntitiesManager::UnregisterSimulatedBody(const AZStd::string& name)
  221. {
  222. if (auto findIt = m_simulatedEntityToEntityIdMap.find(name); findIt != m_simulatedEntityToEntityIdMap.end())
  223. {
  224. // remove registry
  225. const auto& entityId = findIt->second;
  226. // remove initial state
  227. if (auto findStateIt = m_entityIdToInitialState.find(entityId); findStateIt != m_entityIdToInitialState.end())
  228. {
  229. m_entityIdToInitialState.erase(findStateIt);
  230. }
  231. m_entityIdToSimulatedEntityMap.erase(entityId);
  232. m_simulatedEntityToEntityIdMap.erase(findIt);
  233. RemoveEntityInfoIfNeeded(name);
  234. // remove info about root of simulated entity only if it was spawned by this component
  235. if (m_simulatedEntityToPrefabRoot.contains(name))
  236. {
  237. m_simulatedEntityToPrefabRoot.erase(name);
  238. }
  239. return AZ::Success();
  240. }
  241. return AZ::Failure(FailedResult(
  242. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  243. AZStd::string::format("Failed to find entity with given name %s", name.c_str())));
  244. }
  245. AZStd::vector<AZStd::string> SimulationEntitiesManager::FilterEntitiesByCategories(
  246. const AZStd::vector<AZStd::string>& prefilteredEntities, const AZStd::vector<EntityCategory>& categories)
  247. {
  248. AZStd::vector<AZStd::string> entities;
  249. entities.reserve(prefilteredEntities.size());
  250. for (auto& category : categories)
  251. {
  252. const auto categoryExists = m_categoryToNames.contains(category);
  253. AZ_Warning(
  254. "SpawnableSceneProviderSystemComponent",
  255. categoryExists,
  256. "Category %d doesn't exists in database, will be skipped",
  257. category);
  258. if (categoryExists)
  259. {
  260. AZStd::ranges::copy_if(
  261. prefilteredEntities,
  262. AZStd::back_inserter(entities),
  263. [this, category](const AZStd::string& entityName)
  264. {
  265. return m_categoryToNames.at(category).contains(entityName);
  266. });
  267. }
  268. }
  269. return entities;
  270. }
  271. AZStd::vector<AZStd::string> SimulationEntitiesManager::FilterEntitiesByTag(
  272. const AZStd::vector<AZStd::string>& prefilteredEntities, const TagFilter& tagFilter)
  273. {
  274. AZStd::vector<AZStd::string> entities;
  275. entities.reserve(prefilteredEntities.size());
  276. for (const auto& name : prefilteredEntities)
  277. {
  278. // if entity doesn't have entity info it cannot be filtered by tag so it should be skipped
  279. auto findIt = m_nameToEntityInfo.find(name);
  280. if (findIt == m_nameToEntityInfo.end())
  281. {
  282. continue;
  283. }
  284. // get entity tags
  285. if (Utils::AreTagsMatching(tagFilter, findIt->second.m_tags))
  286. {
  287. entities.push_back(name);
  288. }
  289. }
  290. return entities;
  291. }
  292. AZ::Outcome<AZStd::vector<AZStd::string>, FailedResult> SimulationEntitiesManager::FilterEntitiesByBounds(
  293. const AZStd::vector<AZStd::string>& prefilteredEntities,
  294. const AZStd::shared_ptr<Physics::ShapeConfiguration> shape,
  295. const AZ::Transform& shapePose)
  296. {
  297. auto* sceneInterface = AZ::Interface<AzPhysics::SceneInterface>::Get();
  298. AZ_Assert(sceneInterface, "Physics scene interface is not available.");
  299. if (m_physicsScenesHandle == AzPhysics::InvalidSceneHandle)
  300. {
  301. return AZ::Failure(
  302. FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, "Physics scene interface is not available."));
  303. }
  304. AzPhysics::OverlapRequest request;
  305. request.m_shapeConfiguration = shape;
  306. request.m_pose = shapePose;
  307. request.m_maxResults = AZStd::numeric_limits<AZ::u32>::max();
  308. AzPhysics::SceneQueryHits result = sceneInterface->QueryScene(m_physicsScenesHandle, &request);
  309. AZStd::vector<AZStd::string> entities;
  310. entities.reserve(prefilteredEntities.size());
  311. for (const auto& name : prefilteredEntities)
  312. {
  313. const auto& entityId = m_simulatedEntityToEntityIdMap.at(name);
  314. AZ::Outcome<AzPhysics::SimulatedBody*, AZStd::string> simulatedBody = Utils::GetSimulatedBody(entityId);
  315. if (simulatedBody.IsSuccess())
  316. {
  317. auto rigidBody = azdynamic_cast<AzPhysics::RigidBody*>(simulatedBody.GetValue());
  318. // entity is simulated body and has collider, check overlap
  319. if (rigidBody && rigidBody->GetShapeCount() > 0)
  320. {
  321. // perform relatively expensive search only for entities which really can be inside the shape
  322. if (AZStd::ranges::contains(result.m_hits, entityId, &AzPhysics::SceneQueryHit::m_entityId))
  323. {
  324. entities.push_back(name);
  325. }
  326. // no matter of the results skip the rest of the loop since it is related to worldTM check
  327. continue;
  328. }
  329. }
  330. // for non physical or no-colliding entities check if World TM is inside the control shape
  331. AZ::Vector3 worldTranslation;
  332. AZ::TransformBus::EventResult(worldTranslation, entityId, &AZ::TransformBus::Events::GetWorldTranslation);
  333. // check if within bounds
  334. if (auto boxShape = dynamic_cast<Physics::BoxShapeConfiguration*>(shape.get()))
  335. {
  336. auto oob = boxShape->ToObb(shapePose);
  337. if (oob.Contains(worldTranslation))
  338. {
  339. entities.push_back(name);
  340. }
  341. }
  342. else if (auto sphereShape = dynamic_cast<Physics::SphereShapeConfiguration*>(shape.get()))
  343. {
  344. auto distance = shapePose.GetTranslation().GetDistance(worldTranslation);
  345. if (distance <= sphereShape->m_radius)
  346. {
  347. entities.push_back(name);
  348. }
  349. }
  350. else
  351. {
  352. AZ_Warning("SimulationInterfaces", false, "Unsupported bounds type, skipped");
  353. }
  354. }
  355. return entities;
  356. }
  357. AZ::Outcome<AZStd::vector<AZStd::string>, FailedResult> SimulationEntitiesManager::FilterEntitiesByRegex(
  358. const AZStd::vector<AZStd::string>& prefilteredEntities, const AZStd::string& nameRegex)
  359. {
  360. AZStd::vector<AZStd::string> entities;
  361. entities.reserve(prefilteredEntities.size());
  362. const AZStd::regex regexSearch(nameRegex, AZStd::regex::extended);
  363. if (!regexSearch.Valid())
  364. {
  365. AZ_Warning("SimulationInterfaces", false, "Invalid regex filter");
  366. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Invalid regex filter"));
  367. }
  368. AZStd::ranges::copy_if(
  369. prefilteredEntities,
  370. AZStd::back_inserter(entities),
  371. [&regexSearch](const AZStd::string& entityName)
  372. {
  373. return AZStd::regex_search(entityName, regexSearch);
  374. });
  375. return entities;
  376. }
  377. AZ::Outcome<EntityNameList, FailedResult> SimulationEntitiesManager::GetEntities(const EntityFilters& filter)
  378. {
  379. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  380. {
  381. return AZ::Failure(outcome.GetError());
  382. }
  383. const bool reFilter = !filter.m_nameFilter.empty();
  384. const bool shapeCastFilter = filter.m_boundsShape != nullptr;
  385. const bool categoriesFilter = !filter.m_entityCategories.empty();
  386. const bool tagFilter = !filter.m_tagsFilter.m_tags.empty();
  387. // get all entities from the map
  388. const auto valueView = AZStd::ranges::views::values(m_entityIdToSimulatedEntityMap);
  389. AZStd::vector<AZStd::string> entities{ valueView.begin(), valueView.end() };
  390. // filter by categories
  391. if (categoriesFilter)
  392. {
  393. entities = FilterEntitiesByCategories(entities, filter.m_entityCategories);
  394. }
  395. // filter based on tag
  396. if (tagFilter)
  397. {
  398. entities = FilterEntitiesByTag(entities, filter.m_tagsFilter);
  399. }
  400. if (shapeCastFilter)
  401. {
  402. auto outcome = FilterEntitiesByBounds(entities, filter.m_boundsShape, filter.m_boundsPose);
  403. if (!outcome.IsSuccess())
  404. {
  405. return AZ::Failure(outcome.GetError());
  406. }
  407. entities = outcome.GetValue();
  408. }
  409. if (reFilter)
  410. {
  411. auto outcome = FilterEntitiesByRegex(entities, filter.m_nameFilter);
  412. if (!outcome.IsSuccess())
  413. {
  414. return AZ::Failure(outcome.GetError());
  415. }
  416. entities = outcome.GetValue();
  417. }
  418. return AZ::Success(entities);
  419. }
  420. AZ::Outcome<EntityState, FailedResult> SimulationEntitiesManager::GetEntityState(const AZStd::string& name)
  421. {
  422. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  423. {
  424. return AZ::Failure(outcome.GetError());
  425. }
  426. const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
  427. if (findIt == m_simulatedEntityToEntityIdMap.end())
  428. {
  429. AZ_Warning("SimulationInterfaces", false, "Entity %s not found", name.c_str());
  430. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found"));
  431. }
  432. EntityState entityState{};
  433. const AZ::EntityId entityId = findIt->second;
  434. AZ_Assert(entityId.IsValid(), "EntityId is not valid");
  435. AZ::TransformBus::EventResult(entityState.m_pose, entityId, &AZ::TransformBus::Events::GetWorldTM);
  436. AZ::Vector3 linearVelocity = AZ::Vector3::CreateZero();
  437. Physics::RigidBodyRequestBus::EventResult(linearVelocity, entityId, &Physics::RigidBodyRequests::GetLinearVelocity);
  438. AZ::Vector3 angularVelocity = AZ::Vector3::CreateZero();
  439. Physics::RigidBodyRequestBus::EventResult(angularVelocity, entityId, &Physics::RigidBodyRequests::GetAngularVelocity);
  440. // transform linear and angular velocities to entity frame
  441. const AZ::Transform entityTransformInv = entityState.m_pose.GetInverse();
  442. entityState.m_twistLinear = entityTransformInv.TransformVector(linearVelocity);
  443. entityState.m_twistAngular = entityTransformInv.TransformVector(angularVelocity);
  444. return AZ::Success(entityState);
  445. }
  446. AZ::Outcome<MultipleEntitiesStates, FailedResult> SimulationEntitiesManager::GetEntitiesStates(const EntityFilters& filter)
  447. {
  448. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  449. {
  450. return AZ::Failure(outcome.GetError());
  451. }
  452. if (!filter.m_tagsFilter.m_tags.empty())
  453. {
  454. AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
  455. return AZ::Failure(
  456. FailedResult(simulation_interfaces::msg::Result::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
  457. }
  458. MultipleEntitiesStates entitiesStates;
  459. const auto& entities = GetEntities(filter);
  460. if (!entities.IsSuccess())
  461. {
  462. return AZ::Failure(entities.GetError());
  463. }
  464. for (const auto& entity : entities.GetValue())
  465. {
  466. auto state = GetEntityState(entity);
  467. if (!state.IsSuccess())
  468. {
  469. return AZ::Failure(state.GetError());
  470. }
  471. entitiesStates.emplace(AZStd::make_pair(entity, state.GetValue()));
  472. }
  473. return entitiesStates;
  474. }
  475. AZ::Outcome<void, FailedResult> SimulationEntitiesManager::SetEntityState(const AZStd::string& name, const EntityState& state)
  476. {
  477. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  478. {
  479. return AZ::Failure(outcome.GetError());
  480. }
  481. const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
  482. if (findIt == m_simulatedEntityToEntityIdMap.end())
  483. {
  484. AZ_Warning("SimulationInterfaces", false, "Entity %s not found", name.c_str());
  485. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found"));
  486. }
  487. const AZ::EntityId entityId = findIt->second;
  488. AZ_Assert(entityId.IsValid(), "EntityId is not valid");
  489. // get entity and all descendants
  490. AZStd::vector<AZ::EntityId> entityAndDescendants;
  491. AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
  492. SetEntitiesState(entityAndDescendants, state);
  493. return AZ::Success();
  494. }
  495. void SimulationEntitiesManager::SetEntitiesState(const AZStd::vector<AZ::EntityId>& entityAndDescendants, const EntityState& state)
  496. {
  497. if (entityAndDescendants.empty())
  498. {
  499. AZ_Error("SimulationInterfaces", false, "Entity and descendants list is empty");
  500. return;
  501. }
  502. const AZ::EntityId entityId = entityAndDescendants.front();
  503. AZ::EntityId parentEntityId = AZ::EntityId{ AZ::EntityId::InvalidEntityId };
  504. AZ::TransformBus::EventResult(parentEntityId, entityId, &AZ::TransformBus::Events::GetParentId);
  505. if (state.m_pose.IsOrthogonal())
  506. {
  507. // disable simulation for all entities
  508. for (const auto& descendant : entityAndDescendants)
  509. {
  510. AzPhysics::SimulatedBodyComponentRequestsBus::Event(descendant, &AzPhysics::SimulatedBodyComponentRequests::DisablePhysics);
  511. }
  512. if (parentEntityId.IsValid())
  513. {
  514. AZ::Transform parentTransform;
  515. AZ::TransformBus::EventResult(parentTransform, parentEntityId, &AZ::TransformBus::Events::GetWorldTM);
  516. float scale = 1.0f;
  517. AZ::TransformBus::EventResult(scale, entityId, &AZ::TransformBus::Events::GetLocalUniformScale);
  518. auto transformToSet = parentTransform.GetInverse() * state.m_pose;
  519. transformToSet.SetUniformScale(scale);
  520. AZ::TransformBus::Event(entityId, &AZ::TransformBus::Events::SetLocalTM, transformToSet);
  521. }
  522. else
  523. {
  524. AZ::TransformBus::Event(entityId, &AZ::TransformBus::Events::SetLocalTM, state.m_pose);
  525. }
  526. for (const auto& descendant : entityAndDescendants)
  527. {
  528. AzPhysics::SimulatedBodyComponentRequestsBus::Event(descendant, &AzPhysics::SimulatedBodyComponentRequests::EnablePhysics);
  529. Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::SetAngularVelocity, AZ::Vector3::CreateZero());
  530. Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::SetLinearVelocity, AZ::Vector3::CreateZero());
  531. }
  532. }
  533. if (!state.m_twistLinear.IsZero(AZ::Constants::FloatEpsilon) || !state.m_twistAngular.IsZero(AZ::Constants::FloatEpsilon))
  534. {
  535. // get rigid body
  536. AzPhysics::RigidBody* rigidBody = nullptr;
  537. Physics::RigidBodyRequestBus::EventResult(rigidBody, entityId, &Physics::RigidBodyRequests::GetRigidBody);
  538. if (rigidBody != nullptr)
  539. {
  540. SetRigidBodyVelocities(rigidBody, state);
  541. }
  542. }
  543. }
  544. void SimulationEntitiesManager::DeleteEntity(const AZStd::string& name, DeletionCompletedCb completedCb)
  545. {
  546. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  547. {
  548. completedCb(AZ::Failure(outcome.GetError()));
  549. return;
  550. }
  551. const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
  552. if (findIt == m_simulatedEntityToEntityIdMap.end())
  553. {
  554. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found")));
  555. return;
  556. }
  557. const AZ::EntityId entityId = findIt->second;
  558. AZ_Assert(entityId.IsValid(), "EntityId is not valid");
  559. // get entity
  560. AZ::Entity* entity = nullptr;
  561. AZ::ComponentApplicationBus::BroadcastResult(entity, &AZ::ComponentApplicationRequests::FindEntity, entityId);
  562. AZ_Assert(entity, "Entity is not available.");
  563. if (entity == nullptr)
  564. {
  565. AZ_Error("SimulationInterfaces", false, "Entity %s (%s) not found", name.c_str(), entityId.ToString().c_str());
  566. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found")));
  567. return;
  568. }
  569. // check if entity is spawned by this component
  570. const auto ticketId = entity->GetEntitySpawnTicketId();
  571. if (m_spawnedTickets.find(ticketId) != m_spawnedTickets.end())
  572. {
  573. // get spawner
  574. auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
  575. AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
  576. // get ticket
  577. auto ticket = m_spawnedTickets[ticketId];
  578. // remove ticket
  579. AzFramework::DespawnAllEntitiesOptionalArgs optionalArgs;
  580. optionalArgs.m_completionCallback = [this, completedCb, name](AzFramework::EntitySpawnTicket::Id ticketId)
  581. {
  582. m_spawnedTickets.erase(ticketId);
  583. UnregisterSimulatedBody(name);
  584. completedCb(AZ::Success());
  585. };
  586. spawner->DespawnAllEntities(ticket, optionalArgs);
  587. }
  588. else
  589. {
  590. UnregisterSimulatedBody(name);
  591. const auto msg = AZStd::string::format(
  592. "Entity %s was not spawned by this component, wont delete it but name will be removed from registry immediately",
  593. name.c_str());
  594. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg)));
  595. }
  596. }
  597. void SimulationEntitiesManager::DeleteAllEntities(DeletionCompletedCb completedCb)
  598. {
  599. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  600. {
  601. completedCb(AZ::Failure(outcome.GetError()));
  602. return;
  603. }
  604. if (m_spawnedTickets.empty())
  605. {
  606. // early return for empty scene
  607. completedCb(AZ::Success());
  608. return;
  609. }
  610. // clear collected data about simulated entities
  611. m_entityIdToSimulatedEntityMap.clear();
  612. m_simulatedEntityToEntityIdMap.clear();
  613. m_simulatedEntityToPrefabRoot.clear();
  614. m_entityIdToInitialState.clear();
  615. m_nameToEntityInfo.clear();
  616. m_categoryToNames.clear();
  617. for (auto m_spawnedTicket : m_spawnedTickets)
  618. {
  619. auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
  620. AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
  621. // get ticket
  622. auto ticket = m_spawnedTickets[m_spawnedTicket.first];
  623. // despawn
  624. AzFramework::DespawnAllEntitiesOptionalArgs optionalArgs;
  625. optionalArgs.m_completionCallback = [this, completedCb](AzFramework::EntitySpawnTicket::Id ticketId)
  626. {
  627. m_spawnedTickets.erase(ticketId);
  628. if (completedCb && m_spawnedTickets.empty())
  629. {
  630. completedCb(AZ::Success());
  631. }
  632. };
  633. spawner->DespawnAllEntities(ticket, optionalArgs);
  634. }
  635. }
  636. AZ::Outcome<SpawnableList, FailedResult> SimulationEntitiesManager::GetSpawnables()
  637. {
  638. AZStd::vector<Spawnable> spawnables;
  639. const auto enumCallback = [&spawnables](const AZ::Data::AssetId assetId, const AZ::Data::AssetInfo& assetInfo)
  640. {
  641. bool isSpawnable = false;
  642. AZ::Data::AssetCatalogRequestBus::BroadcastResult(
  643. isSpawnable, &AZ::Data::AssetCatalogRequests::DoesAssetIdMatchWildcardPattern, assetId, "*.spawnable");
  644. if (isSpawnable)
  645. {
  646. Spawnable spawnable;
  647. spawnable.m_uri = Utils::RelPathToUri(assetInfo.m_relativePath);
  648. spawnables.push_back(spawnable);
  649. }
  650. };
  651. AZ::Data::AssetCatalogRequestBus::Broadcast(&AZ::Data::AssetCatalogRequests::EnumerateAssets, nullptr, enumCallback, nullptr);
  652. return AZ::Success(spawnables);
  653. }
  654. void SimulationEntitiesManager::SpawnEntity(
  655. const AZStd::string& name,
  656. const AZStd::string& uri,
  657. const AZStd::string& entityNamespace,
  658. const AZ::Transform& initialPose,
  659. const bool allowRename,
  660. PreInsertionCb preinsertionCb,
  661. SpawnCompletedCb completedCb)
  662. {
  663. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  664. {
  665. completedCb(AZ::Failure(outcome.GetError()));
  666. return;
  667. }
  668. if (!allowRename)
  669. {
  670. // If API user does not allow renaming, check if name is unique
  671. if (m_simulatedEntityToEntityIdMap.contains(name))
  672. {
  673. const auto msg = AZStd::string::format("Entity name %s is not unique", name.c_str());
  674. completedCb(AZ::Failure(FailedResult(simulation_interfaces::srv::SpawnEntity::Response::NAME_NOT_UNIQUE, msg)));
  675. return;
  676. }
  677. if (name.empty())
  678. {
  679. const auto msg = AZStd::string::format("Entity name is empty");
  680. completedCb(AZ::Failure(FailedResult(simulation_interfaces::srv::SpawnEntity::Response::NAME_INVALID, msg)));
  681. return;
  682. }
  683. }
  684. if (!initialPose.IsOrthogonal())
  685. {
  686. AZ_Warning("SimulationInterfaces", false, "Initial pose is not orthogonal");
  687. completedCb(
  688. AZ::Failure(FailedResult(
  689. simulation_interfaces::srv::SpawnEntity::Response::INVALID_POSE, "Initial pose is not orthogonal"))); // INVALID_POSE
  690. return;
  691. }
  692. // get rel path from uri
  693. const AZStd::string relPath = Utils::UriToRelPath(uri);
  694. // create spawnable
  695. AZ::Data::AssetId assetId;
  696. AZ::Data::AssetCatalogRequestBus::BroadcastResult(
  697. assetId,
  698. &AZ::Data::AssetCatalogRequestBus::Events::GetAssetIdByPath,
  699. relPath.c_str(),
  700. azrtti_typeid<AZ::Data::AssetData>(),
  701. false);
  702. AZ_Warning("SimulationInterfaces", assetId.IsValid(), "AssetId is not valid, relative path %s", relPath.c_str());
  703. auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
  704. AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
  705. AZ::Data::Asset<AzFramework::Spawnable> spawnableAsset =
  706. AZ::Data::AssetManager::Instance().GetAsset<AzFramework::Spawnable>(assetId, AZ::Data::AssetLoadBehavior::NoLoad);
  707. if (!spawnableAsset)
  708. {
  709. const auto msg = AZStd::string::format("Spawnable asset %s not found", uri.c_str());
  710. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, msg)));
  711. return;
  712. }
  713. auto ticket = AzFramework::EntitySpawnTicket(spawnableAsset);
  714. AzFramework::SpawnAllEntitiesOptionalArgs optionalArgs;
  715. optionalArgs.m_preInsertionCallback = [this, initialPose, entityNamespace](auto id, auto view)
  716. {
  717. auto spawnData = m_spawnCompletedCallbacks.find(id);
  718. if (view.empty())
  719. {
  720. if (spawnData != m_spawnCompletedCallbacks.end())
  721. {
  722. spawnData->second.m_preInsertionCb(
  723. AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, "Spawned prefab is empty")));
  724. }
  725. return;
  726. }
  727. AZ::Entity* root = *view.begin();
  728. for (auto* entity : view)
  729. {
  730. ROS2::ROS2FrameComponent* frameComponent = entity->template FindComponent<ROS2::ROS2FrameComponent>();
  731. if (frameComponent)
  732. {
  733. const AZStd::string f = frameComponent->GetNamespacedFrameID();
  734. auto config = frameComponent->GetConfiguration();
  735. config.m_namespaceConfiguration.m_customNamespace = entityNamespace;
  736. config.m_namespaceConfiguration.m_namespaceStrategy = ROS2::NamespaceConfiguration::NamespaceStrategy::Custom;
  737. AZ_Printf("SimulationInterfaces::SpawnEntity", "Setting namespace to %s for entity %s\n", entityNamespace.c_str(), entity->GetName().c_str());
  738. frameComponent->SetConfiguration(config);
  739. break;
  740. }
  741. }
  742. auto* transformInterface = root->FindComponent<AzFramework::TransformComponent>();
  743. if (transformInterface)
  744. {
  745. transformInterface->SetWorldTM(initialPose);
  746. }
  747. // run preinsertion Callback if exists
  748. if (spawnData != m_spawnCompletedCallbacks.end())
  749. {
  750. spawnData->second.m_preInsertionCb(AZ::Success(view));
  751. }
  752. };
  753. optionalArgs.m_completionCallback =
  754. [this](AzFramework::EntitySpawnTicket::Id ticketId, AzFramework::SpawnableConstEntityContainerView view)
  755. {
  756. const AZ::Entity* root = *view.begin();
  757. AZ::EntityId trackingEntity{ AZ::EntityId::InvalidEntityId };
  758. // find first physical entity to set as tracking entity. If none of physical entity was found, set root as tracking entity
  759. // if spawned prefab has tracking tag on any of the entities, force tracking entity owning the tag
  760. for (const auto* entity : view)
  761. {
  762. // check if entity is physical entity == check if it is simulated body, if so get first occurrence
  763. AzPhysics::SimulatedBody* simBody = nullptr;
  764. AzPhysics::SimulatedBodyComponentRequestsBus::EventResult(
  765. simBody, entity->GetId(), &AzPhysics::SimulatedBodyComponentRequests::GetSimulatedBody);
  766. if ((!trackingEntity.IsValid() && simBody != nullptr) &&
  767. (simBody->GetNativeType() == RigidBody || simBody->GetNativeType() == RigidBodyStatic ||
  768. simBody->GetNativeType() == ArticulationLink))
  769. {
  770. trackingEntity = entity->GetId();
  771. break;
  772. }
  773. }
  774. if (!trackingEntity.IsValid()) // physical entity was not found, assign root instead
  775. {
  776. trackingEntity = root->GetId();
  777. }
  778. auto spawnData = m_spawnCompletedCallbacks.find(ticketId);
  779. if (spawnData != m_spawnCompletedCallbacks.end())
  780. {
  781. auto finalNameOutcome = RegisterNewSimulatedBody(spawnData->second.m_userProposedName, trackingEntity);
  782. if (finalNameOutcome.IsSuccess())
  783. {
  784. m_simulatedEntityToPrefabRoot[finalNameOutcome.GetValue()] = root->GetId();
  785. spawnData->second.m_completedCb(AZ::Success(finalNameOutcome.GetValue()));
  786. }
  787. else
  788. {
  789. spawnData->second.m_completedCb(AZ::Failure(FailedResult(
  790. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, "Failed to spawn/or register simulation entity")));
  791. }
  792. m_spawnCompletedCallbacks.erase(spawnData);
  793. }
  794. };
  795. spawner->SpawnAllEntities(ticket, optionalArgs);
  796. auto ticketId = ticket.GetId();
  797. SpawnCompletedCbData data;
  798. // to ensure that callbacks are valid
  799. data.m_completedCb = completedCb ? completedCb : SpawnCompletedCb{};
  800. data.m_preInsertionCb = preinsertionCb ? preinsertionCb : PreInsertionCb{};
  801. data.m_userProposedName = name;
  802. m_spawnCompletedCallbacks[ticketId] = data;
  803. m_spawnedTickets[ticketId] = ticket;
  804. AZ_Info("SimulationInterfaces", "Spawning uri %s with ticket id %d\n", uri.c_str(), ticketId);
  805. }
  806. AZStd::string SimulationEntitiesManager::GetSimulatedEntityName(AZ::EntityId entityId, const AZStd::string& proposedName) const
  807. {
  808. // Get O3DE entity name
  809. AZStd::string newName = proposedName;
  810. // check if name is not unique. If not, add Entity Name to name
  811. if (m_simulatedEntityToEntityIdMap.contains(newName))
  812. {
  813. AZStd::string entityName;
  814. AZ::ComponentApplicationBus::BroadcastResult(entityName, &AZ::ComponentApplicationRequests::GetEntityName, entityId);
  815. // name is not unique, add entityId to name
  816. newName = AZStd::string::format("%s_%s", newName.c_str(), entityName.c_str());
  817. }
  818. // check if name is still not unique, if not, add EntityId to name
  819. if (m_simulatedEntityToEntityIdMap.contains(newName))
  820. {
  821. newName = AZStd::string::format("%s_%s", newName.c_str(), entityId.ToString().c_str());
  822. }
  823. return newName;
  824. }
  825. AZ::Outcome<void, FailedResult> SimulationEntitiesManager::ResetAllEntitiesToInitialState()
  826. {
  827. if (auto outcome = IsWorldLoaded(); !outcome.IsSuccess())
  828. {
  829. return AZ::Failure(outcome.GetError());
  830. }
  831. for (const auto& [entityId, initialState] : m_entityIdToInitialState)
  832. {
  833. AZStd::vector<AZ::EntityId> entityAndDescendants;
  834. AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
  835. SetEntitiesState(entityAndDescendants, initialState);
  836. }
  837. return AZ::Success();
  838. }
  839. AZ::Outcome<void, FailedResult> SimulationEntitiesManager::IsWorldLoaded()
  840. {
  841. bool canOperate = false;
  842. SimulationManagerRequestBus::BroadcastResult(canOperate, &SimulationManagerRequests::EntitiesOperationsPossible);
  843. if (!canOperate)
  844. {
  845. return AZ::Failure(FailedResult(
  846. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  847. "Simulator needs to have loaded world to allow entities manipulation"));
  848. }
  849. return AZ::Success();
  850. }
  851. AZ::Outcome<void, SimulationInterfaces::FailedResult> SimulationEntitiesManager::SetEntityInfo(
  852. const AZStd::string& name, const EntityInfo& info)
  853. {
  854. if (!m_simulatedEntityToEntityIdMap.contains(name))
  855. {
  856. return AZ::Failure(SimulationInterfaces::FailedResult(
  857. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  858. AZStd::string::format("Entity with given name \"%s\" doesn't exists", name.c_str())));
  859. }
  860. // check if entity with given name has entity info assigned, clear it if needed
  861. RemoveEntityInfoIfNeeded(name);
  862. // add to cache storing entityInfo by name. it is ensured that name is deleted if it already exists
  863. m_nameToEntityInfo.insert({ name, info });
  864. // assign entity name to category
  865. // if set is not created yet, create it
  866. if (!m_categoryToNames.contains(info.m_category))
  867. {
  868. m_categoryToNames.emplace(info.m_category, AZStd::unordered_set<AZStd::string>{});
  869. }
  870. m_categoryToNames.at(info.m_category).insert(name);
  871. return AZ::Success();
  872. }
  873. AZ::Outcome<EntityInfo, SimulationInterfaces::FailedResult> SimulationEntitiesManager::GetEntityInfo(const AZStd::string& name)
  874. {
  875. if (!m_simulatedEntityToEntityIdMap.contains(name))
  876. {
  877. return AZ::Failure(SimulationInterfaces::FailedResult(
  878. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  879. AZStd::string::format("Entity with given name \"%s\" doesn't exists", name.c_str())));
  880. }
  881. auto findIt = m_nameToEntityInfo.find(name);
  882. if (findIt == m_nameToEntityInfo.end())
  883. {
  884. const auto msg = AZStd::string::format("Entity with given name \"%s\" doesn't have assigned EntityInfo", name.c_str());
  885. AZ_Warning("SpawnableSceneProviderSystemComponent", false, msg.c_str());
  886. return AZ::Failure(SimulationInterfaces::FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg));
  887. }
  888. return AZ::Success(findIt->second);
  889. }
  890. void SimulationEntitiesManager::RemoveEntityInfoIfNeeded(const AZStd::string& name)
  891. {
  892. // if deleted entity had assigned entity info, remove it
  893. if (m_nameToEntityInfo.contains(name))
  894. {
  895. auto info = m_nameToEntityInfo.at(name);
  896. m_nameToEntityInfo.erase(name);
  897. // if entity Info is added, entity name is added to category to name map, lack of this entity in this map is clearly a bug
  898. AZ_Assert(m_categoryToNames.contains(info.m_category), "Failed to get entities with category %d", info.m_category);
  899. m_categoryToNames.at(info.m_category).erase(name);
  900. }
  901. }
  902. AZ::Outcome<Bounds, FailedResult> SimulationEntitiesManager::GetEntityBounds(const AZStd::string& name)
  903. {
  904. if (!m_simulatedEntityToEntityIdMap.contains(name))
  905. {
  906. return AZ::Failure(SimulationInterfaces::FailedResult(
  907. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  908. AZStd::string::format("Entity with given name \"%s\" doesn't exists", name.c_str())));
  909. }
  910. auto simulatedBodyOutcome = Utils::GetSimulatedBody(m_simulatedEntityToEntityIdMap.at(name));
  911. if (!simulatedBodyOutcome.IsSuccess())
  912. {
  913. return AZ::Success(Bounds{ 0, {} });
  914. }
  915. auto rigidBody = azdynamic_cast<AzPhysics::RigidBody*>(simulatedBodyOutcome.GetValue());
  916. if (!rigidBody)
  917. {
  918. return AZ::Success(Bounds{ 0, {} });
  919. }
  920. if (rigidBody->GetShapeCount() == 0)
  921. {
  922. return AZ::Failure(FailedResult(
  923. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, "Entity doesn't have colliders/boundss to return"));
  924. }
  925. AZ_Warning(
  926. "Simulation Interfaces",
  927. rigidBody->GetShapeCount() == 1,
  928. "Entity Bounds in simulation interfaces doesn't support multiple shapes, only first one will be taken ");
  929. auto shape = rigidBody->GetShape(0);
  930. auto boundsOutput = Utils::ConvertPhysicalShapeToBounds(shape, m_simulatedEntityToEntityIdMap.at(name));
  931. if (boundsOutput.IsSuccess())
  932. {
  933. return AZ::Success(boundsOutput.GetValue());
  934. }
  935. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, boundsOutput.GetError()));
  936. }
  937. AZ::Outcome<AZ::EntityId, FailedResult> SimulationEntitiesManager::GetEntityId(const AZStd::string& name)
  938. {
  939. if (!m_simulatedEntityToEntityIdMap.contains(name))
  940. {
  941. return AZ::Failure(SimulationInterfaces::FailedResult(
  942. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  943. AZStd::string::format("Entity with given name \"%s\" doesn't exists", name.c_str())));
  944. }
  945. return AZ::Success(m_simulatedEntityToEntityIdMap.at(name));
  946. }
  947. AZ::Outcome<AZ::EntityId, FailedResult> SimulationEntitiesManager::GetEntityRoot(const AZStd::string& name)
  948. {
  949. if (!m_simulatedEntityToPrefabRoot.contains(name))
  950. {
  951. return AZ::Failure(SimulationInterfaces::FailedResult(
  952. simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED,
  953. AZStd::string::format("Entity with given name \"%s\" doesn't exists in available cache of prefab roots", name.c_str())));
  954. }
  955. return AZ::Success(m_simulatedEntityToPrefabRoot.at(name));
  956. }
  957. } // namespace SimulationInterfaces