SimulationEntitiesManager.cpp 36 KB

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