2
0

SimulationEntitiesManager.cpp 35 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791
  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 <Clients/SimulationFeaturesAggregator.h>
  10. #include <SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h>
  11. #include <SimulationInterfaces/SimulationInterfacesTypeIds.h>
  12. #include "CommonUtilities.h"
  13. #include <AzCore/Asset/AssetManager.h>
  14. #include <AzCore/Asset/AssetManagerBus.h>
  15. #include <AzCore/Component/ComponentApplicationBus.h>
  16. #include <AzCore/Component/TransformBus.h>
  17. #include <AzCore/Console/IConsole.h>
  18. #include <AzCore/Serialization/SerializeContext.h>
  19. #include <AzCore/Settings/SettingsRegistry.h>
  20. #include <AzCore/std/containers/vector.h>
  21. #include <AzCore/std/string/regex.h>
  22. #include <AzFramework/Components/TransformComponent.h>
  23. #include <AzFramework/Physics/PhysicsSystem.h>
  24. #include <AzFramework/Physics/RigidBodyBus.h>
  25. #include <AzFramework/Physics/SimulatedBodies/RigidBody.h>
  26. #include <AzFramework/Spawnable/Spawnable.h>
  27. #include <AzFramework/Spawnable/SpawnableEntitiesInterface.h>
  28. #include <ROS2/Frame/ROS2FrameComponent.h>
  29. #include <simulation_interfaces/msg/result.hpp>
  30. #include <simulation_interfaces/msg/simulator_features.hpp>
  31. #include <simulation_interfaces/srv/spawn_entity.hpp>
  32. namespace SimulationInterfaces
  33. {
  34. namespace
  35. {
  36. void SetRigidBodyVelocities(AzPhysics::RigidBody* rigidBody, const EntityState& state)
  37. {
  38. if (!state.m_twistAngular.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
  39. {
  40. // get transform
  41. AZ::Vector3 angularVelWorld = rigidBody->GetTransform().TransformVector(state.m_twistAngular);
  42. rigidBody->SetAngularVelocity(angularVelWorld);
  43. }
  44. if (!state.m_twistLinear.IsClose(AZ::Vector3::CreateZero(), AZ::Constants::FloatEpsilon))
  45. {
  46. // get transform
  47. AZ::Vector3 linearVelWorld = rigidBody->GetTransform().TransformVector(state.m_twistLinear);
  48. rigidBody->SetLinearVelocity(linearVelWorld);
  49. }
  50. }
  51. AzPhysics::Scene* GetSceneHelper(AzPhysics::SceneHandle sceneHandle)
  52. {
  53. AzPhysics::SystemInterface* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
  54. AZ_Assert(physicsSystem, "Physics system is not available.");
  55. AzPhysics::Scene* scene = physicsSystem->GetScene(sceneHandle);
  56. return scene;
  57. }
  58. } // namespace
  59. AZ_COMPONENT_IMPL(SimulationEntitiesManager, "SimulationEntitiesManager", SimulationEntitiesManagerTypeId);
  60. void SimulationEntitiesManager::Reflect(AZ::ReflectContext* context)
  61. {
  62. if (auto serializeContext = azrtti_cast<AZ::SerializeContext*>(context))
  63. {
  64. serializeContext->Class<SimulationEntitiesManager, AZ::Component>()->Version(0);
  65. }
  66. }
  67. void SimulationEntitiesManager::GetProvidedServices(AZ::ComponentDescriptor::DependencyArrayType& provided)
  68. {
  69. provided.push_back(AZ_CRC_CE("SimulationInterfacesService"));
  70. }
  71. void SimulationEntitiesManager::GetIncompatibleServices(AZ::ComponentDescriptor::DependencyArrayType& incompatible)
  72. {
  73. incompatible.push_back(AZ_CRC_CE("SimulationInterfacesService"));
  74. }
  75. void SimulationEntitiesManager::GetRequiredServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& required)
  76. {
  77. required.push_back(AZ_CRC_CE("AssetCatalogService"));
  78. required.push_back(AZ_CRC_CE("SimulationFeaturesAggregator"));
  79. }
  80. void SimulationEntitiesManager::GetDependentServices([[maybe_unused]] AZ::ComponentDescriptor::DependencyArrayType& dependent)
  81. {
  82. dependent.push_back(AZ_CRC_CE("PhysicsService"));
  83. dependent.push_back(AZ_CRC_CE("SimulationFeaturesAggregator"));
  84. }
  85. SimulationEntitiesManager::SimulationEntitiesManager()
  86. {
  87. if (SimulationEntityManagerInterface::Get() == nullptr)
  88. {
  89. SimulationEntityManagerInterface::Register(this);
  90. }
  91. }
  92. SimulationEntitiesManager::~SimulationEntitiesManager()
  93. {
  94. if (SimulationEntityManagerInterface::Get() == this)
  95. {
  96. SimulationEntityManagerInterface::Unregister(this);
  97. }
  98. }
  99. bool SimulationEntitiesManager::RegisterNewSimulatedBody(AzPhysics::SceneHandle sceneHandle, AzPhysics::SimulatedBodyHandle bodyHandle)
  100. {
  101. auto* scene = GetSceneHelper(sceneHandle);
  102. AZ_Assert(scene, "Scene is not available.");
  103. if (scene == nullptr)
  104. {
  105. return false;
  106. }
  107. auto* body = scene->GetSimulatedBodyFromHandle(bodyHandle);
  108. if (body == nullptr)
  109. {
  110. AZ_Trace("SimulationInterfaces", "Simulated body pointer is not valid");
  111. return false;
  112. }
  113. auto* rigidBody = azdynamic_cast<AzPhysics::RigidBody*>(body);
  114. if (rigidBody != nullptr)
  115. {
  116. [[maybe_unused]] auto shapeCount = rigidBody->GetShapeCount();
  117. AZ_Warning(
  118. "SimulationInterfaces",
  119. shapeCount > 0,
  120. "Entity %s has no collider shapes, it won't be available by bound search",
  121. rigidBody->GetEntityId().ToString().c_str());
  122. }
  123. const AZ::EntityId entityId = body->GetEntityId();
  124. if (!entityId.IsValid())
  125. {
  126. AZ_Trace("SimulationInterfaces", "EntityId is not valid");
  127. return false;
  128. }
  129. AZ::Entity* entity = nullptr;
  130. AZ::ComponentApplicationBus::BroadcastResult(entity, &AZ::ComponentApplicationRequests::FindEntity, entityId);
  131. if (entity == nullptr)
  132. {
  133. AZ_Trace("SimulationInterfaces", "Entity pointer is not valid");
  134. return false;
  135. }
  136. // check if entity is not spawned by this component
  137. const auto ticketId = entity->GetEntitySpawnTicketId();
  138. auto spawnDataIt = m_spawnCompletedCallbacks.find(ticketId);
  139. const bool wasSpawned = spawnDataIt != m_spawnCompletedCallbacks.end();
  140. const AZStd::string proposedName = wasSpawned ? spawnDataIt->second.m_userProposedName : entity->GetName();
  141. // register entity
  142. const AZStd::string registeredName = this->AddSimulatedEntity(entityId, proposedName);
  143. // cache registered name for later use in SpawnCompletionCallback
  144. if (wasSpawned && !spawnDataIt->second.m_registered)
  145. {
  146. spawnDataIt->second.m_registered = true;
  147. spawnDataIt->second.m_resultedName = registeredName;
  148. }
  149. // cache the initial state - for simulator reset with SCOPE_STATE.
  150. EntityState initialState{};
  151. initialState.m_pose = entity->GetTransform()->GetWorldTM();
  152. if (rigidBody)
  153. {
  154. initialState.m_twistLinear = rigidBody->GetLinearVelocity();
  155. initialState.m_twistAngular = rigidBody->GetAngularVelocity();
  156. }
  157. m_entityIdToInitialState[entityId] = initialState;
  158. AZ_Info("SimulationInterfaces", "Registered entity %s\n", registeredName.c_str());
  159. return true;
  160. }
  161. AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>> SimulationEntitiesManager::
  162. RegisterNewSimulatedBodies(const AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>>& handles)
  163. {
  164. AZStd::vector<AZStd::pair<AzPhysics::SceneHandle, AzPhysics::SimulatedBodyHandle>> unconfiguredHandles;
  165. for (const auto& handle : handles)
  166. {
  167. if (!RegisterNewSimulatedBody(handle.first, handle.second))
  168. {
  169. unconfiguredHandles.push_back(handle);
  170. }
  171. }
  172. return unconfiguredHandles;
  173. }
  174. void SimulationEntitiesManager::Activate()
  175. {
  176. m_simulationBodyAddedHandler = AzPhysics::SceneEvents::OnSimulationBodyAdded::Handler(
  177. [this](AzPhysics::SceneHandle sceneHandle, AzPhysics::SimulatedBodyHandle bodyHandle)
  178. {
  179. m_unconfiguredScenesHandles.push_back(AZStd::make_pair(sceneHandle, bodyHandle));
  180. m_unconfiguredScenesHandles = RegisterNewSimulatedBodies(m_unconfiguredScenesHandles);
  181. });
  182. m_simulationBodyRemovedHandler = AzPhysics::SceneEvents::OnSimulationBodyRemoved::Handler(
  183. [this](AzPhysics::SceneHandle sceneHandle, AzPhysics::SimulatedBodyHandle bodyHandle)
  184. {
  185. auto* scene = GetSceneHelper(sceneHandle);
  186. if (scene == nullptr)
  187. {
  188. return;
  189. }
  190. const auto* body = scene->GetSimulatedBodyFromHandle(bodyHandle);
  191. AZ_Assert(body, "Simulated body is not available.");
  192. const AZ::EntityId entityId = body->GetEntityId();
  193. // remove simulated entity
  194. this->RemoveSimulatedEntity(entityId);
  195. });
  196. m_sceneAddedHandler = AzPhysics::SystemEvents::OnSceneAddedEvent::Handler(
  197. [this](AzPhysics::SceneHandle sceneHandle)
  198. {
  199. AZ_Warning(
  200. "SimulationInterfaces",
  201. m_physicsScenesHandle == AzPhysics::InvalidSceneHandle,
  202. "SimulationInterfaces already gathered physics scene");
  203. auto* scene = GetSceneHelper(sceneHandle);
  204. AZ_Assert(scene, "Scene is not available.");
  205. if (scene == nullptr)
  206. {
  207. return;
  208. }
  209. scene->RegisterSimulationBodyAddedHandler(m_simulationBodyAddedHandler);
  210. scene->RegisterSimulationBodyRemovedHandler(m_simulationBodyRemovedHandler);
  211. AZ_Printf("SimulationInterfaces", "Registered simulation body added handler\n");
  212. m_physicsScenesHandle = sceneHandle;
  213. });
  214. m_sceneRemovedHandler = AzPhysics::SystemEvents::OnSceneRemovedEvent::Handler(
  215. [this](AzPhysics::SceneHandle sceneHandle)
  216. {
  217. if (m_physicsScenesHandle == sceneHandle)
  218. {
  219. m_entityIdToSimulatedEntityMap.clear();
  220. m_simulatedEntityToEntityIdMap.clear();
  221. m_simulationBodyAddedHandler.Disconnect();
  222. m_simulationBodyRemovedHandler.Disconnect();
  223. m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
  224. }
  225. });
  226. AzPhysics::SystemInterface* physicsSystem = AZ::Interface<AzPhysics::SystemInterface>::Get();
  227. if (physicsSystem)
  228. {
  229. physicsSystem->RegisterSceneAddedEvent(m_sceneAddedHandler);
  230. physicsSystem->RegisterSceneRemovedEvent(m_sceneRemovedHandler);
  231. SimulationEntityManagerRequestBus::Handler::BusConnect();
  232. }
  233. SimulationFeaturesAggregatorRequestBus::Broadcast(
  234. &SimulationFeaturesAggregatorRequests::AddSimulationFeatures,
  235. AZStd::unordered_set<SimulationFeatureType>{
  236. // not implemented: simulation_interfaces::msg::SimulatorFeatures::ENTITY_TAGS,
  237. simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_BOX,
  238. // not implemented: simulation_interfaces::msg::SimulatorFeatures::ENTITY_BOUNDS_CONVEX,
  239. // not implemented: simulation_interfaces::msg::SimulatorFeatures::ENTITY_CATEGORIES,
  240. simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_GETTING,
  241. simulation_interfaces::msg::SimulatorFeatures::ENTITY_STATE_SETTING,
  242. simulation_interfaces::msg::SimulatorFeatures::DELETING,
  243. simulation_interfaces::msg::SimulatorFeatures::SPAWNABLES,
  244. simulation_interfaces::msg::SimulatorFeatures::SPAWNING });
  245. AZ::TickBus::Handler::BusConnect();
  246. }
  247. void SimulationEntitiesManager::Deactivate()
  248. {
  249. AZ::TickBus::Handler::BusDisconnect();
  250. SimulationEntityManagerRequestBus::Handler::BusDisconnect();
  251. m_simulationBodyAddedHandler.Disconnect();
  252. m_simulationBodyRemovedHandler.Disconnect();
  253. m_physicsScenesHandle = AzPhysics::InvalidSceneHandle;
  254. m_sceneAddedHandler.Disconnect();
  255. m_sceneRemovedHandler.Disconnect();
  256. m_unconfiguredScenesHandles.clear();
  257. m_entityIdToSimulatedEntityMap.clear();
  258. m_simulatedEntityToEntityIdMap.clear();
  259. m_entityIdToInitialState.clear();
  260. m_spawnedTickets.clear();
  261. }
  262. AZStd::string SimulationEntitiesManager::AddSimulatedEntity(AZ::EntityId entityId, const AZStd::string& userProposedName)
  263. {
  264. if (!entityId.IsValid())
  265. {
  266. return "";
  267. }
  268. // check if entity is already registered
  269. auto findIt = m_entityIdToSimulatedEntityMap.find(entityId);
  270. if (findIt != m_entityIdToSimulatedEntityMap.end())
  271. {
  272. return findIt->second;
  273. }
  274. // register entity under unique name
  275. AZStd::string simulatedEntityName = GetSimulatedEntityName(entityId, userProposedName);
  276. m_simulatedEntityToEntityIdMap[simulatedEntityName] = entityId;
  277. m_entityIdToSimulatedEntityMap[entityId] = simulatedEntityName;
  278. return simulatedEntityName;
  279. }
  280. void SimulationEntitiesManager::RemoveSimulatedEntity(AZ::EntityId entityId)
  281. {
  282. if (auto findIt = m_entityIdToSimulatedEntityMap.find(entityId); findIt != m_entityIdToSimulatedEntityMap.end())
  283. {
  284. const auto& simulatedEntityName = findIt->second;
  285. m_entityIdToSimulatedEntityMap.erase(findIt);
  286. m_simulatedEntityToEntityIdMap.erase(simulatedEntityName);
  287. }
  288. if (auto findIt = m_entityIdToInitialState.find(entityId); findIt != m_entityIdToInitialState.end())
  289. {
  290. m_entityIdToInitialState.erase(findIt);
  291. }
  292. }
  293. AZ::Outcome<EntityNameList, FailedResult> SimulationEntitiesManager::GetEntities(const EntityFilters& filter)
  294. {
  295. if (!filter.m_tagsFilter.m_tags.empty())
  296. {
  297. AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
  298. return AZ::Failure(
  299. FailedResult(simulation_interfaces::msg::Result::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
  300. }
  301. const bool reFilter = !filter.m_nameFilter.empty();
  302. const bool shapeCastFilter = filter.m_boundsShape != nullptr;
  303. AZStd::vector<AZStd::string> entities;
  304. if (!shapeCastFilter)
  305. {
  306. // get all entities from the map
  307. entities.reserve(m_entityIdToSimulatedEntityMap.size());
  308. AZStd::transform(
  309. m_entityIdToSimulatedEntityMap.begin(),
  310. m_entityIdToSimulatedEntityMap.end(),
  311. AZStd::back_inserter(entities),
  312. [](const auto& pair)
  313. {
  314. return pair.second;
  315. });
  316. }
  317. else
  318. {
  319. auto* sceneInterface = AZ::Interface<AzPhysics::SceneInterface>::Get();
  320. AZ_Assert(sceneInterface, "Physics scene interface is not available.");
  321. if (m_physicsScenesHandle == AzPhysics::InvalidSceneHandle)
  322. {
  323. return AZ::Failure(
  324. FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, "Physics scene interface is not available."));
  325. }
  326. AzPhysics::OverlapRequest request;
  327. request.m_shapeConfiguration = filter.m_boundsShape;
  328. request.m_pose = filter.m_boundsPose;
  329. request.m_maxResults = AZStd::numeric_limits<AZ::u32>::max();
  330. AzPhysics::SceneQueryHits result = sceneInterface->QueryScene(m_physicsScenesHandle, &request);
  331. for (const auto& hit : result.m_hits)
  332. {
  333. const AZ::EntityId entityId = hit.m_entityId;
  334. if (auto findIt = m_entityIdToSimulatedEntityMap.find(entityId); findIt != m_entityIdToSimulatedEntityMap.end())
  335. {
  336. entities.push_back(findIt->second);
  337. }
  338. }
  339. }
  340. if (reFilter)
  341. {
  342. const AZStd::vector<AZStd::string> prefilteredEntities = AZStd::move(entities);
  343. entities.clear();
  344. const AZStd::regex regex(filter.m_nameFilter, AZStd::regex::extended);
  345. if (!regex.Valid())
  346. {
  347. AZ_Warning("SimulationInterfaces", false, "Invalid regex filter");
  348. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Invalid regex filter"));
  349. }
  350. AZStd::ranges::copy_if(
  351. prefilteredEntities,
  352. AZStd::back_inserter(entities),
  353. [&regex](const AZStd::string& entityName)
  354. {
  355. return AZStd::regex_search(entityName, regex);
  356. });
  357. }
  358. return AZ::Success(entities);
  359. }
  360. AZ::Outcome<EntityState, FailedResult> SimulationEntitiesManager::GetEntityState(const AZStd::string& name)
  361. {
  362. const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
  363. if (findIt == m_simulatedEntityToEntityIdMap.end())
  364. {
  365. AZ_Warning("SimulationInterfaces", false, "Entity %s not found", name.c_str());
  366. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found"));
  367. }
  368. EntityState entityState{};
  369. const AZ::EntityId entityId = findIt->second;
  370. AZ_Assert(entityId.IsValid(), "EntityId is not valid");
  371. AZ::TransformBus::EventResult(entityState.m_pose, entityId, &AZ::TransformBus::Events::GetWorldTM);
  372. AZ::Vector3 linearVelocity = AZ::Vector3::CreateZero();
  373. Physics::RigidBodyRequestBus::EventResult(linearVelocity, entityId, &Physics::RigidBodyRequests::GetLinearVelocity);
  374. AZ::Vector3 angularVelocity = AZ::Vector3::CreateZero();
  375. Physics::RigidBodyRequestBus::EventResult(angularVelocity, entityId, &Physics::RigidBodyRequests::GetAngularVelocity);
  376. // transform linear and angular velocities to entity frame
  377. const AZ::Transform entityTransformInv = entityState.m_pose.GetInverse();
  378. entityState.m_twistLinear = entityTransformInv.TransformVector(linearVelocity);
  379. entityState.m_twistAngular = entityTransformInv.TransformVector(angularVelocity);
  380. return AZ::Success(entityState);
  381. }
  382. AZ::Outcome<MultipleEntitiesStates, FailedResult> SimulationEntitiesManager::GetEntitiesStates(const EntityFilters& filter)
  383. {
  384. if (!filter.m_tagsFilter.m_tags.empty())
  385. {
  386. AZ_Warning("SimulationInterfaces", false, "Tags filter is not implemented yet");
  387. return AZ::Failure(
  388. FailedResult(simulation_interfaces::msg::Result::RESULT_FEATURE_UNSUPPORTED, "Tags filter is not implemented yet"));
  389. }
  390. MultipleEntitiesStates entitiesStates;
  391. const auto& entities = GetEntities(filter);
  392. if (!entities.IsSuccess())
  393. {
  394. return AZ::Failure(entities.GetError());
  395. }
  396. for (const auto& entity : entities.GetValue())
  397. {
  398. auto state = GetEntityState(entity);
  399. if (!state.IsSuccess())
  400. {
  401. return AZ::Failure(state.GetError());
  402. }
  403. entitiesStates.emplace(AZStd::make_pair(entity, state.GetValue()));
  404. }
  405. return entitiesStates;
  406. }
  407. AZ::Outcome<void, FailedResult> SimulationEntitiesManager::SetEntityState(const AZStd::string& name, const EntityState& state)
  408. {
  409. const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
  410. if (findIt == m_simulatedEntityToEntityIdMap.end())
  411. {
  412. AZ_Warning("SimulationInterfaces", false, "Entity %s not found", name.c_str());
  413. return AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found"));
  414. }
  415. const AZ::EntityId entityId = findIt->second;
  416. AZ_Assert(entityId.IsValid(), "EntityId is not valid");
  417. // get entity and all descendants
  418. AZStd::vector<AZ::EntityId> entityAndDescendants;
  419. AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
  420. SetEntitiesState(entityAndDescendants, state);
  421. return AZ::Success();
  422. }
  423. void SimulationEntitiesManager::SetEntitiesState(const AZStd::vector<AZ::EntityId>& entityAndDescendants, const EntityState& state)
  424. {
  425. if (entityAndDescendants.empty())
  426. {
  427. AZ_Error("SimulationInterfaces", false, "Entity and descendants list is empty");
  428. return;
  429. }
  430. const AZ::EntityId entityId = entityAndDescendants.front();
  431. AZ::EntityId parentEntityId = AZ::EntityId{ AZ::EntityId::InvalidEntityId };
  432. AZ::TransformBus::EventResult(parentEntityId, entityId, &AZ::TransformBus::Events::GetParentId);
  433. if (state.m_pose.IsOrthogonal())
  434. {
  435. // disable simulation for all entities
  436. for (const auto& descendant : entityAndDescendants)
  437. {
  438. AzPhysics::SimulatedBodyComponentRequestsBus::Event(descendant, &AzPhysics::SimulatedBodyComponentRequests::DisablePhysics);
  439. }
  440. if (parentEntityId.IsValid())
  441. {
  442. AZ::Transform parentTransform;
  443. AZ::TransformBus::EventResult(parentTransform, parentEntityId, &AZ::TransformBus::Events::GetWorldTM);
  444. auto transformToSet = parentTransform.GetInverse() * state.m_pose;
  445. AZ::TransformBus::Event(entityId, &AZ::TransformBus::Events::SetLocalTM, transformToSet);
  446. }
  447. else
  448. {
  449. AZ::TransformBus::Event(entityId, &AZ::TransformBus::Events::SetLocalTM, state.m_pose);
  450. }
  451. for (const auto& descendant : entityAndDescendants)
  452. {
  453. AzPhysics::SimulatedBodyComponentRequestsBus::Event(descendant, &AzPhysics::SimulatedBodyComponentRequests::EnablePhysics);
  454. Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::SetAngularVelocity, AZ::Vector3::CreateZero());
  455. Physics::RigidBodyRequestBus::Event(descendant, &Physics::RigidBodyRequests::SetLinearVelocity, AZ::Vector3::CreateZero());
  456. }
  457. }
  458. if (!state.m_twistLinear.IsZero(AZ::Constants::FloatEpsilon) || !state.m_twistAngular.IsZero(AZ::Constants::FloatEpsilon))
  459. {
  460. // get rigid body
  461. AzPhysics::RigidBody* rigidBody = nullptr;
  462. Physics::RigidBodyRequestBus::EventResult(rigidBody, entityId, &Physics::RigidBodyRequests::GetRigidBody);
  463. if (rigidBody != nullptr)
  464. {
  465. SetRigidBodyVelocities(rigidBody, state);
  466. }
  467. }
  468. }
  469. void SimulationEntitiesManager::DeleteEntity(const AZStd::string& name, DeletionCompletedCb completedCb)
  470. {
  471. const auto findIt = m_simulatedEntityToEntityIdMap.find(name);
  472. if (findIt == m_simulatedEntityToEntityIdMap.end())
  473. {
  474. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found")));
  475. return;
  476. }
  477. const AZ::EntityId entityId = findIt->second;
  478. AZ_Assert(entityId.IsValid(), "EntityId is not valid");
  479. // get entity
  480. AZ::Entity* entity = nullptr;
  481. AZ::ComponentApplicationBus::BroadcastResult(entity, &AZ::ComponentApplicationRequests::FindEntity, entityId);
  482. AZ_Assert(entity, "Entity is not available.");
  483. if (entity == nullptr)
  484. {
  485. AZ_Error("SimulationInterfaces", false, "Entity %s (%s) not found", name.c_str(), entityId.ToString().c_str());
  486. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, "Entity not found")));
  487. return;
  488. }
  489. // check if entity is spawned by this component
  490. const auto ticketId = entity->GetEntitySpawnTicketId();
  491. if (m_spawnedTickets.find(ticketId) != m_spawnedTickets.end())
  492. {
  493. // get spawner
  494. auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
  495. AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
  496. // get ticket
  497. auto ticket = m_spawnedTickets[ticketId];
  498. // remove ticket
  499. AzFramework::DespawnAllEntitiesOptionalArgs optionalArgs;
  500. optionalArgs.m_completionCallback = [this, completedCb](AzFramework::EntitySpawnTicket::Id ticketId)
  501. {
  502. m_spawnedTickets.erase(ticketId);
  503. completedCb(AZ::Success());
  504. };
  505. spawner->DespawnAllEntities(ticket, optionalArgs);
  506. }
  507. else
  508. {
  509. const auto msg = AZStd::string::format("Entity %s was not spawned by this component, wont delete it", name.c_str());
  510. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED, msg)));
  511. }
  512. }
  513. void SimulationEntitiesManager::DeleteAllEntities(DeletionCompletedCb completedCb)
  514. {
  515. if (m_spawnedTickets.empty())
  516. {
  517. // early return for empty scene
  518. completedCb(AZ::Success());
  519. return;
  520. }
  521. for (auto m_spawnedTicket : m_spawnedTickets)
  522. {
  523. auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
  524. AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
  525. // get ticket
  526. auto ticket = m_spawnedTickets[m_spawnedTicket.first];
  527. // despawn
  528. AzFramework::DespawnAllEntitiesOptionalArgs optionalArgs;
  529. optionalArgs.m_completionCallback = [this, completedCb](AzFramework::EntitySpawnTicket::Id ticketId)
  530. {
  531. m_spawnedTickets.erase(ticketId);
  532. if (completedCb && m_spawnedTickets.empty())
  533. {
  534. completedCb(AZ::Success());
  535. }
  536. };
  537. spawner->DespawnAllEntities(ticket, optionalArgs);
  538. }
  539. }
  540. AZ::Outcome<SpawnableList, FailedResult> SimulationEntitiesManager::GetSpawnables()
  541. {
  542. AZStd::vector<Spawnable> spawnables;
  543. const auto enumCallback = [&spawnables](const AZ::Data::AssetId assetId, const AZ::Data::AssetInfo& assetInfo)
  544. {
  545. bool isSpawnable = false;
  546. AZ::Data::AssetCatalogRequestBus::BroadcastResult(
  547. isSpawnable, &AZ::Data::AssetCatalogRequests::DoesAssetIdMatchWildcardPattern, assetId, "*.spawnable");
  548. if (isSpawnable)
  549. {
  550. Spawnable spawnable;
  551. spawnable.m_uri = Utils::RelPathToUri(assetInfo.m_relativePath);
  552. spawnables.push_back(spawnable);
  553. }
  554. };
  555. AZ::Data::AssetCatalogRequestBus::Broadcast(&AZ::Data::AssetCatalogRequests::EnumerateAssets, nullptr, enumCallback, nullptr);
  556. return AZ::Success(spawnables);
  557. }
  558. void SimulationEntitiesManager::SpawnEntity(
  559. const AZStd::string& name,
  560. const AZStd::string& uri,
  561. const AZStd::string& entityNamespace,
  562. const AZ::Transform& initialPose,
  563. const bool allowRename,
  564. SpawnCompletedCb completedCb)
  565. {
  566. if (!allowRename)
  567. {
  568. // If API user does not allow renaming, check if name is unique
  569. if (m_simulatedEntityToEntityIdMap.contains(name))
  570. {
  571. const auto msg = AZStd::string::format("Entity name %s is not unique", name.c_str());
  572. completedCb(AZ::Failure(FailedResult(simulation_interfaces::srv::SpawnEntity::Response::NAME_NOT_UNIQUE, msg)));
  573. return;
  574. }
  575. if (name.empty())
  576. {
  577. const auto msg = AZStd::string::format("Entity name is empty");
  578. completedCb(AZ::Failure(FailedResult(simulation_interfaces::srv::SpawnEntity::Response::NAME_INVALID, msg)));
  579. return;
  580. }
  581. }
  582. if (!initialPose.IsOrthogonal())
  583. {
  584. AZ_Warning("SimulationInterfaces", false, "Initial pose is not orthogonal");
  585. completedCb(
  586. AZ::Failure(FailedResult(
  587. simulation_interfaces::srv::SpawnEntity::Response::INVALID_POSE, "Initial pose is not orthogonal"))); // INVALID_POSE
  588. return;
  589. }
  590. // get rel path from uri
  591. const AZStd::string relPath = Utils::UriToRelPath(uri);
  592. // create spawnable
  593. AZ::Data::AssetId assetId;
  594. AZ::Data::AssetCatalogRequestBus::BroadcastResult(
  595. assetId,
  596. &AZ::Data::AssetCatalogRequestBus::Events::GetAssetIdByPath,
  597. relPath.c_str(),
  598. azrtti_typeid<AZ::Data::AssetData>(),
  599. false);
  600. AZ_Warning("SimulationInterfaces", assetId.IsValid(), "AssetId is not valid, relative path %s", relPath.c_str());
  601. auto spawner = AZ::Interface<AzFramework::SpawnableEntitiesDefinition>::Get();
  602. AZ_Assert(spawner, "SpawnableEntitiesDefinition is not available.");
  603. AZ::Data::Asset<AzFramework::Spawnable> spawnableAsset =
  604. AZ::Data::AssetManager::Instance().GetAsset<AzFramework::Spawnable>(assetId, AZ::Data::AssetLoadBehavior::NoLoad);
  605. if (!spawnableAsset)
  606. {
  607. const auto msg = AZStd::string::format("Spawnable asset %s not found", uri.c_str());
  608. completedCb(AZ::Failure(FailedResult(simulation_interfaces::msg::Result::RESULT_NOT_FOUND, msg)));
  609. return;
  610. }
  611. auto ticket = AzFramework::EntitySpawnTicket(spawnableAsset);
  612. AzFramework::SpawnAllEntitiesOptionalArgs optionalArgs;
  613. optionalArgs.m_preInsertionCallback = [initialPose, entityNamespace, name](auto id, auto view)
  614. {
  615. if (view.empty())
  616. {
  617. return;
  618. }
  619. for (auto* entity : view)
  620. {
  621. ROS2::ROS2FrameComponent* frameComponent = entity->template FindComponent<ROS2::ROS2FrameComponent>();
  622. if (frameComponent)
  623. {
  624. const AZStd::string f = frameComponent->GetFrameID();
  625. if (f.empty())
  626. {
  627. frameComponent->SetFrameID(name);
  628. }
  629. else
  630. {
  631. frameComponent->SetFrameID(AZStd::string::format("%s/%s", entityNamespace.c_str(), f.c_str()));
  632. }
  633. }
  634. }
  635. const AZ::Entity* root = *view.begin();
  636. auto* transformInterface = root->FindComponent<AzFramework::TransformComponent>();
  637. if (transformInterface)
  638. {
  639. transformInterface->SetWorldTM(initialPose);
  640. }
  641. };
  642. optionalArgs.m_completionCallback =
  643. [this, uri](AzFramework::EntitySpawnTicket::Id ticketId, AzFramework::SpawnableConstEntityContainerView view)
  644. {
  645. m_unconfiguredScenesHandles = RegisterNewSimulatedBodies(m_unconfiguredScenesHandles);
  646. // at this point the entities are spawned and should be registered in simulation interface and callback should be called
  647. // if that is not a case, it means that the AZFramework::Physics::OnSimulationBodyAdded event was not called.
  648. // That means the prefab has no physics component or the physics component is not enabled - we need to call the callback here
  649. // and return the error.
  650. auto spawnData = m_spawnCompletedCallbacks.find(ticketId);
  651. if (spawnData != m_spawnCompletedCallbacks.end())
  652. {
  653. // call the API user's callback, when the entity was registered
  654. if (spawnData->second.m_registered)
  655. {
  656. spawnData->second.m_completedCb(AZ::Success(spawnData->second.m_resultedName));
  657. }
  658. else
  659. {
  660. // call the error callback, when the entity was not registered
  661. const auto msg = AZStd::string::format(
  662. "Entity %s (uri : %s) was not registered in simulation interface - "
  663. "no physics component or physics component is not enabled in source prefab.\n"
  664. "Entity will be in simulation, but not available in simulation interface.\n"
  665. "Please add some physics component (at least one static rigid body component) to the prefab.\n"
  666. "Technically, it is a memory leak.\n",
  667. spawnData->second.m_userProposedName.c_str(),
  668. uri.c_str());
  669. spawnData->second.m_completedCb(msg);
  670. }
  671. m_spawnCompletedCallbacks.erase(spawnData);
  672. }
  673. };
  674. spawner->SpawnAllEntities(ticket, optionalArgs);
  675. auto ticketId = ticket.GetId();
  676. AZ_Info("SimulationInterfaces", "Spawning uri %s with ticket id %d\n", uri.c_str(), ticketId);
  677. SpawnCompletedCbData data;
  678. data.m_userProposedName = name;
  679. data.m_completedCb = completedCb;
  680. m_spawnCompletedCallbacks[ticketId] = data;
  681. m_spawnedTickets[ticketId] = ticket;
  682. }
  683. AZStd::string SimulationEntitiesManager::GetSimulatedEntityName(AZ::EntityId entityId, const AZStd::string& proposedName) const
  684. {
  685. // Get O3DE entity name
  686. AZStd::string newName = proposedName;
  687. // check if name is not unique. If not, add Entity Name to name
  688. if (m_simulatedEntityToEntityIdMap.contains(newName))
  689. {
  690. AZStd::string entityName;
  691. AZ::ComponentApplicationBus::BroadcastResult(entityName, &AZ::ComponentApplicationRequests::GetEntityName, entityId);
  692. // name is not unique, add entityId to name
  693. newName = AZStd::string::format("%s_%s", newName.c_str(), entityName.c_str());
  694. }
  695. // check if name is still not unique, if not, add EntityId to name
  696. if (m_simulatedEntityToEntityIdMap.contains(newName))
  697. {
  698. newName = AZStd::string::format("%s_%s", newName.c_str(), entityId.ToString().c_str());
  699. }
  700. return newName;
  701. }
  702. void SimulationEntitiesManager::ResetAllEntitiesToInitialState()
  703. {
  704. for (const auto& [entityId, initialState] : m_entityIdToInitialState)
  705. {
  706. AZStd::vector<AZ::EntityId> entityAndDescendants;
  707. AZ::TransformBus::EventResult(entityAndDescendants, entityId, &AZ::TransformBus::Events::GetEntityAndAllDescendants);
  708. SetEntitiesState(entityAndDescendants, initialState);
  709. }
  710. }
  711. void SimulationEntitiesManager::OnTick([[maybe_unused]] float deltaTime, [[maybe_unused]] AZ::ScriptTimePoint time)
  712. {
  713. m_unconfiguredScenesHandles = RegisterNewSimulatedBodies(m_unconfiguredScenesHandles);
  714. }
  715. } // namespace SimulationInterfaces