ResetSimulationServiceHandler.cpp 4.8 KB

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