From ff97d65cc0118f2fcfe0cc4ac2ff689eafb33db8 Mon Sep 17 00:00:00 2001 From: Axel1092 Date: Wed, 22 Apr 2020 12:00:13 +0200 Subject: [PATCH] Fixed server-client sincronization for map change. --- .../source/carla/client/detail/Client.cpp | 4 ++++ LibCarla/source/carla/client/detail/Client.h | 2 ++ .../source/carla/client/detail/Simulator.cpp | 2 +- .../Source/Carla/Game/CarlaGameInstance.h | 4 ++++ .../Carla/Source/Carla/Server/CarlaServer.cpp | 22 +++++++++++++++++-- 5 files changed, 31 insertions(+), 3 deletions(-) diff --git a/LibCarla/source/carla/client/detail/Client.cpp b/LibCarla/source/carla/client/detail/Client.cpp index 01375030d..868ec7ce1 100644 --- a/LibCarla/source/carla/client/detail/Client.cpp +++ b/LibCarla/source/carla/client/detail/Client.cpp @@ -145,6 +145,10 @@ namespace detail { _pimpl->CallAndWait("load_new_episode", std::move(map_name)); } + bool Client::CheckIntermediateEpisode() { + return _pimpl->CallAndWait("check_intermediate_episode"); + } + void Client::CopyOpenDriveToServer(std::string opendrive, const rpc::OpendriveGenerationParameters & params) { // Await response, we need to be sure in this one. _pimpl->CallAndWait("copy_opendrive_to_file", std::move(opendrive), params); diff --git a/LibCarla/source/carla/client/detail/Client.h b/LibCarla/source/carla/client/detail/Client.h index 5d18c7bfb..003619717 100644 --- a/LibCarla/source/carla/client/detail/Client.h +++ b/LibCarla/source/carla/client/detail/Client.h @@ -88,6 +88,8 @@ namespace detail { void LoadEpisode(std::string map_name); + bool CheckIntermediateEpisode(); + void CopyOpenDriveToServer( std::string opendrive, const rpc::OpendriveGenerationParameters & params); diff --git a/LibCarla/source/carla/client/detail/Simulator.cpp b/LibCarla/source/carla/client/detail/Simulator.cpp index 139d4eaf3..2b543c31a 100644 --- a/LibCarla/source/carla/client/detail/Simulator.cpp +++ b/LibCarla/source/carla/client/detail/Simulator.cpp @@ -90,7 +90,7 @@ namespace detail { using namespace std::literals::chrono_literals; _episode->WaitForState(10ms); auto episode = GetCurrentEpisode(); - if (episode.GetId() != id) { + if (episode.GetId() != id && !_client.CheckIntermediateEpisode()) { return episode; } } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h index bafe01cbf..eafe8d801 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameInstance.h @@ -87,6 +87,10 @@ public: void CheckAndLoadMap(UWorld *world, UCarlaEpisode &Episode); + bool IsLevelPendingLoad() const { + return bShouldLoadLevel; + } + private: UPROPERTY(Category = "CARLA Settings", EditAnywhere) diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp index e3738504f..59d772be2 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaServer.cpp @@ -228,14 +228,32 @@ void FCarlaServer::FPimpl::BindActions() BIND_SYNC(load_new_episode) << [this](const std::string &map_name) -> R { REQUIRE_CARLA_EPISODE(); - UCarlaStatics::GetGameInstance(Episode->GetWorld())->SetMapToLoad(cr::ToFString(map_name)); - if (!Episode->LoadNewEpisode(cr::ToFString("OpendriveMap"))) + FString MapName = cr::ToFString(map_name); + auto Maps = UCarlaStatics::GetAllMapNames(); + bool bMissingMap = true; + for (auto & Map : Maps) + { + if(Map.Contains(MapName)) + { + bMissingMap = false; + break; + } + } + if(bMissingMap) { RESPOND_ERROR("map not found"); } + UCarlaStatics::GetGameInstance(Episode->GetWorld())->SetMapToLoad(MapName); + Episode->LoadNewEpisode(cr::ToFString("EmptyMap")); return R::Success(); }; + BIND_SYNC(check_intermediate_episode) << [this]() -> R + { + REQUIRE_CARLA_EPISODE(); + return UCarlaStatics::GetGameInstance(Episode->GetWorld())->IsLevelPendingLoad(); + }; + BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, carla::rpc::OpendriveGenerationParameters Params) -> R { REQUIRE_CARLA_EPISODE();