OpenDrive .xodr file integrated with the required file system
This commit is contained in:
parent
47f733c099
commit
1a58b48564
|
@ -23,7 +23,9 @@ namespace detail {
|
|||
WalkerNavigation::WalkerNavigation(Client &client) : _client(client), _next_check_index(0) {
|
||||
// Here call the server to retrieve the navmesh data.
|
||||
auto files = _client.GetRequiredFiles("Nav");
|
||||
_nav.Load(_client.GetCacheFile(files[0]));
|
||||
if (!files.empty()) {
|
||||
_nav.Load(_client.GetCacheFile(files[0]));
|
||||
}
|
||||
}
|
||||
|
||||
void WalkerNavigation::Tick(std::shared_ptr<Episode> episode) {
|
||||
|
|
|
@ -130,7 +130,7 @@ void ULoadAssetMaterialsCommandlet::ApplyRoadPainterMaterials(const FString &Loa
|
|||
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::LoadXODR(TileData.XODRName);
|
||||
const FString XodrContent = UOpenDrive::GetXODR(GetWorld());
|
||||
XODRMap = carla::opendrive::OpenDriveParser::Load(carla::rpc::FromLongFString(XodrContent));
|
||||
|
||||
// Acquire the TilesInfo.txt file for storing the tile data (offset and size)
|
||||
|
|
|
@ -292,7 +292,7 @@ void ACarlaGameModeBase::GenerateSpawnPoints()
|
|||
|
||||
void ACarlaGameModeBase::ParseOpenDrive(const FString &MapName)
|
||||
{
|
||||
std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::LoadXODR(MapName));
|
||||
std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::GetXODR(GetWorld()));
|
||||
Map = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
|
||||
if (!Map.has_value()) {
|
||||
UE_LOG(LogCarla, Error, TEXT("Invalid Map"));
|
||||
|
|
|
@ -9,73 +9,40 @@
|
|||
|
||||
#include "Runtime/Core/Public/HAL/FileManagerGeneric.h"
|
||||
|
||||
FString UOpenDrive::FindPathToXODRFile(const FString &InMapName)
|
||||
|
||||
FString UOpenDrive::GetXODR(const UWorld *World)
|
||||
{
|
||||
FString MapName = InMapName;
|
||||
#if WITH_EDITOR
|
||||
{
|
||||
// When playing in editor the map name gets an extra prefix, here we
|
||||
// remove it.
|
||||
FString CorrectedMapName = MapName;
|
||||
constexpr auto PIEPrefix = TEXT("UEDPIE_0_");
|
||||
CorrectedMapName.RemoveFromStart(PIEPrefix);
|
||||
UE_LOG(LogCarla, Log, TEXT("UOpenDrive: Corrected map name from %s to %s"), *MapName, *CorrectedMapName);
|
||||
MapName = CorrectedMapName;
|
||||
}
|
||||
#endif // WITH_EDITOR
|
||||
const auto mapName = World->GetMapName();
|
||||
const auto mapDir = FPaths::GetPath(UCarlaStatics::GetGameInstance(World)->GetMapPath());
|
||||
const auto folderDir = mapDir + "/OpenDrive/";
|
||||
const auto fileName = mapDir.EndsWith(mapName) ? "*" : mapName;
|
||||
|
||||
MapName += TEXT(".xodr");
|
||||
|
||||
const FString DefaultFilePath =
|
||||
FPaths::ProjectContentDir() +
|
||||
TEXT("Carla/Maps/OpenDrive/") +
|
||||
MapName;
|
||||
|
||||
auto &FileManager = IFileManager::Get();
|
||||
|
||||
if (FileManager.FileExists(*DefaultFilePath))
|
||||
{
|
||||
return DefaultFilePath;
|
||||
}
|
||||
|
||||
TArray<FString> FilesFound;
|
||||
FileManager.FindFilesRecursive(
|
||||
FilesFound,
|
||||
*FPaths::ProjectContentDir(),
|
||||
*MapName,
|
||||
true,
|
||||
false,
|
||||
false);
|
||||
|
||||
return FilesFound.Num() > 0 ? FilesFound[0u] : FString{};
|
||||
}
|
||||
|
||||
FString UOpenDrive::LoadXODR(const FString &MapName)
|
||||
{
|
||||
const auto FilePath = FindPathToXODRFile(MapName);
|
||||
// Find all the xodr and bin files from the map
|
||||
TArray<FString> Files;
|
||||
IFileManager::Get().FindFilesRecursive(Files, *folderDir, *FString(fileName + ".xodr"), true, false, false);
|
||||
|
||||
FString Content;
|
||||
|
||||
if (FilePath.IsEmpty())
|
||||
if (!Files.Num())
|
||||
{
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to find OpenDrive file for map '%s'"), *MapName);
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to find OpenDrive file for map '%s'"), *mapName);
|
||||
}
|
||||
else if (FFileHelper::LoadFileToString(Content, *FilePath))
|
||||
else if (FFileHelper::LoadFileToString(Content, *Files[0]))
|
||||
{
|
||||
UE_LOG(LogTemp, Log, TEXT("Loaded OpenDrive file '%s'"), *FilePath);
|
||||
UE_LOG(LogTemp, Log, TEXT("Loaded OpenDrive file '%s'"), *Files[0]);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to load OpenDrive file '%s'"), *FilePath);
|
||||
UE_LOG(LogTemp, Error, TEXT("Failed to load OpenDrive file '%s'"), *Files[0]);
|
||||
}
|
||||
|
||||
return Content;
|
||||
}
|
||||
|
||||
UOpenDriveMap *UOpenDrive::LoadOpenDriveMap(const FString &MapName)
|
||||
UOpenDriveMap *UOpenDrive::LoadOpenDriveMap(const UWorld *World)
|
||||
{
|
||||
UOpenDriveMap *Map = nullptr;
|
||||
auto XODRContent = LoadXODR(MapName);
|
||||
auto XODRContent = GetXODR(World);
|
||||
if (!XODRContent.IsEmpty())
|
||||
{
|
||||
Map = NewObject<UOpenDriveMap>();
|
||||
|
@ -87,7 +54,5 @@ UOpenDriveMap *UOpenDrive::LoadOpenDriveMap(const FString &MapName)
|
|||
UOpenDriveMap *UOpenDrive::LoadCurrentOpenDriveMap(const UObject *WorldContextObject)
|
||||
{
|
||||
UWorld *World = GEngine->GetWorldFromContextObject(WorldContextObject, EGetWorldErrorMode::LogAndReturnNull);
|
||||
return World != nullptr ?
|
||||
LoadOpenDriveMap(World->GetMapName()) :
|
||||
nullptr;
|
||||
return World != nullptr ? LoadOpenDriveMap(World) : nullptr;
|
||||
}
|
||||
|
|
|
@ -19,19 +19,15 @@ class CARLA_API UOpenDrive : public UBlueprintFunctionLibrary
|
|||
|
||||
public:
|
||||
|
||||
/// Find the path to the XODR file associated to MapName. Return empty if no
|
||||
/// such file is found.
|
||||
static FString FindPathToXODRFile(const FString &MapName);
|
||||
|
||||
/// Return the OpenDrive XML associated to @a MapName, or empty if the file
|
||||
/// is not found.
|
||||
UFUNCTION(BlueprintCallable, Category="CARLA|OpenDrive")
|
||||
static FString LoadXODR(const FString &MapName);
|
||||
static FString GetXODR(const UWorld *World);
|
||||
|
||||
/// Load OpenDriveMap associated to the given MapName. Return nullptr if no
|
||||
/// XODR can be found with same MapName.
|
||||
UFUNCTION(BlueprintCallable, Category="CARLA|OpenDrive")
|
||||
static UOpenDriveMap *LoadOpenDriveMap(const FString &MapName);
|
||||
static UOpenDriveMap *LoadOpenDriveMap(const UWorld *World);
|
||||
|
||||
/// Load OpenDriveMap associated to the currently loaded map. Return nullptr
|
||||
/// if no XODR can be found that matches the current map.
|
||||
|
|
|
@ -136,7 +136,7 @@ void AOpenDriveActor::BuildRoutes(FString MapName)
|
|||
|
||||
// As the OpenDrive file has the same name as level, build the path to the
|
||||
// xodr file using the lavel name and the game content directory.
|
||||
const FString XodrContent = UOpenDrive::LoadXODR(MapName);
|
||||
const FString XodrContent = UOpenDrive::GetXODR(GetWorld());
|
||||
|
||||
auto map = carla::opendrive::OpenDriveParser::Load(carla::rpc::FromLongFString(XodrContent));
|
||||
|
||||
|
|
|
@ -170,7 +170,7 @@ void AOpenDriveGenerator::BeginPlay()
|
|||
Super::BeginPlay();
|
||||
|
||||
// Search for "{project_content_folder}/Carla/Maps/OpenDrive/{current_map_name}.xodr"
|
||||
const FString XodrContent = UOpenDrive::LoadXODR(GetWorld()->GetMapName());
|
||||
const FString XodrContent = UOpenDrive::GetXODR(GetWorld());
|
||||
LoadOpenDrive(XodrContent);
|
||||
|
||||
GenerateAll();
|
||||
|
|
|
@ -341,7 +341,7 @@ void FCarlaServer::FPimpl::BindActions()
|
|||
BIND_SYNC(get_map_info) << [this]() -> R<cr::MapInfo>
|
||||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
auto FileContents = UOpenDrive::LoadXODR(Episode->GetMapName());
|
||||
auto FileContents = UOpenDrive::GetXODR(Episode->GetWorld());
|
||||
const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
|
||||
return cr::MapInfo{
|
||||
cr::FromFString(Episode->GetMapName()),
|
||||
|
@ -369,14 +369,14 @@ void FCarlaServer::FPimpl::BindActions()
|
|||
}
|
||||
|
||||
// Get the map's folder absolute path and check if it's in its own folder
|
||||
auto mapDir = FPaths::GetPath(UCarlaStatics::GetGameInstance(Episode->GetWorld())->GetMapPath()) + "/" + folder.c_str();
|
||||
auto fileName = mapDir.EndsWith(Episode->GetMapName() + "/") ? "*" : Episode->GetMapName();
|
||||
const auto mapDir = FPaths::GetPath(UCarlaStatics::GetGameInstance(Episode->GetWorld())->GetMapPath());
|
||||
const auto folderDir = mapDir + "/" + folder.c_str();
|
||||
const auto fileName = mapDir.EndsWith(Episode->GetMapName()) ? "*" : Episode->GetMapName();
|
||||
|
||||
// Find all the xodr and bin files from the map
|
||||
TArray<FString> Files;
|
||||
auto &FileManager = IFileManager::Get();
|
||||
FileManager.FindFilesRecursive(Files, *mapDir, *FString(fileName + ".xodr"), true, false, false);
|
||||
FileManager.FindFilesRecursive(Files, *mapDir, *FString(fileName + ".bin"), true, false, false);
|
||||
IFileManager::Get().FindFilesRecursive(Files, *folderDir, *FString(fileName + ".xodr"), true, false, false);
|
||||
IFileManager::Get().FindFilesRecursive(Files, *folderDir, *FString(fileName + ".bin"), true, false, false);
|
||||
|
||||
// Remove the start of the path until the content folder and put each file in the result
|
||||
std::vector<std::string> result;
|
||||
|
|
|
@ -271,8 +271,7 @@ void ATrafficLightManager::MatchTrafficLightActorsWithOpenDriveSignals()
|
|||
TArray<AActor*> Actors;
|
||||
UGameplayStatics::GetAllActorsOfClass(GetWorld(), ATrafficLightBase::StaticClass(), Actors);
|
||||
|
||||
FString MapName = GetWorld()->GetName();
|
||||
std::string opendrive_xml = carla::rpc::FromFString(UOpenDrive::LoadXODR(MapName));
|
||||
std::string opendrive_xml = carla::rpc::FromFString(UOpenDrive::GetXODR(GetWorld()));
|
||||
auto Map = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
|
||||
|
||||
if (!Map)
|
||||
|
|
Loading…
Reference in New Issue