Remove intermediate map when changing map. (#2911)

* Fixed load_new_episode and removed intermediate check.

* Recovered intermediate state.

* Removing intermediate map

* Fixing merge issue

* Remove unnecessary check in load_new_episode
This commit is contained in:
doterop 2020-06-15 10:53:26 +02:00 committed by GitHub
parent d8c165ae07
commit f114dc0aa1
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
7 changed files with 8 additions and 67 deletions

View File

@ -145,10 +145,6 @@ namespace detail {
_pimpl->CallAndWait<void>("load_new_episode", std::move(map_name)); _pimpl->CallAndWait<void>("load_new_episode", std::move(map_name));
} }
bool Client::CheckIntermediateEpisode() {
return _pimpl->CallAndWait<bool>("check_intermediate_episode");
}
void Client::CopyOpenDriveToServer(std::string opendrive, const rpc::OpendriveGenerationParameters & params) { void Client::CopyOpenDriveToServer(std::string opendrive, const rpc::OpendriveGenerationParameters & params) {
// Await response, we need to be sure in this one. // Await response, we need to be sure in this one.
_pimpl->CallAndWait<void>("copy_opendrive_to_file", std::move(opendrive), params); _pimpl->CallAndWait<void>("copy_opendrive_to_file", std::move(opendrive), params);

View File

@ -89,8 +89,6 @@ namespace detail {
void LoadEpisode(std::string map_name); void LoadEpisode(std::string map_name);
bool CheckIntermediateEpisode();
void CopyOpenDriveToServer( void CopyOpenDriveToServer(
std::string opendrive, const rpc::OpendriveGenerationParameters & params); std::string opendrive, const rpc::OpendriveGenerationParameters & params);

View File

@ -90,7 +90,7 @@ namespace detail {
using namespace std::literals::chrono_literals; using namespace std::literals::chrono_literals;
_episode->WaitForState(10ms); _episode->WaitForState(10ms);
auto episode = GetCurrentEpisode(); auto episode = GetCurrentEpisode();
if (episode.GetId() != id && !_client.CheckIntermediateEpisode()) { if (episode.GetId() != id) {
return episode; return episode;
} }
} }

View File

@ -17,18 +17,3 @@ UCarlaGameInstance::UCarlaGameInstance() {
} }
UCarlaGameInstance::~UCarlaGameInstance() = default; UCarlaGameInstance::~UCarlaGameInstance() = default;
void UCarlaGameInstance::SetMapToLoad(const FString MapName)
{
MapToLoad = MapName;
bShouldLoadLevel = true;
}
void UCarlaGameInstance::CheckAndLoadMap(UWorld *world, UCarlaEpisode &Episode)
{
if(bShouldLoadLevel)
{
Episode.LoadNewEpisode(MapToLoad);
bShouldLoadLevel = false;
}
}

View File

@ -83,14 +83,6 @@ public:
return GenerationParameters; return GenerationParameters;
} }
void SetMapToLoad(const FString MapName);
void CheckAndLoadMap(UWorld *world, UCarlaEpisode &Episode);
bool IsLevelPendingLoad() const {
return bShouldLoadLevel;
}
private: private:
UPROPERTY(Category = "CARLA Settings", EditAnywhere) UPROPERTY(Category = "CARLA Settings", EditAnywhere)
@ -100,9 +92,4 @@ private:
carla::rpc::OpendriveGenerationParameters GenerationParameters; carla::rpc::OpendriveGenerationParameters GenerationParameters;
UPROPERTY()
bool bShouldLoadLevel = false;
UPROPERTY()
FString MapToLoad;
}; };

View File

@ -142,7 +142,6 @@ void ACarlaGameModeBase::BeginPlay()
Recorder->GetReplayer()->CheckPlayAfterMapLoaded(); Recorder->GetReplayer()->CheckPlayAfterMapLoaded();
} }
UCarlaStatics::GetGameInstance(GetWorld())->CheckAndLoadMap(GetWorld(), *Episode);
} }
void ACarlaGameModeBase::Tick(float DeltaSeconds) void ACarlaGameModeBase::Tick(float DeltaSeconds)
@ -194,15 +193,12 @@ void ACarlaGameModeBase::SpawnActorFactories()
void ACarlaGameModeBase::ParseOpenDrive(const FString &MapName) void ACarlaGameModeBase::ParseOpenDrive(const FString &MapName)
{ {
if(!UCarlaStatics::GetGameInstance(Episode->GetWorld())->IsLevelPendingLoad()) std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::LoadXODR(MapName));
{ Map = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::LoadXODR(MapName)); if (!Map.has_value()) {
Map = carla::opendrive::OpenDriveParser::Load(opendrive_xml); UE_LOG(LogCarla, Error, TEXT("Invalid Map"));
if (!Map.has_value()) { } else {
UE_LOG(LogCarla, Error, TEXT("Invalid Map")); Episode->MapGeoReference = Map->GetGeoReference();
} else {
Episode->MapGeoReference = Map->GetGeoReference();
}
} }
} }

View File

@ -229,34 +229,13 @@ void FCarlaServer::FPimpl::BindActions()
BIND_SYNC(load_new_episode) << [this](const std::string &map_name) -> R<void> BIND_SYNC(load_new_episode) << [this](const std::string &map_name) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();
FString MapName = cr::ToFString(map_name); if(!Episode->LoadNewEpisode(cr::ToFString(map_name)))
MapName = MapName.IsEmpty() ? Episode->GetMapName() : MapName;
auto Maps = UCarlaStatics::GetAllMapNames();
Maps.Add("OpenDriveMap");
bool bMissingMap = true;
for (auto & Map : Maps)
{
if(Map.Contains(MapName))
{
bMissingMap = false;
break;
}
}
if(bMissingMap)
{ {
RESPOND_ERROR("map not found"); RESPOND_ERROR("map not found");
} }
UCarlaStatics::GetGameInstance(Episode->GetWorld())->SetMapToLoad(MapName);
Episode->LoadNewEpisode(cr::ToFString("EmptyMap"));
return R<void>::Success(); return R<void>::Success();
}; };
BIND_SYNC(check_intermediate_episode) << [this]() -> R<bool>
{
REQUIRE_CARLA_EPISODE();
return UCarlaStatics::GetGameInstance(Episode->GetWorld())->IsLevelPendingLoad();
};
BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, cr::OpendriveGenerationParameters Params) -> R<void> BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, cr::OpendriveGenerationParameters Params) -> R<void>
{ {
REQUIRE_CARLA_EPISODE(); REQUIRE_CARLA_EPISODE();