ResetSimulationServiceHandler.cpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123
  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 "ResetSimulationServiceHandler.h"
  9. #include <AzCore/Component/ComponentApplicationBus.h>
  10. #include <AzCore/std/optional.h>
  11. #include <ROS2/Clock/ROS2Clock.h>
  12. #include <ROS2/ROS2Bus.h>
  13. #include <SimulationInterfaces/SimulationEntityManagerRequestBus.h>
  14. #include <SimulationInterfaces/SimulationFeaturesAggregatorRequestBus.h>
  15. #include <SimulationInterfaces/SimulationMangerRequestBus.h>
  16. #include <builtin_interfaces/msg/time.hpp>
  17. #include <simulation_interfaces/msg/detail/result__struct.hpp>
  18. namespace ROS2SimulationInterfaces
  19. {
  20. AZStd::unordered_set<SimulationFeatureType> ResetSimulationServiceHandler::GetProvidedFeatures()
  21. {
  22. return AZStd::unordered_set<SimulationFeatureType>{ SimulationFeatures::SIMULATION_RESET,
  23. SimulationFeatures::SIMULATION_RESET_TIME,
  24. SimulationFeatures::SIMULATION_RESET_STATE,
  25. SimulationFeatures::SIMULATION_RESET_SPAWNED };
  26. }
  27. AZStd::optional<ResetSimulationServiceHandler::Response> ResetSimulationServiceHandler::HandleServiceRequest(
  28. const std::shared_ptr<rmw_request_id_t> header, const Request& request)
  29. {
  30. if (request.scope == Request::SCOPE_STATE)
  31. {
  32. Response response;
  33. SimulationInterfaces::SimulationEntityManagerRequestBus::Broadcast(
  34. &SimulationInterfaces::SimulationEntityManagerRequests::ResetAllEntitiesToInitialState);
  35. response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
  36. return response;
  37. }
  38. if (request.scope == Request::SCOPE_SPAWNED)
  39. {
  40. auto deletionCompletedCb = [this](const AZ::Outcome<void, SimulationInterfaces::FailedResult>& outcome)
  41. {
  42. Response response;
  43. if (outcome.IsSuccess())
  44. {
  45. response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
  46. }
  47. else
  48. {
  49. const auto& failedResult = outcome.GetError();
  50. response.result.result = aznumeric_cast<uint8_t>(failedResult.m_errorCode);
  51. response.result.error_message = failedResult.m_errorString.c_str();
  52. }
  53. SendResponse(response);
  54. };
  55. SimulationInterfaces::SimulationEntityManagerRequestBus::Broadcast(
  56. &SimulationInterfaces::SimulationEntityManagerRequests::DeleteAllEntities, deletionCompletedCb);
  57. return AZStd::nullopt;
  58. }
  59. if (request.scope == Request::SCOPE_TIME)
  60. {
  61. auto* interface = ROS2::ROS2Interface::Get();
  62. AZ_Assert(interface, "ROS2Interface is not available");
  63. auto& clock = interface->GetSimulationClock();
  64. builtin_interfaces::msg::Time time;
  65. time.sec = 0;
  66. time.nanosec = 0;
  67. auto results = clock.AdjustTime(time);
  68. if (results.IsSuccess())
  69. {
  70. Response response;
  71. response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
  72. return response;
  73. }
  74. else
  75. {
  76. Response response;
  77. response.result.result = simulation_interfaces::msg::Result::RESULT_OPERATION_FAILED;
  78. const auto& errorMessage = results.GetError();
  79. response.result.error_message = std::string(errorMessage.c_str(), errorMessage.size());
  80. return response;
  81. }
  82. }
  83. if (request.scope == Request::SCOPE_ALL || request.scope == Request::SCOPE_DEFAULT)
  84. {
  85. // check if we are in GameLauncher
  86. AZ::ApplicationTypeQuery appType;
  87. AZ::ComponentApplicationBus::Broadcast(&AZ::ComponentApplicationBus::Events::QueryApplicationType, appType);
  88. if (appType.IsValid() && appType.IsEditor())
  89. {
  90. Response response;
  91. response.result.result = simulation_interfaces::msg::Result::RESULT_FEATURE_UNSUPPORTED;
  92. response.result.error_message = "Feature not supported in Editor.";
  93. return response;
  94. }
  95. auto levelReloadCompletion = [this]()
  96. {
  97. Response response;
  98. response.result.result = simulation_interfaces::msg::Result::RESULT_OK;
  99. SendResponse(response);
  100. };
  101. SimulationInterfaces::SimulationManagerRequestBus::Broadcast(
  102. &SimulationInterfaces::SimulationManagerRequests::ReloadLevel, levelReloadCompletion);
  103. return AZStd::nullopt;
  104. }
  105. // no case matched, return response that request was invalid
  106. Response invalidResponse;
  107. invalidResponse.result.result = simulation_interfaces::msg::Result::RESULT_NOT_FOUND;
  108. invalidResponse.result.error_message = "Passed unknown scope";
  109. return invalidResponse;
  110. }
  111. } // namespace ROS2SimulationInterfaces