Navigation .bin file integrated with the required file system
This commit is contained in:
parent
1a58b48564
commit
6d39572e09
|
@ -127,7 +127,6 @@ void ULoadAssetMaterialsCommandlet::ApplyRoadPainterMaterials(const FString &Loa
|
|||
|
||||
if (FilledData == false) {
|
||||
|
||||
TileData.XODRName = LoadedMapName.LeftChop((LoadedMapName.GetCharArray().Num() - 1) - LoadedMapName.Find("_", ESearchCase::IgnoreCase, ESearchDir::Type::FromStart));
|
||||
// As the OpenDrive file has the same name as level, build the path to the
|
||||
// xodr file using the label name and the game content directory.
|
||||
const FString XodrContent = UOpenDrive::GetXODR(GetWorld());
|
||||
|
|
|
@ -26,9 +26,6 @@ struct CARLA_API FLargeMapTileData
|
|||
{
|
||||
GENERATED_USTRUCT_BODY()
|
||||
|
||||
UPROPERTY()
|
||||
FString XODRName;
|
||||
|
||||
UPROPERTY()
|
||||
float FirstTileCenterX;
|
||||
|
||||
|
|
|
@ -128,7 +128,7 @@ void ACarlaGameModeBase::InitGame(
|
|||
Recorder->SetEpisode(Episode);
|
||||
Episode->SetRecorder(Recorder);
|
||||
|
||||
ParseOpenDrive(Episode->MapName);
|
||||
ParseOpenDrive();
|
||||
|
||||
if(Map.has_value())
|
||||
{
|
||||
|
@ -290,7 +290,7 @@ void ACarlaGameModeBase::GenerateSpawnPoints()
|
|||
}
|
||||
}
|
||||
|
||||
void ACarlaGameModeBase::ParseOpenDrive(const FString &MapName)
|
||||
void ACarlaGameModeBase::ParseOpenDrive()
|
||||
{
|
||||
std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::GetXODR(GetWorld()));
|
||||
Map = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
|
||||
|
|
|
@ -109,7 +109,7 @@ private:
|
|||
|
||||
void GenerateSpawnPoints();
|
||||
|
||||
void ParseOpenDrive(const FString &MapName);
|
||||
void ParseOpenDrive();
|
||||
|
||||
void RegisterEnvironmentObjects();
|
||||
|
||||
|
|
|
@ -169,7 +169,6 @@ void AOpenDriveGenerator::BeginPlay()
|
|||
{
|
||||
Super::BeginPlay();
|
||||
|
||||
// Search for "{project_content_folder}/Carla/Maps/OpenDrive/{current_map_name}.xodr"
|
||||
const FString XodrContent = UOpenDrive::GetXODR(GetWorld());
|
||||
LoadOpenDrive(XodrContent);
|
||||
|
||||
|
|
|
@ -22,32 +22,24 @@ TArray<uint8> FNavigationMesh::Load(FString MapName)
|
|||
}
|
||||
#endif // WITH_EDITOR
|
||||
|
||||
FString FilePath =
|
||||
FPaths::ProjectContentDir() +
|
||||
TEXT("Carla/Maps/Nav/") +
|
||||
MapName + TEXT(".bin");
|
||||
const auto FileName = MapName + ".bin";
|
||||
|
||||
auto &FileManager = IFileManager::Get();
|
||||
if (!FileManager.FileExists(*FilePath))
|
||||
{
|
||||
TArray<FString> FilesFound;
|
||||
FileManager.FindFilesRecursive(
|
||||
FilesFound,
|
||||
*FPaths::ProjectContentDir(),
|
||||
*(MapName + TEXT(".bin")),
|
||||
true,
|
||||
false,
|
||||
false);
|
||||
if (FilesFound.Num() > 0)
|
||||
FilePath = FilesFound[0u];
|
||||
}
|
||||
TArray<FString> Files;
|
||||
IFileManager::Get().FindFilesRecursive(Files, *FPaths::ProjectContentDir(), *FileName, true, false, false);
|
||||
|
||||
TArray<uint8> Content;
|
||||
UE_LOG(LogCarla, Log, TEXT("Loading Navigation Mesh file '%s'"), *FilePath);
|
||||
|
||||
if (!FFileHelper::LoadFileToArray(Content, *FilePath, 0))
|
||||
if (!Files.Num())
|
||||
{
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to load Navigation Mesh file '%s'"), *FilePath);
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to find OpenDrive file for map '%s'"), *MapName);
|
||||
}
|
||||
else if (FFileHelper::LoadFileToArray(Content, *Files[0], 0))
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Loading Navigation Mesh file '%s'"), *Files[0]);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to load Navigation Mesh file '%s'"), *Files[0]);
|
||||
}
|
||||
|
||||
return Content;
|
||||
|
|
Loading…
Reference in New Issue