Digital Twins first iteration (#6260)
* Added way to download files from overpass api * Save downloaded text to a file * Changed log type for File manipulation * Online process files when request is valid * Correct file format * Correct file format for UE4 class * Fix compilation issue due to name change * Create Widget with OpenFileDialogFunctionality * Step xodr to map completed * Generated Static meshes and replace procedural actors * Created and saved assets during road generation * Formatted file correctly * OSM To ODR broguht to UE4 * Full pipeline working on linux * Added osm2odr support in editor in Windos * Added Widget to CartaTools * Fixed Linux compilation error * Added Carla Game Instance included to avoid compilation error * Osm Renderer Tool dummy version * Server creates SVG files when client request it * SVG creation and rasterization - libraries integration * Server size working * Added Simplify to LibCarla, Added timers to measure time generation. Add mesh deformation during road creation. * Fixed mesh format translations * Trying to paint bitmap into the UTexture * Bitmap sent and drawn in widget texture with bugs * Map bitmap shown on widget * Concated meshes generated in the same lane to avoid errors during simplification * Navigation added to widget * Avoid Simplify to remove border vertices and try to parallel assets creation process * Road Generation 0.1 version ready * Removing Engine Association, Formatting CarlaTools Build dependencies * Change container type of generated procedural mesh componetns to be supported by UPROPERTY * Fixed indices jumping by two * Started dynamic database creation * Dynamic database creation temporally removed * First step of merge. Coords of bottom left corner and top right corner * Libraries added to build system * Git ignore for osmrenderer to avoid ThirdParties directory to be tracked * Lat and Lon coords for corners sent from server to client * Transformed to local coords meshes' vertices' coords * Coords format error fixed * Saving xodr and osm files inside of OpenDrive folder * Widget fixed * UI design improved * WIP Windows build system for osm-world-renderer * Socket implementation replaced by boost asio framework in osmrenderer * Build system adapted to wndows * Headers fixed to avoid windows specific heraders compilation * Added widget to import building from houdini * Added origin latitude and longituda to OSM to OpenDRIVE conversion functions. Fixed Houdini importer widgets. * Add Houdini plugin download to the build system * Moved houdini blueprint. Houdini plugin now dowloads by default * Added houdini download for windows --------- Co-authored-by: Aaron <samaniegoaaron112@gmail.com> Co-authored-by: Blyron <53337103+Blyron@users.noreply.github.com> Co-authored-by: aollero <aollero@cvc.uab.cat> Co-authored-by: aollero <adriollero@gmail.com> Co-authored-by: bernat <bernatx@gmail.com>
This commit is contained in:
parent
de7e9bf030
commit
777b174a08
|
@ -70,7 +70,6 @@ namespace geom {
|
||||||
double s_current = s_start;
|
double s_current = s_start;
|
||||||
|
|
||||||
std::vector<geom::Vector3D> vertices;
|
std::vector<geom::Vector3D> vertices;
|
||||||
|
|
||||||
if (lane.IsStraight()) {
|
if (lane.IsStraight()) {
|
||||||
// Mesh optimization: If the lane is straight just add vertices at the
|
// Mesh optimization: If the lane is straight just add vertices at the
|
||||||
// begining and at the end of it
|
// begining and at the end of it
|
||||||
|
@ -157,7 +156,6 @@ namespace geom {
|
||||||
current_vertex = current_vertex + segments_size;
|
current_vertex = current_vertex + segments_size;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
out_mesh.AddVertices(vertices);
|
out_mesh.AddVertices(vertices);
|
||||||
|
|
||||||
// Add the adient material, create the strip and close the material
|
// Add the adient material, create the strip and close the material
|
||||||
|
@ -179,7 +177,6 @@ namespace geom {
|
||||||
out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
|
out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
out_mesh.EndMaterial();
|
out_mesh.EndMaterial();
|
||||||
return std::make_unique<Mesh>(out_mesh);
|
return std::make_unique<Mesh>(out_mesh);
|
||||||
}
|
}
|
||||||
|
@ -385,7 +382,6 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
||||||
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
|
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
|
||||||
const road::LaneSection &lane_section) const {
|
const road::LaneSection &lane_section) const {
|
||||||
const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
|
const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
|
||||||
|
|
||||||
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
|
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
|
||||||
|
|
||||||
if (lane_section.GetLength() < road_param.max_road_len) {
|
if (lane_section.GetLength() < road_param.max_road_len) {
|
||||||
|
@ -405,7 +401,6 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
||||||
{
|
{
|
||||||
(mesh_uptr_list[lane_pair.second.GetType()][0])->ConcatMesh(lane_section_mesh, vertices_in_width);
|
(mesh_uptr_list[lane_pair.second.GetType()][0])->ConcatMesh(lane_section_mesh, vertices_in_width);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
s_current = s_until;
|
s_current = s_until;
|
||||||
}
|
}
|
||||||
|
|
|
@ -593,6 +593,12 @@ ALargeMapManager::TileID ALargeMapManager::GetTileID(FDVector TileLocation) cons
|
||||||
return GetTileID(TileID);
|
return GetTileID(TileID);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
FCarlaMapTile* ALargeMapManager::GetCarlaMapTile(FVector Location)
|
||||||
|
{
|
||||||
|
TileID TileID = GetTileID(Location);
|
||||||
|
return GetCarlaMapTile(TileID);
|
||||||
|
}
|
||||||
|
|
||||||
FCarlaMapTile& ALargeMapManager::GetCarlaMapTile(ULevel* InLevel)
|
FCarlaMapTile& ALargeMapManager::GetCarlaMapTile(ULevel* InLevel)
|
||||||
{
|
{
|
||||||
FCarlaMapTile* Tile = nullptr;
|
FCarlaMapTile* Tile = nullptr;
|
||||||
|
@ -610,11 +616,11 @@ FCarlaMapTile& ALargeMapManager::GetCarlaMapTile(ULevel* InLevel)
|
||||||
return *Tile;
|
return *Tile;
|
||||||
}
|
}
|
||||||
|
|
||||||
FCarlaMapTile* ALargeMapManager::GetCarlaMapTile(FIntVector TileVectorID)
|
FCarlaMapTile& ALargeMapManager::GetCarlaMapTile(FIntVector TileVectorID)
|
||||||
{
|
{
|
||||||
TileID TileID = GetTileID(TileVectorID);
|
TileID TileID = GetTileID(TileVectorID);
|
||||||
FCarlaMapTile* Tile = MapTiles.Find(TileID);
|
FCarlaMapTile* Tile = MapTiles.Find(TileID);
|
||||||
return Tile;
|
return *Tile;
|
||||||
}
|
}
|
||||||
|
|
||||||
FCarlaMapTile* ALargeMapManager::GetCarlaMapTile(TileID TileID)
|
FCarlaMapTile* ALargeMapManager::GetCarlaMapTile(TileID TileID)
|
||||||
|
|
|
@ -38,20 +38,20 @@ struct FActiveActor
|
||||||
FQuat Rotation;
|
FQuat Rotation;
|
||||||
};
|
};
|
||||||
|
|
||||||
USTRUCT()
|
USTRUCT(BlueprintType)
|
||||||
struct FCarlaMapTile
|
struct FCarlaMapTile
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
UPROPERTY(VisibleAnywhere, Category = "Carla Map Tile")
|
UPROPERTY(VisibleAnywhere, BlueprintReadWrite, Category = "Carla Map Tile")
|
||||||
FString Name; // Tile_{TileID_X}_{TileID_Y}
|
FString Name; // Tile_{TileID_X}_{TileID_Y}
|
||||||
|
|
||||||
// Absolute location, does not depend on rebasing
|
// Absolute location, does not depend on rebasing
|
||||||
UPROPERTY(VisibleAnywhere, Category = "Carla Map Tile")
|
UPROPERTY(VisibleAnywhere, BlueprintReadWrite, Category = "Carla Map Tile")
|
||||||
FVector Location{0.0f};
|
FVector Location{0.0f};
|
||||||
// TODO: not FVector
|
// TODO: not FVector
|
||||||
|
|
||||||
UPROPERTY(VisibleAnywhere, Category = "Carla Map Tile")
|
UPROPERTY(VisibleAnywhere, BlueprintReadWrite, Category = "Carla Map Tile")
|
||||||
ULevelStreamingDynamic* StreamingLevel = nullptr;
|
ULevelStreamingDynamic* StreamingLevel = nullptr;
|
||||||
|
|
||||||
bool TilesSpawned = false;
|
bool TilesSpawned = false;
|
||||||
|
@ -166,6 +166,7 @@ public:
|
||||||
|
|
||||||
float GetActorStreamingDistance() const;
|
float GetActorStreamingDistance() const;
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable, Category = "Large Map Manager")
|
||||||
FIntVector GetTileVectorID(FVector TileLocation) const;
|
FIntVector GetTileVectorID(FVector TileLocation) const;
|
||||||
|
|
||||||
FIntVector GetTileVectorID(FDVector TileLocation) const;
|
FIntVector GetTileVectorID(FDVector TileLocation) const;
|
||||||
|
@ -174,6 +175,7 @@ public:
|
||||||
|
|
||||||
FVector GetTileLocation(TileID TileID) const;
|
FVector GetTileLocation(TileID TileID) const;
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable, Category = "Large Map Manager")
|
||||||
FVector GetTileLocation(FIntVector TileVectorID) const;
|
FVector GetTileLocation(FIntVector TileVectorID) const;
|
||||||
|
|
||||||
FDVector GetTileLocationD(TileID TileID) const;
|
FDVector GetTileLocationD(TileID TileID) const;
|
||||||
|
@ -187,11 +189,12 @@ public:
|
||||||
|
|
||||||
TileID GetTileID(FIntVector TileVectorID) const;
|
TileID GetTileID(FIntVector TileVectorID) const;
|
||||||
public:
|
public:
|
||||||
FCarlaMapTile& GetCarlaMapTile(FVector Location);
|
FCarlaMapTile* GetCarlaMapTile(FVector Location);
|
||||||
|
|
||||||
FCarlaMapTile& GetCarlaMapTile(ULevel* InLevel);
|
FCarlaMapTile& GetCarlaMapTile(ULevel* InLevel);
|
||||||
|
|
||||||
FCarlaMapTile* GetCarlaMapTile(FIntVector TileVectorID);
|
UFUNCTION(BlueprintCallable, Category = "Large Map Manager")
|
||||||
|
FCarlaMapTile& GetCarlaMapTile(FIntVector TileVectorID);
|
||||||
|
|
||||||
FCarlaMapTile* GetCarlaMapTile(TileID TileID);
|
FCarlaMapTile* GetCarlaMapTile(TileID TileID);
|
||||||
|
|
||||||
|
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -6,6 +6,7 @@ using UnrealBuildTool;
|
||||||
|
|
||||||
public class CarlaTools : ModuleRules
|
public class CarlaTools : ModuleRules
|
||||||
{
|
{
|
||||||
|
bool UsingHoudini = true;
|
||||||
private bool IsWindows(ReadOnlyTargetRules Target)
|
private bool IsWindows(ReadOnlyTargetRules Target)
|
||||||
{
|
{
|
||||||
return (Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32);
|
return (Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32);
|
||||||
|
@ -66,10 +67,24 @@ public class CarlaTools : ModuleRules
|
||||||
"Carla",
|
"Carla",
|
||||||
"PhysXVehicles",
|
"PhysXVehicles",
|
||||||
"Json",
|
"Json",
|
||||||
"JsonUtilities"
|
"JsonUtilities",
|
||||||
|
"Networking",
|
||||||
|
"Sockets",
|
||||||
|
"RHI",
|
||||||
|
"RenderCore"
|
||||||
// ... add private dependencies that you statically link with here ...
|
// ... add private dependencies that you statically link with here ...
|
||||||
}
|
}
|
||||||
);
|
);
|
||||||
|
if(UsingHoudini)
|
||||||
|
{
|
||||||
|
PrivateDependencyModuleNames.AddRange(
|
||||||
|
new string[]
|
||||||
|
{
|
||||||
|
"HoudiniEngine",
|
||||||
|
"HoudiniEngineEditor",
|
||||||
|
"HoudiniEngineRuntime"
|
||||||
|
});
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
DynamicallyLoadedModuleNames.AddRange(
|
DynamicallyLoadedModuleNames.AddRange(
|
||||||
|
|
|
@ -0,0 +1,82 @@
|
||||||
|
// Copyright (c) 2023 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||||
|
// de Barcelona (UAB).
|
||||||
|
//
|
||||||
|
// This work is licensed under the terms of the MIT license.
|
||||||
|
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||||
|
|
||||||
|
#include "HoudiniImportNodeWrapper.h"
|
||||||
|
#include "HoudiniAsset.h"
|
||||||
|
|
||||||
|
UHoudiniImportNodeWrapper::UHoudiniImportNodeWrapper(const FObjectInitializer& ObjectInitializer)
|
||||||
|
{
|
||||||
|
if ( HasAnyFlags(RF_ClassDefaultObject) == false )
|
||||||
|
{
|
||||||
|
AddToRoot();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
UHoudiniImportNodeWrapper* UHoudiniImportNodeWrapper::ImportBuildings(
|
||||||
|
UObject* InHoudiniObject,
|
||||||
|
const FTransform& InInstantiateAt,
|
||||||
|
UObject* InWorldContextObject,
|
||||||
|
const FString& MapName, const FString& OSMFilePath,
|
||||||
|
float Latitude, float Longitude,
|
||||||
|
int ClusterSize, int CurrentCluster)
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Start building import"));
|
||||||
|
UHoudiniAsset* InHoudiniAsset = Cast<UHoudiniAsset>(InHoudiniObject);
|
||||||
|
if (!InHoudiniAsset)
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaTools, Error, TEXT("Houdini asset not valid"));
|
||||||
|
return nullptr;
|
||||||
|
}
|
||||||
|
UHoudiniImportNodeWrapper* WrapperNode = NewObject<UHoudiniImportNodeWrapper>();
|
||||||
|
|
||||||
|
TMap<FName, FHoudiniParameterTuple> InParameters =
|
||||||
|
{ {"userMapName", FHoudiniParameterTuple(MapName)},
|
||||||
|
{"osmPath", FHoudiniParameterTuple(OSMFilePath)},
|
||||||
|
{"clusterSize", FHoudiniParameterTuple(ClusterSize)},
|
||||||
|
{"displayedCluster", FHoudiniParameterTuple(CurrentCluster)},
|
||||||
|
{"startCooking", FHoudiniParameterTuple(true)},
|
||||||
|
{"lat", FHoudiniParameterTuple(Latitude)},
|
||||||
|
{"lon", FHoudiniParameterTuple(Longitude)}};
|
||||||
|
|
||||||
|
WrapperNode->HDANode =
|
||||||
|
UHoudiniPublicAPIProcessHDANode::ProcessHDA(
|
||||||
|
InHoudiniAsset, InInstantiateAt, InParameters, {}, {},
|
||||||
|
InWorldContextObject, nullptr,
|
||||||
|
true, true);
|
||||||
|
WrapperNode->HDANode->Completed.AddDynamic(WrapperNode, &UHoudiniImportNodeWrapper::HandleCompleted);
|
||||||
|
WrapperNode->HDANode->Failed.AddDynamic(WrapperNode, &UHoudiniImportNodeWrapper::HandleFailed);
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("HDA node created"));
|
||||||
|
return WrapperNode;
|
||||||
|
}
|
||||||
|
|
||||||
|
void UHoudiniImportNodeWrapper::Activate()
|
||||||
|
{
|
||||||
|
HDANode->Activate();
|
||||||
|
}
|
||||||
|
|
||||||
|
void UHoudiniImportNodeWrapper::HandleCompleted(
|
||||||
|
UHoudiniPublicAPIAssetWrapper* ,
|
||||||
|
bool bCookSuccess, bool bBakeSuccess)
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Generation Finished"));
|
||||||
|
if (Completed.IsBound())
|
||||||
|
{
|
||||||
|
Completed.Broadcast(bCookSuccess, bBakeSuccess);
|
||||||
|
}
|
||||||
|
RemoveFromRoot();
|
||||||
|
}
|
||||||
|
|
||||||
|
void UHoudiniImportNodeWrapper::HandleFailed(
|
||||||
|
UHoudiniPublicAPIAssetWrapper* ,
|
||||||
|
bool bCookSuccess, bool bBakeSuccess)
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Generation failed"));
|
||||||
|
if (Failed.IsBound())
|
||||||
|
{
|
||||||
|
Failed.Broadcast(bCookSuccess, bBakeSuccess);
|
||||||
|
}
|
||||||
|
RemoveFromRoot();
|
||||||
|
}
|
|
@ -0,0 +1,132 @@
|
||||||
|
// Copyright (c) 2023 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||||
|
// de Barcelona (UAB).
|
||||||
|
//
|
||||||
|
// This work is licensed under the terms of the MIT license.
|
||||||
|
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||||
|
|
||||||
|
#include "HoudiniImporterWidget.h"
|
||||||
|
|
||||||
|
#include "EditorLevelUtils.h"
|
||||||
|
#include "Kismet/GameplayStatics.h"
|
||||||
|
#include "Kismet/KismetSystemLibrary.h"
|
||||||
|
#include "FileHelpers.h"
|
||||||
|
|
||||||
|
void UHoudiniImporterWidget::CreateSubLevels(ALargeMapManager* LargeMapManager)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void UHoudiniImporterWidget::MoveActorsToSubLevel(TArray<AActor*> Actors, ALargeMapManager* LargeMapManager)
|
||||||
|
{
|
||||||
|
TMap<FCarlaMapTile*, TArray<AActor*>> ActorsToMove;
|
||||||
|
for (AActor* Actor : Actors)
|
||||||
|
{
|
||||||
|
UHierarchicalInstancedStaticMeshComponent* Component
|
||||||
|
= Cast<UHierarchicalInstancedStaticMeshComponent>(
|
||||||
|
Actor->GetComponentByClass(
|
||||||
|
UHierarchicalInstancedStaticMeshComponent::StaticClass()));
|
||||||
|
FVector ActorLocation = Actor->GetActorLocation();
|
||||||
|
if (Component)
|
||||||
|
{
|
||||||
|
ActorLocation = FVector(0);
|
||||||
|
for(int32 i = 0; i < Component->GetInstanceCount(); ++i)
|
||||||
|
{
|
||||||
|
FTransform Transform;
|
||||||
|
Component->GetInstanceTransform(i, Transform, true);
|
||||||
|
ActorLocation = ActorLocation + Transform.GetTranslation();
|
||||||
|
}
|
||||||
|
ActorLocation = ActorLocation / Component->GetInstanceCount();
|
||||||
|
}
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Actor at location %s"),
|
||||||
|
*ActorLocation.ToString());
|
||||||
|
FCarlaMapTile* Tile = LargeMapManager->GetCarlaMapTile(ActorLocation);
|
||||||
|
if(!Tile)
|
||||||
|
{
|
||||||
|
UE_LOG(LogCarlaTools, Error, TEXT("Error: actor in location %s is outside the map"),
|
||||||
|
*ActorLocation.ToString());
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if(Component)
|
||||||
|
{
|
||||||
|
UpdateInstancedMeshCoordinates(Component, Tile->Location);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
UpdateGenericActorCoordinates(Actor, Tile->Location);
|
||||||
|
}
|
||||||
|
ActorsToMove.FindOrAdd(Tile).Add(Actor);
|
||||||
|
}
|
||||||
|
|
||||||
|
for (auto& Element : ActorsToMove)
|
||||||
|
{
|
||||||
|
FCarlaMapTile* Tile = Element.Key;
|
||||||
|
TArray<AActor*> ActorList = Element.Value;
|
||||||
|
ULevelStreamingDynamic* StreamingLevel = Tile->StreamingLevel;
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Got Tile %s in location %s"),
|
||||||
|
*StreamingLevel->PackageNameToLoad.ToString(), *Tile->Location.ToString());
|
||||||
|
StreamingLevel->bShouldBlockOnLoad = true;
|
||||||
|
StreamingLevel->SetShouldBeVisible(true);
|
||||||
|
StreamingLevel->SetShouldBeLoaded(true);
|
||||||
|
ULevelStreaming* Level =
|
||||||
|
UEditorLevelUtils::AddLevelToWorld(
|
||||||
|
GetWorld(), *Tile->Name, ULevelStreamingDynamic::StaticClass(), FTransform());
|
||||||
|
|
||||||
|
int MovedActors = UEditorLevelUtils::MoveActorsToLevel(ActorList, Level, false, false);
|
||||||
|
// StreamingLevel->SetShouldBeLoaded(false);
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Moved %d actors"), MovedActors);
|
||||||
|
FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr);
|
||||||
|
UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void UHoudiniImporterWidget::UpdateGenericActorCoordinates(
|
||||||
|
AActor* Actor, FVector TileOrigin)
|
||||||
|
{
|
||||||
|
FVector LocalLocation = Actor->GetActorLocation() - TileOrigin;
|
||||||
|
Actor->SetActorLocation(LocalLocation);
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("New location %s"),
|
||||||
|
*LocalLocation.ToString());
|
||||||
|
}
|
||||||
|
|
||||||
|
void UHoudiniImporterWidget::UpdateInstancedMeshCoordinates(
|
||||||
|
UHierarchicalInstancedStaticMeshComponent* Component, FVector TileOrigin)
|
||||||
|
{
|
||||||
|
TArray<FTransform> NewTransforms;
|
||||||
|
for(int32 i = 0; i < Component->GetInstanceCount(); ++i)
|
||||||
|
{
|
||||||
|
FTransform Transform;
|
||||||
|
Component->GetInstanceTransform(i, Transform, true);
|
||||||
|
Transform.AddToTranslation(-TileOrigin);
|
||||||
|
NewTransforms.Add(Transform);
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("New instance location %s"),
|
||||||
|
*Transform.GetTranslation().ToString());
|
||||||
|
}
|
||||||
|
Component->BatchUpdateInstancesTransforms(0, NewTransforms, true, true, true);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool UHoudiniImporterWidget::GetNumberOfClusters(
|
||||||
|
TArray<AActor*> ActorList, int& OutNumClusters)
|
||||||
|
{
|
||||||
|
|
||||||
|
for (AActor* Actor : ActorList)
|
||||||
|
{
|
||||||
|
FString ObjectName = UKismetSystemLibrary::GetObjectName(Actor);
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("Searching in string %s"), *ObjectName);
|
||||||
|
if(ObjectName.StartsWith("b"))
|
||||||
|
{
|
||||||
|
int Index = ObjectName.Find("of");
|
||||||
|
if(Index == -1)
|
||||||
|
{
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
UE_LOG(LogCarlaTools, Log, TEXT("found of substr at %d"), Index);
|
||||||
|
FString NumClusterString = ObjectName.Mid(Index+2, ObjectName.Len());
|
||||||
|
OutNumClusters = FCString::Atoi(*NumClusterString);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
UE_LOG(LogCarlaTools, Warning, TEXT("Num clusters not found"));
|
||||||
|
OutNumClusters = -1;
|
||||||
|
return false;
|
||||||
|
}
|
|
@ -917,7 +917,7 @@ bool UMapGeneratorWidget::CreateTilesMaps(const FMapGeneratorMetaInfo& MetaInfo)
|
||||||
|
|
||||||
// Terrain ROI
|
// Terrain ROI
|
||||||
FRoiTile ThisTileIndex(i, j);
|
FRoiTile ThisTileIndex(i, j);
|
||||||
if(FRegionOfInterest::IsTileInRegionsSet(ThisTileIndex, MetaInfo.TerrainRoisMap))
|
if(FCarlaRegionOfInterest::IsTileInRegionsSet(ThisTileIndex, MetaInfo.TerrainRoisMap))
|
||||||
{
|
{
|
||||||
FTerrainROI TileRegion = MetaInfo.TerrainRoisMap[ThisTileIndex];
|
FTerrainROI TileRegion = MetaInfo.TerrainRoisMap[ThisTileIndex];
|
||||||
|
|
||||||
|
@ -1156,7 +1156,7 @@ bool UMapGeneratorWidget::CookVegetationToTiles(const FMapGeneratorMetaInfo& Met
|
||||||
|
|
||||||
FRoiTile ThisTileIndex(TileIndexX, TileIndexY);
|
FRoiTile ThisTileIndex(TileIndexX, TileIndexY);
|
||||||
TArray<UProceduralFoliageSpawner*> FoliageSpawnersToCook;
|
TArray<UProceduralFoliageSpawner*> FoliageSpawnersToCook;
|
||||||
if(FRegionOfInterest::IsTileInRegionsSet(ThisTileIndex, MetaInfo.VegetationRoisMap))
|
if(FCarlaRegionOfInterest::IsTileInRegionsSet(ThisTileIndex, MetaInfo.VegetationRoisMap))
|
||||||
{
|
{
|
||||||
FVegetationROI TileRegion = MetaInfo.VegetationRoisMap[ThisTileIndex];
|
FVegetationROI TileRegion = MetaInfo.VegetationRoisMap[ThisTileIndex];
|
||||||
FoliageSpawnersToCook = TileRegion.GetFoliageSpawners();
|
FoliageSpawnersToCook = TileRegion.GetFoliageSpawners();
|
||||||
|
|
|
@ -0,0 +1,211 @@
|
||||||
|
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). This work is licensed under the terms of the MIT license. For a copy, see <https://opensource.org/licenses/MIT>.
|
||||||
|
|
||||||
|
|
||||||
|
#include "MapPreviewUserWidget.h"
|
||||||
|
|
||||||
|
#if PLATFORM_WINDOWS
|
||||||
|
#include "AllowWindowsPlatformTypes.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "GenericPlatform/GenericPlatformMath.h"
|
||||||
|
//#include "GenericPlatform/GenericPlatformProcess.h"
|
||||||
|
#include "GenericPlatform/GenericPlatformFile.h"
|
||||||
|
|
||||||
|
#include "Sockets.h"
|
||||||
|
#include "Interfaces/IPv4/IPv4Address.h"
|
||||||
|
#include "Common/TcpSocketBuilder.h"
|
||||||
|
#include "SocketSubsystem.h"
|
||||||
|
#include "SocketTypes.h"
|
||||||
|
|
||||||
|
#if PLATFORM_WINDOWS
|
||||||
|
#include "HideWindowsPlatformTypes.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "Engine/Texture2D.h"
|
||||||
|
#include "Containers/ResourceArray.h"
|
||||||
|
#include "Containers/UnrealString.h"
|
||||||
|
#include "Rendering/Texture2DResource.h"
|
||||||
|
#include "RHI.h"
|
||||||
|
#include "RHICommandList.h"
|
||||||
|
#include "RenderingThread.h"
|
||||||
|
#include "Misc/Timespan.h"
|
||||||
|
#include "Containers/UnrealString.h"
|
||||||
|
#include "Misc/Paths.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//#include "Unix/UnixPlatformProcess.h"
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::CreateTexture()
|
||||||
|
{
|
||||||
|
if(!MapTexture)
|
||||||
|
{
|
||||||
|
MapTexture = UTexture2D::CreateTransient(512,512,EPixelFormat::PF_R8G8B8A8,"MapTextureRendered");
|
||||||
|
MapTexture->UpdateResource();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::ConnectToSocket(FString DatabasePath, FString StylesheetPath, int Size)
|
||||||
|
{
|
||||||
|
//FSocket* Socket = FSocket::CreateTCPConnection(nullptr, TEXT("OSMRendererSocket"));
|
||||||
|
Socket = FTcpSocketBuilder(TEXT("OSMRendererSocket")).AsReusable();
|
||||||
|
FIPv4Address RemoteAddress;
|
||||||
|
FIPv4Address::Parse(FIPv4Address::InternalLoopback.ToString(), RemoteAddress);
|
||||||
|
TSharedRef<FInternetAddr> RemoteAddr = ISocketSubsystem::Get(PLATFORM_SOCKETSUBSYSTEM)->CreateInternetAddr();
|
||||||
|
RemoteAddr->SetIp(RemoteAddress.Value);
|
||||||
|
RemoteAddr->SetPort(5000);
|
||||||
|
|
||||||
|
// Connect to the remote server
|
||||||
|
bool Connected = Socket->Connect(*RemoteAddr);
|
||||||
|
if (!Connected)
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Error, TEXT("Error connecting to remote server"));
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Send a message
|
||||||
|
FString Message = "-C " + DatabasePath + " " + StylesheetPath + " " + FString::FromInt(Size);
|
||||||
|
SendStr(Message);
|
||||||
|
UE_LOG(LogTemp, Log, TEXT("Configuration Completed"));
|
||||||
|
}
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::RenderMap(FString Latitude, FString Longitude, FString Zoom)
|
||||||
|
{
|
||||||
|
FString Message = "-R " + Latitude + " " + Longitude + " " + Zoom;
|
||||||
|
//FString Message = "-R 40.415 -3.702 100000";
|
||||||
|
SendStr(Message);
|
||||||
|
|
||||||
|
TArray<uint8_t> ReceivedData;
|
||||||
|
uint32 ReceivedDataSize;
|
||||||
|
|
||||||
|
if(Socket->Wait(ESocketWaitConditions::WaitForRead, FTimespan::FromSeconds(5)))
|
||||||
|
{
|
||||||
|
while(Socket->HasPendingData(ReceivedDataSize))
|
||||||
|
{
|
||||||
|
int32 BytesReceived = 0;
|
||||||
|
TArray<uint8_t> ThisReceivedData;
|
||||||
|
ThisReceivedData.Init(0, FMath::Min(ReceivedDataSize, uint32(512*512*4)));
|
||||||
|
bool bRecv = Socket->Recv(ThisReceivedData.GetData(), ThisReceivedData.Num(), BytesReceived);
|
||||||
|
if (!bRecv)
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Error, TEXT("Error receiving message"));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Log, TEXT("Received %d bytes. %d"), BytesReceived, ReceivedDataSize);
|
||||||
|
ReceivedData.Append(ThisReceivedData);
|
||||||
|
UE_LOG(LogTemp, Log, TEXT("Size of Data: %d"), ReceivedData.Num());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// TODO: Move to function
|
||||||
|
if(ReceivedData.Num() > 0)
|
||||||
|
{
|
||||||
|
ENQUEUE_RENDER_COMMAND(UpdateDynamicTextureCode)
|
||||||
|
(
|
||||||
|
[NewData=ReceivedData, Texture=MapTexture](auto &InRHICmdList) mutable
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Log, TEXT("RHI: Updating texture"));
|
||||||
|
FUpdateTextureRegion2D Region;
|
||||||
|
Region.SrcX = 0;
|
||||||
|
Region.SrcY = 0;
|
||||||
|
Region.DestX = 0;
|
||||||
|
Region.DestY = 0;
|
||||||
|
Region.Width = Texture->GetSizeX();
|
||||||
|
Region.Height = Texture->GetSizeY();
|
||||||
|
|
||||||
|
FTexture2DResource* Resource = (FTexture2DResource*)Texture->Resource;
|
||||||
|
RHIUpdateTexture2D(Resource->GetTexture2DRHI(), 0, Region, Region.Width * sizeof(uint8_t) * 4, &NewData[0]);
|
||||||
|
}
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
FString UMapPreviewUserWidget::RecvCornersLatLonCoords()
|
||||||
|
{
|
||||||
|
SendStr("-L");
|
||||||
|
uint8 TempBuffer[40];
|
||||||
|
int32 BytesReceived = 0;
|
||||||
|
if(Socket->Wait(ESocketWaitConditions::WaitForRead, FTimespan::FromSeconds(5)))
|
||||||
|
{
|
||||||
|
bool bRecv = Socket->Recv(TempBuffer, 40, BytesReceived);
|
||||||
|
if(!bRecv)
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Error, TEXT("Error receiving LatLon message"));
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
|
||||||
|
FString CoordStr = FString(UTF8_TO_TCHAR((char*)TempBuffer));
|
||||||
|
return CoordStr;
|
||||||
|
}
|
||||||
|
return "";
|
||||||
|
}
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::Shutdown()
|
||||||
|
{
|
||||||
|
// Close the socket
|
||||||
|
Socket->Close();
|
||||||
|
}
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::OpenServer()
|
||||||
|
{
|
||||||
|
|
||||||
|
/*FPlatformProcess::CreateProc(
|
||||||
|
TEXT("/home/adas/carla/osm-world-renderer/build/osm-world-renderer"),
|
||||||
|
nullptr, // Args
|
||||||
|
true, // if true process will have its own window
|
||||||
|
false, // if true it will be minimized
|
||||||
|
false, // if true it will be hidden in task bar
|
||||||
|
nullptr, // filled with PID
|
||||||
|
0, // priority
|
||||||
|
nullptr, // directory to place after running the program
|
||||||
|
nullptr // redirection pipe
|
||||||
|
);*/
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::CloseServer()
|
||||||
|
{
|
||||||
|
SendStr("-X");
|
||||||
|
}
|
||||||
|
|
||||||
|
bool UMapPreviewUserWidget::SendStr(FString Msg)
|
||||||
|
{
|
||||||
|
if(!Socket)
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Error, TEXT("Error. No socket."));
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string MessageStr = std::string(TCHAR_TO_UTF8(*Msg));
|
||||||
|
int32 BytesSent = 0;
|
||||||
|
bool bSent = Socket->Send((uint8*)MessageStr.c_str(), MessageStr.size(), BytesSent);
|
||||||
|
if (!bSent)
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Error, TEXT("Error sending message"));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
UE_LOG(LogTemp, Log, TEXT("Sent %d bytes"), BytesSent);
|
||||||
|
}
|
||||||
|
return bSent;
|
||||||
|
}
|
||||||
|
|
||||||
|
void UMapPreviewUserWidget::UpdateLatLonCoordProperties()
|
||||||
|
{
|
||||||
|
FString CoordStr = RecvCornersLatLonCoords();
|
||||||
|
UE_LOG(LogTemp, Log, TEXT("Received laton [%s] with size %d"), *CoordStr, CoordStr.Len());
|
||||||
|
|
||||||
|
TArray<FString> CoordsArray;
|
||||||
|
CoordStr.ParseIntoArray(CoordsArray, TEXT("&"), true);
|
||||||
|
|
||||||
|
check(CoordsArray.Num() == 4);
|
||||||
|
|
||||||
|
TopRightLat = FCString::Atof(*CoordsArray[0]);
|
||||||
|
TopRightLon = FCString::Atof(*CoordsArray[1]);
|
||||||
|
BottomLeftLat = FCString::Atof(*CoordsArray[2]);
|
||||||
|
BottomLeftLon = FCString::Atof(*CoordsArray[3]);
|
||||||
|
}
|
|
@ -230,6 +230,21 @@ void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>&
|
||||||
TempPMC->bUseComplexAsSimpleCollision = true;
|
TempPMC->bUseComplexAsSimpleCollision = true;
|
||||||
TempPMC->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
|
TempPMC->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
|
||||||
|
|
||||||
|
FVector MeshCentroid = FVector(0,0,0);
|
||||||
|
for( auto Vertex : Mesh->GetVertices() )
|
||||||
|
{
|
||||||
|
MeshCentroid += Vertex.ToFVector();
|
||||||
|
}
|
||||||
|
|
||||||
|
MeshCentroid /= Mesh->GetVertices().size();
|
||||||
|
|
||||||
|
for( auto& Vertex : Mesh->GetVertices() )
|
||||||
|
{
|
||||||
|
Vertex.x -= MeshCentroid.X;
|
||||||
|
Vertex.y -= MeshCentroid.Y;
|
||||||
|
Vertex.z -= MeshCentroid.Z;
|
||||||
|
}
|
||||||
|
|
||||||
const FProceduralCustomMesh MeshData = *Mesh;
|
const FProceduralCustomMesh MeshData = *Mesh;
|
||||||
TempPMC->CreateMeshSection_LinearColor(
|
TempPMC->CreateMeshSection_LinearColor(
|
||||||
0,
|
0,
|
||||||
|
@ -240,6 +255,7 @@ void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>&
|
||||||
TArray<FLinearColor>(), // VertexColor
|
TArray<FLinearColor>(), // VertexColor
|
||||||
TArray<FProcMeshTangent>(), // Tangents
|
TArray<FProcMeshTangent>(), // Tangents
|
||||||
true); // Create collision
|
true); // Create collision
|
||||||
|
TempActor->SetActorLocation(MeshCentroid * 100);
|
||||||
ActorMeshList.Add(TempActor);
|
ActorMeshList.Add(TempActor);
|
||||||
|
|
||||||
RoadType.Add(LaneTypeToFString(PairMap.first));
|
RoadType.Add(LaneTypeToFString(PairMap.first));
|
||||||
|
@ -249,6 +265,7 @@ void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>&
|
||||||
|
|
||||||
end = FPlatformTime::Seconds();
|
end = FPlatformTime::Seconds();
|
||||||
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("Mesh spawnning and translation code executed in %f seconds."), end - start);
|
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("Mesh spawnning and translation code executed in %f seconds."), end - start);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void UOpenDriveToMap::GenerateSpawnPoints( const boost::optional<carla::road::Map>& CarlaMap )
|
void UOpenDriveToMap::GenerateSpawnPoints( const boost::optional<carla::road::Map>& CarlaMap )
|
||||||
|
@ -351,7 +368,6 @@ TArray<UStaticMesh*> UOpenDriveToMap::CreateStaticMeshAssets()
|
||||||
double end = FPlatformTime::Seconds();
|
double end = FPlatformTime::Seconds();
|
||||||
|
|
||||||
IPlatformFile& PlatformFile = FPlatformFileManager::Get().GetPlatformFile();
|
IPlatformFile& PlatformFile = FPlatformFileManager::Get().GetPlatformFile();
|
||||||
|
|
||||||
TArray<UStaticMesh*> StaticMeshes;
|
TArray<UStaticMesh*> StaticMeshes;
|
||||||
|
|
||||||
double BuildMeshDescriptionTime = 0.0f;
|
double BuildMeshDescriptionTime = 0.0f;
|
||||||
|
@ -407,7 +423,6 @@ TArray<UStaticMesh*> UOpenDriveToMap::CreateStaticMeshAssets()
|
||||||
SrcModel.BuildSettings.DstLightmapIndex = 1;
|
SrcModel.BuildSettings.DstLightmapIndex = 1;
|
||||||
CurrentStaticMesh->CreateMeshDescription(0, MoveTemp(MeshDescription));
|
CurrentStaticMesh->CreateMeshDescription(0, MoveTemp(MeshDescription));
|
||||||
CurrentStaticMesh->CommitMeshDescription(0);
|
CurrentStaticMesh->CommitMeshDescription(0);
|
||||||
|
|
||||||
end = FPlatformTime::Seconds();
|
end = FPlatformTime::Seconds();
|
||||||
MeshInitTime += end - start;
|
MeshInitTime += end - start;
|
||||||
start = FPlatformTime::Seconds();
|
start = FPlatformTime::Seconds();
|
||||||
|
@ -457,7 +472,6 @@ TArray<UStaticMesh*> UOpenDriveToMap::CreateStaticMeshAssets()
|
||||||
// Notify asset registry of new asset
|
// Notify asset registry of new asset
|
||||||
FAssetRegistryModule::AssetCreated(CurrentStaticMesh);
|
FAssetRegistryModule::AssetCreated(CurrentStaticMesh);
|
||||||
UPackage::SavePackage(Package, CurrentStaticMesh, EObjectFlags::RF_Public | EObjectFlags::RF_Standalone, *MeshName, GError, nullptr, true, true, SAVE_NoError);
|
UPackage::SavePackage(Package, CurrentStaticMesh, EObjectFlags::RF_Public | EObjectFlags::RF_Standalone, *MeshName, GError, nullptr, true, true, SAVE_NoError);
|
||||||
|
|
||||||
end = FPlatformTime::Seconds();
|
end = FPlatformTime::Seconds();
|
||||||
PackSaveTime += end - start;
|
PackSaveTime += end - start;
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,64 @@
|
||||||
|
// Copyright (c) 2023 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||||
|
// de Barcelona (UAB).
|
||||||
|
//
|
||||||
|
// This work is licensed under the terms of the MIT license.
|
||||||
|
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "CoreMinimal.h"
|
||||||
|
#include "Kismet/BlueprintAsyncActionBase.h"
|
||||||
|
|
||||||
|
#include "HoudiniPublicAPIProcessHDANode.h"
|
||||||
|
|
||||||
|
#include "HoudiniImportNodeWrapper.generated.h"
|
||||||
|
|
||||||
|
// Delegate type for output pins on the node.
|
||||||
|
DECLARE_DYNAMIC_MULTICAST_DELEGATE_TwoParams(FOnProcessImporterOutputPinDelegate, const bool, bCookSuccess, const bool, bBakeSuccess);
|
||||||
|
|
||||||
|
UCLASS()
|
||||||
|
class CARLATOOLS_API UHoudiniImportNodeWrapper : public UBlueprintAsyncActionBase
|
||||||
|
{
|
||||||
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
public:
|
||||||
|
|
||||||
|
UHoudiniImportNodeWrapper(const FObjectInitializer& ObjectInitializer);
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable, meta=(AdvancedDisplay=5,AutoCreateRefTerm="InInstantiateAt",BlueprintInternalUseOnly="true", WorldContext="WorldContextObject"), Category="Houdini Importer")
|
||||||
|
static UHoudiniImportNodeWrapper* ImportBuildings(
|
||||||
|
UObject* InHoudiniAsset,
|
||||||
|
const FTransform& InInstantiateAt,
|
||||||
|
UObject* InWorldContextObject,
|
||||||
|
const FString& MapName, const FString& OSMFilePath,
|
||||||
|
float Latitude, float Longitude,
|
||||||
|
int ClusterSize, int CurrentCluster);
|
||||||
|
|
||||||
|
// Fires on task completed
|
||||||
|
UPROPERTY(BlueprintAssignable, Category="Houdini|Public API")
|
||||||
|
FOnProcessImporterOutputPinDelegate Completed;
|
||||||
|
|
||||||
|
// Fires if the task fails
|
||||||
|
UPROPERTY(BlueprintAssignable, Category="Houdini|Public API")
|
||||||
|
FOnProcessImporterOutputPinDelegate Failed;
|
||||||
|
|
||||||
|
virtual void Activate() override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
UFUNCTION()
|
||||||
|
void HandleCompleted(
|
||||||
|
UHoudiniPublicAPIAssetWrapper* AssetWrapper,
|
||||||
|
bool bCookSuccess,
|
||||||
|
bool bBakeSuccess);
|
||||||
|
|
||||||
|
UFUNCTION()
|
||||||
|
void HandleFailed(
|
||||||
|
UHoudiniPublicAPIAssetWrapper* AssetWrapper,
|
||||||
|
bool bCookSuccess,
|
||||||
|
bool bBakeSuccess);
|
||||||
|
|
||||||
|
private:
|
||||||
|
UHoudiniPublicAPIProcessHDANode* HDANode;
|
||||||
|
|
||||||
|
};
|
|
@ -0,0 +1,38 @@
|
||||||
|
// Copyright (c) 2023 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||||
|
// de Barcelona (UAB).
|
||||||
|
//
|
||||||
|
// This work is licensed under the terms of the MIT license.
|
||||||
|
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "CoreMinimal.h"
|
||||||
|
#include "EditorUtilityWidget.h"
|
||||||
|
#include "Carla/MapGen/LargeMapManager.h"
|
||||||
|
#include "Components/HierarchicalInstancedStaticMeshComponent.h"
|
||||||
|
#include "Engine/LevelStreaming.h"
|
||||||
|
|
||||||
|
#include "HoudiniImporterWidget.generated.h"
|
||||||
|
|
||||||
|
UCLASS(BlueprintType)
|
||||||
|
class CARLATOOLS_API UHoudiniImporterWidget : public UEditorUtilityWidget
|
||||||
|
{
|
||||||
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable, Category="HoudiniImporterWidget")
|
||||||
|
void CreateSubLevels(ALargeMapManager* LargeMapManager);
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable, Category="HoudiniImporterWidget")
|
||||||
|
void MoveActorsToSubLevel(TArray<AActor*> Actors, ALargeMapManager* LargeMapManager);
|
||||||
|
|
||||||
|
void UpdateGenericActorCoordinates(AActor* Actor, FVector TileOrigin);
|
||||||
|
|
||||||
|
void UpdateInstancedMeshCoordinates(
|
||||||
|
UHierarchicalInstancedStaticMeshComponent* Component, FVector TileOrigin);
|
||||||
|
|
||||||
|
// Gets the total number of cluster from the actor name following the following scheme
|
||||||
|
// b{builsing}c{cluster}of{clustersize}
|
||||||
|
UFUNCTION(BlueprintCallable, Category="HoudiniImporterWidget")
|
||||||
|
bool GetNumberOfClusters(TArray<AActor*> ActorList, int& OutNumClusters);
|
||||||
|
|
||||||
|
};
|
|
@ -0,0 +1,57 @@
|
||||||
|
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de Barcelona (UAB). This work is licensed under the terms of the MIT license. For a copy, see <https://opensource.org/licenses/MIT>.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "CoreMinimal.h"
|
||||||
|
#include "Blueprint/UserWidget.h"
|
||||||
|
#include "MapPreviewUserWidget.generated.h"
|
||||||
|
|
||||||
|
class FSocket;
|
||||||
|
class UTexture2D;
|
||||||
|
|
||||||
|
UCLASS()
|
||||||
|
class CARLATOOLS_API UMapPreviewUserWidget : public UUserWidget
|
||||||
|
{
|
||||||
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
private:
|
||||||
|
FSocket* Socket;
|
||||||
|
|
||||||
|
bool SendStr(FString Msg);
|
||||||
|
FString RecvCornersLatLonCoords();
|
||||||
|
|
||||||
|
public:
|
||||||
|
UPROPERTY(EditAnywhere, BlueprintReadWrite)
|
||||||
|
UTexture2D* MapTexture;
|
||||||
|
|
||||||
|
UPROPERTY(BlueprintReadOnly)
|
||||||
|
float TopRightLat = 0.f;
|
||||||
|
UPROPERTY(BlueprintReadOnly)
|
||||||
|
float TopRightLon = 0.f;
|
||||||
|
UPROPERTY(BlueprintReadOnly)
|
||||||
|
float BottomLeftLat = 0.f;
|
||||||
|
UPROPERTY(BlueprintReadOnly)
|
||||||
|
float BottomLeftLon = 0.f;
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void ConnectToSocket(FString DatabasePath, FString StylesheetPath, int Size);
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void RenderMap(FString Latitude, FString Longitude, FString Zoom);
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void Shutdown();
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void CreateTexture();
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void OpenServer();
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void CloseServer();
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable)
|
||||||
|
void UpdateLatLonCoordProperties();
|
||||||
|
|
||||||
|
};
|
|
@ -5,6 +5,7 @@
|
||||||
#include "CoreMinimal.h"
|
#include "CoreMinimal.h"
|
||||||
#include "Blueprint/UserWidget.h"
|
#include "Blueprint/UserWidget.h"
|
||||||
#include "ProceduralMeshComponent.h"
|
#include "ProceduralMeshComponent.h"
|
||||||
|
#include "Math/Vector2D.h"
|
||||||
|
|
||||||
#include <compiler/disable-ue4-macros.h>
|
#include <compiler/disable-ue4-macros.h>
|
||||||
#include <boost/optional.hpp>
|
#include <boost/optional.hpp>
|
||||||
|
@ -44,6 +45,9 @@ public:
|
||||||
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||||
FString Url;
|
FString Url;
|
||||||
|
|
||||||
|
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||||
|
FVector2D OriginGeoCoordinates;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual void NativeConstruct() override;
|
virtual void NativeConstruct() override;
|
||||||
virtual void NativeDestruct() override;
|
virtual void NativeDestruct() override;
|
||||||
|
|
|
@ -111,7 +111,7 @@ FORCEINLINE uint32 GetTypeHash(const FRoiTile& Thing)
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
USTRUCT(BlueprintType)
|
USTRUCT(BlueprintType)
|
||||||
struct CARLATOOLS_API FRegionOfInterest
|
struct CARLATOOLS_API FCarlaRegionOfInterest
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
@ -121,7 +121,7 @@ struct CARLATOOLS_API FRegionOfInterest
|
||||||
UPROPERTY(BlueprintReadWrite)
|
UPROPERTY(BlueprintReadWrite)
|
||||||
TEnumAsByte<ERegionOfInterestType> RegionType = ERegionOfInterestType::NONE_REGION;
|
TEnumAsByte<ERegionOfInterestType> RegionType = ERegionOfInterestType::NONE_REGION;
|
||||||
|
|
||||||
FRegionOfInterest()
|
FCarlaRegionOfInterest()
|
||||||
{
|
{
|
||||||
TilesList.Empty();
|
TilesList.Empty();
|
||||||
}
|
}
|
||||||
|
@ -141,13 +141,13 @@ struct CARLATOOLS_API FRegionOfInterest
|
||||||
template <typename R>
|
template <typename R>
|
||||||
static FORCEINLINE bool IsTileInRegionsSet(FRoiTile RoiTile, TMap<FRoiTile, R> RoisMap)
|
static FORCEINLINE bool IsTileInRegionsSet(FRoiTile RoiTile, TMap<FRoiTile, R> RoisMap)
|
||||||
{
|
{
|
||||||
static_assert(TIsDerivedFrom<R, FRegionOfInterest>::IsDerived,
|
static_assert(TIsDerivedFrom<R, FCarlaRegionOfInterest>::IsDerived,
|
||||||
"ROIs Map Value type is not an URegionOfInterest derived type.");
|
"ROIs Map Value type is not an URegionOfInterest derived type.");
|
||||||
return RoisMap.Contains(RoiTile);
|
return RoisMap.Contains(RoiTile);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Checking if two regions of interest are equal.
|
/// Checking if two regions of interest are equal.
|
||||||
bool Equals(const FRegionOfInterest& Other)
|
bool Equals(const FCarlaRegionOfInterest& Other)
|
||||||
{
|
{
|
||||||
// Checking if the number of tiles in the two regions is the same.
|
// Checking if the number of tiles in the two regions is the same.
|
||||||
if(this->TilesList.Num() != Other.TilesList.Num())
|
if(this->TilesList.Num() != Other.TilesList.Num())
|
||||||
|
@ -185,14 +185,14 @@ struct CARLATOOLS_API FRegionOfInterest
|
||||||
};
|
};
|
||||||
|
|
||||||
USTRUCT(BlueprintType)
|
USTRUCT(BlueprintType)
|
||||||
struct CARLATOOLS_API FVegetationROI : public FRegionOfInterest
|
struct CARLATOOLS_API FVegetationROI : public FCarlaRegionOfInterest
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
UPROPERTY(BlueprintReadWrite)
|
UPROPERTY(BlueprintReadWrite)
|
||||||
TArray<UProceduralFoliageSpawner*> FoliageSpawners;
|
TArray<UProceduralFoliageSpawner*> FoliageSpawners;
|
||||||
|
|
||||||
FVegetationROI() : FRegionOfInterest()
|
FVegetationROI() : FCarlaRegionOfInterest()
|
||||||
{
|
{
|
||||||
this->FoliageSpawners.Empty();
|
this->FoliageSpawners.Empty();
|
||||||
}
|
}
|
||||||
|
@ -218,7 +218,7 @@ struct CARLATOOLS_API FVegetationROI : public FRegionOfInterest
|
||||||
};
|
};
|
||||||
|
|
||||||
USTRUCT(BlueprintType)
|
USTRUCT(BlueprintType)
|
||||||
struct CARLATOOLS_API FTerrainROI : public FRegionOfInterest
|
struct CARLATOOLS_API FTerrainROI : public FCarlaRegionOfInterest
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
@ -230,7 +230,7 @@ struct CARLATOOLS_API FTerrainROI : public FRegionOfInterest
|
||||||
UPROPERTY(BlueprintReadWrite)
|
UPROPERTY(BlueprintReadWrite)
|
||||||
UTextureRenderTarget2D* RoiHeightmapRenderTarget;
|
UTextureRenderTarget2D* RoiHeightmapRenderTarget;
|
||||||
|
|
||||||
FTerrainROI() : FRegionOfInterest(), RoiMaterialInstance()
|
FTerrainROI() : FCarlaRegionOfInterest(), RoiMaterialInstance()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -259,7 +259,7 @@ struct CARLATOOLS_API FTerrainROI : public FRegionOfInterest
|
||||||
};
|
};
|
||||||
|
|
||||||
USTRUCT(BlueprintType)
|
USTRUCT(BlueprintType)
|
||||||
struct CARLATOOLS_API FMiscSpreadedActorsROI : public FRegionOfInterest
|
struct CARLATOOLS_API FMiscSpreadedActorsROI : public FCarlaRegionOfInterest
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
@ -272,14 +272,14 @@ struct CARLATOOLS_API FMiscSpreadedActorsROI : public FRegionOfInterest
|
||||||
UPROPERTY(BlueprintReadWrite)
|
UPROPERTY(BlueprintReadWrite)
|
||||||
TEnumAsByte<ESpreadedActorsDensity> ActorsDensity;
|
TEnumAsByte<ESpreadedActorsDensity> ActorsDensity;
|
||||||
|
|
||||||
FMiscSpreadedActorsROI() : FRegionOfInterest(), ActorClass(), Probability(0.0f), ActorsDensity(ESpreadedActorsDensity::LOW)
|
FMiscSpreadedActorsROI() : FCarlaRegionOfInterest(), ActorClass(), Probability(0.0f), ActorsDensity(ESpreadedActorsDensity::LOW)
|
||||||
{}
|
{}
|
||||||
};
|
};
|
||||||
|
|
||||||
/// A struct that is used to store the information of a region of interest that is used to
|
/// A struct that is used to store the information of a region of interest that is used to
|
||||||
/// spawn actors in specific locations.
|
/// spawn actors in specific locations.
|
||||||
USTRUCT(BlueprintType)
|
USTRUCT(BlueprintType)
|
||||||
struct CARLATOOLS_API FMiscSpecificLocationActorsROI : public FRegionOfInterest
|
struct CARLATOOLS_API FMiscSpecificLocationActorsROI : public FCarlaRegionOfInterest
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
@ -295,12 +295,12 @@ struct CARLATOOLS_API FMiscSpecificLocationActorsROI : public FRegionOfInterest
|
||||||
UPROPERTY(BlueprintReadWrite)
|
UPROPERTY(BlueprintReadWrite)
|
||||||
float MaxRotationRange;
|
float MaxRotationRange;
|
||||||
|
|
||||||
FMiscSpecificLocationActorsROI() : FRegionOfInterest(), ActorClass(), ActorLocation(0.0f)
|
FMiscSpecificLocationActorsROI() : FCarlaRegionOfInterest(), ActorClass(), ActorLocation(0.0f)
|
||||||
{}
|
{}
|
||||||
};
|
};
|
||||||
|
|
||||||
USTRUCT(BlueprintType)
|
USTRUCT(BlueprintType)
|
||||||
struct CARLATOOLS_API FSoilTypeROI : public FRegionOfInterest
|
struct CARLATOOLS_API FSoilTypeROI : public FCarlaRegionOfInterest
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
|
|
|
@ -113,6 +113,16 @@ if %REMOVE_INTERMEDIATE% == true (
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
|
|
||||||
|
rem Download Houdini Plugin
|
||||||
|
|
||||||
|
set HOUDINI_PLUGIN_REPO=https://github.com/sideeffects/HoudiniEngineForUnreal.git
|
||||||
|
set HOUDINI_PLUGIN_PATH=Plugins/HoudiniEngine
|
||||||
|
set HOUDINI_PLUGIN_BRANCH=Houdini19.5-Unreal4.26
|
||||||
|
set HOUDINI_PATCH=${CARLA_UTIL_FOLDER}/Patches/houdini_patch.txt
|
||||||
|
if not exist "%HOUDINI_PLUGIN_PATH%" (
|
||||||
|
call git clone -b %HOUDINI_PLUGIN_BRANCH% %HOUDINI_PLUGIN_REPO% %HOUDINI_PLUGIN_PATH%
|
||||||
|
)
|
||||||
|
|
||||||
rem Build Carla Editor
|
rem Build Carla Editor
|
||||||
rem
|
rem
|
||||||
|
|
||||||
|
|
|
@ -16,6 +16,7 @@ USE_CARSIM=false
|
||||||
USE_CHRONO=false
|
USE_CHRONO=false
|
||||||
USE_PYTORCH=false
|
USE_PYTORCH=false
|
||||||
EDITOR_FLAGS=""
|
EDITOR_FLAGS=""
|
||||||
|
USE_HOUDINI=false
|
||||||
|
|
||||||
GDB=
|
GDB=
|
||||||
RHI="-vulkan"
|
RHI="-vulkan"
|
||||||
|
@ -61,6 +62,9 @@ while [[ $# -gt 0 ]]; do
|
||||||
--pytorch )
|
--pytorch )
|
||||||
USE_PYTORCH=true;
|
USE_PYTORCH=true;
|
||||||
shift ;;
|
shift ;;
|
||||||
|
--with-houdini )
|
||||||
|
USE_HOUDINI=true;
|
||||||
|
shift ;;
|
||||||
-h | --help )
|
-h | --help )
|
||||||
echo "$DOC_STRING"
|
echo "$DOC_STRING"
|
||||||
echo "$USAGE_STRING"
|
echo "$USAGE_STRING"
|
||||||
|
@ -123,6 +127,21 @@ if ${REMOVE_INTERMEDIATE} ; then
|
||||||
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
# ==============================================================================
|
||||||
|
# -- Download Houdini Plugin for Unreal Engine ---------------------------------
|
||||||
|
# ==============================================================================
|
||||||
|
|
||||||
|
HOUDINI_PLUGIN_REPO=https://github.com/sideeffects/HoudiniEngineForUnreal.git
|
||||||
|
HOUDINI_PLUGIN_PATH=Plugins/HoudiniEngine
|
||||||
|
HOUDINI_PLUGIN_BRANCH=Houdini19.5-Unreal4.26
|
||||||
|
HOUDINI_PATCH=${CARLA_UTIL_FOLDER}/Patches/houdini_patch.txt
|
||||||
|
if [[ ! -d ${HOUDINI_PLUGIN_PATH} ]] ; then
|
||||||
|
git clone -b ${HOUDINI_PLUGIN_BRANCH} ${HOUDINI_PLUGIN_REPO} ${HOUDINI_PLUGIN_PATH}
|
||||||
|
pushd ${HOUDINI_PLUGIN_PATH} >/dev/null
|
||||||
|
git apply ${HOUDINI_PATCH}
|
||||||
|
popd >/dev/null
|
||||||
|
fi
|
||||||
|
|
||||||
# ==============================================================================
|
# ==============================================================================
|
||||||
# -- Build CarlaUE4 ------------------------------------------------------------
|
# -- Build CarlaUE4 ------------------------------------------------------------
|
||||||
# ==============================================================================
|
# ==============================================================================
|
||||||
|
|
|
@ -109,7 +109,6 @@ if %BUILD_OSM2ODR% == true (
|
||||||
|
|
||||||
cmake --build . --config Release --target install | findstr /V "Up-to-date:"
|
cmake --build . --config Release --target install | findstr /V "Up-to-date:"
|
||||||
if %errorlevel% neq 0 goto error_install
|
if %errorlevel% neq 0 goto error_install
|
||||||
|
|
||||||
copy %OSM2ODR_INSTALL_PATH%\lib\osm2odr.lib %CARLA_DEPENDENCIES_FOLDER%\lib
|
copy %OSM2ODR_INSTALL_PATH%\lib\osm2odr.lib %CARLA_DEPENDENCIES_FOLDER%\lib
|
||||||
copy %OSM2ODR_INSTALL_PATH%\include\OSM2ODR.h %CARLA_DEPENDENCIES_FOLDER%\include
|
copy %OSM2ODR_INSTALL_PATH%\include\OSM2ODR.h %CARLA_DEPENDENCIES_FOLDER%\include
|
||||||
)
|
)
|
||||||
|
|
|
@ -112,6 +112,28 @@ if ${BUILD_OSM2ODR} ; then
|
||||||
LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1"
|
LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1"
|
||||||
LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu"
|
LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu"
|
||||||
|
|
||||||
|
echo $LLVM_INCLUDE
|
||||||
|
echo $LLVM_LIBPATH
|
||||||
|
|
||||||
|
cmake ${OSM2ODR_SOURCE_FOLDER} \
|
||||||
|
-G "Eclipse CDT4 - Ninja" \
|
||||||
|
-DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \
|
||||||
|
-DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \
|
||||||
|
-DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install-server/include \
|
||||||
|
-DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install-server/lib/libproj.a \
|
||||||
|
-DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/include \
|
||||||
|
-DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/lib/libxerces-c.a
|
||||||
|
|
||||||
|
ninja osm2odr
|
||||||
|
ninja install
|
||||||
|
|
||||||
|
mkdir -p ${OSM2ODR_SERVER_BUILD_FOLDER}
|
||||||
|
cd ${OSM2ODR_SERVER_BUILD_FOLDER}
|
||||||
|
|
||||||
|
LLVM_BASENAME=llvm-8.0
|
||||||
|
LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1"
|
||||||
|
LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu"
|
||||||
|
|
||||||
cmake ${OSM2ODR_SOURCE_FOLDER} \
|
cmake ${OSM2ODR_SOURCE_FOLDER} \
|
||||||
-G "Eclipse CDT4 - Ninja" \
|
-G "Eclipse CDT4 - Ninja" \
|
||||||
-DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \
|
-DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \
|
||||||
|
|
|
@ -0,0 +1,85 @@
|
||||||
|
@echo off
|
||||||
|
setlocal enabledelayedexpansion
|
||||||
|
|
||||||
|
set LIBOSMSCOUT_REPO=https://github.com/Framstag/libosmscout
|
||||||
|
set LUNASVG_REPO=https://github.com/sammycage/lunasvg
|
||||||
|
|
||||||
|
set LIBOSMSCOUT_SOURCE_PATH=%INSTALLATION_DIR:/=\%libosmscout-source\
|
||||||
|
set LIBOSMSCOUT_VSPROJECT_PATH=%INSTALLATION_DIR:/=\%libosmscout-visualstudio\
|
||||||
|
|
||||||
|
set LUNASVG_SOURCE_PATH=%INSTALLATION_DIR:/=\%lunasvg-source\
|
||||||
|
set LUNASVG_VSPROJECT_PATH=%INSTALLATION_DIR:/=\%lunasvg-visualstudio\
|
||||||
|
|
||||||
|
set OSM_RENDERER_SOURCE=%ROOT_PATH:/=\%osm-world-renderer\
|
||||||
|
set OSM_RENDERER_VSPROJECT_PATH=%INSTALLATION_DIR:/=\%%osm-world-renderer-visualstudio\
|
||||||
|
|
||||||
|
rem Installation path for server dependencies
|
||||||
|
set DEPENDENCIES_INSTALLATION_PATH=%OSM_RENDERER_SOURCE:/=\%ThirdParties\
|
||||||
|
|
||||||
|
|
||||||
|
rem ============================================================================
|
||||||
|
rem -- Download dependency manager for libosmscout -----------------------------
|
||||||
|
rem ============================================================================
|
||||||
|
set VCPKG_REPO=https://github.com/microsoft/vcpkg
|
||||||
|
set VCPKG_PATH=%INSTALLATION_DIR:/=\%vcpkg\
|
||||||
|
set VCPKG_CMAKE_TOOLCHAIN_PATH=%VCPKG_PATH:/=\%scripts\buildsystems\vcpkg.cmake
|
||||||
|
|
||||||
|
rem if not exist "%VCPKG_PATH%" git clone %VCPKG_REPO% %VCPKG_PATH%
|
||||||
|
|
||||||
|
rem .\"%VCPKG_PATH:/=\%"bootstrap-vcpkg.bat
|
||||||
|
|
||||||
|
|
||||||
|
rem ============================================================================
|
||||||
|
rem -- Download and build libosmscout ------------------------------------------
|
||||||
|
rem ============================================================================
|
||||||
|
|
||||||
|
if not exist "%LIBOSMSCOUT_SOURCE_PATH%" git clone %LIBOSMSCOUT_REPO% %LIBOSMSCOUT_SOURCE_PATH%
|
||||||
|
|
||||||
|
if not exist "%LIBOSMSCOUT_VSPROJECT_PATH%" mkdir "%LIBOSMSCOUT_VSPROJECT_PATH%"
|
||||||
|
cd "%LIBOSMSCOUT_VSPROJECT_PATH%"
|
||||||
|
|
||||||
|
cmake -G "Visual Studio 16 2019"^
|
||||||
|
-DCMAKE_INSTALL_PREFIX="%DEPENDENCIES_INSTALLATION_PATH:\=/%"^
|
||||||
|
-DOSMSCOUT_BUILD_TOOL_STYLEEDITOR=OFF^
|
||||||
|
-DOSMSCOUT_BUILD_TOOL_OSMSCOUT2=OFF^
|
||||||
|
-DOSMSCOUT_BUILD_TESTS=OFF^
|
||||||
|
-DOSMSCOUT_BUILD_CLIENT_QT=OFF^
|
||||||
|
-DOSMSCOUT_BUILD_DEMOS=OFF^
|
||||||
|
"%LIBOSMSCOUT_SOURCE_PATH%"
|
||||||
|
|
||||||
|
rem -DCMAKE_CXX_FLAGS_RELEASE="/DM_PI=3.14159265358979323846"^
|
||||||
|
|
||||||
|
cmake --build . --config=Release --target install
|
||||||
|
|
||||||
|
rem ============================================================================
|
||||||
|
rem -- Download and build lunasvg ----------------------------------------------
|
||||||
|
rem ============================================================================
|
||||||
|
|
||||||
|
if not exist "%LUNASVG_SOURCE_PATH%" git clone %LUNASVG_REPO% %LUNASVG_SOURCE_PATH%
|
||||||
|
|
||||||
|
if not exist "%LUNASVG_VSPROJECT_PATH%" mkdir "%LUNASVG_VSPROJECT_PATH%"
|
||||||
|
cd "%LUNASVG_VSPROJECT_PATH%"
|
||||||
|
|
||||||
|
cmake -G "Visual Studio 16 2019" -A x64^
|
||||||
|
-DCMAKE_INSTALL_PREFIX="%DEPENDENCIES_INSTALLATION_PATH:\=/%"^
|
||||||
|
"%LUNASVG_SOURCE_PATH%"
|
||||||
|
|
||||||
|
cmake --build . --config Release --target install
|
||||||
|
|
||||||
|
|
||||||
|
rem ===========================================================================
|
||||||
|
rem -- Build osm-map-renderer tool --------------------------------------------
|
||||||
|
rem ===========================================================================
|
||||||
|
|
||||||
|
if not exist "%OSM_RENDERER_VSPROJECT_PATH%" mkdir "%OSM_RENDERER_VSPROJECT_PATH%"
|
||||||
|
cd "%OSM_RENDERER_VSPROJECT_PATH%"
|
||||||
|
|
||||||
|
cmake -G "Visual Studio 16 2019" -A x64^
|
||||||
|
-DCMAKE_CXX_FLAGS_RELEASE="/std:c++17 /wd4251 /I%INSTALLATION_DIR:/=\%boost-1.80.0-install\include"^
|
||||||
|
"%OSM_RENDERER_SOURCE%"
|
||||||
|
|
||||||
|
cmake --build . --config Release
|
||||||
|
rem cmake --build . --config Release
|
||||||
|
rem -DOSMSCOUT_BUILD_MAP_QT=OFF^
|
||||||
|
|
||||||
|
copy "%DEPENDENCIES_INSTALLATION_PATH:/=\%"bin "%OSM_RENDERER_VSPROJECT_PATH:/=\%"Release\
|
|
@ -0,0 +1,69 @@
|
||||||
|
#! /bin/bash
|
||||||
|
|
||||||
|
source $(dirname "$0")/Environment.sh
|
||||||
|
|
||||||
|
LIBOSMSCOUT_REPO=https://github.com/Framstag/libosmscout
|
||||||
|
LUNASVG_REPO=https://github.com/sammycage/lunasvg
|
||||||
|
|
||||||
|
LIBOSMSCOUT_SOURCE_FOLDER=${CARLA_BUILD_FOLDER}/libosmscout-source
|
||||||
|
LIBOSMSCOUT_BUILD_FOLDER=${CARLA_BUILD_FOLDER}/libosmscout-build
|
||||||
|
|
||||||
|
LUNASVG_SOURCE_FOLDER=${CARLA_BUILD_FOLDER}/lunasvg-source
|
||||||
|
LUNASVG_BUILD_FOLDER=${CARLA_BUILD_FOLDER}/lunasvg-build
|
||||||
|
|
||||||
|
OSM_RENDERER_SOURCE=${CARLA_ROOT_FOLDER}/osm-world-renderer
|
||||||
|
OSM_RENDERER_BUILD=${CARLA_BUILD_FOLDER}/osm-world-renderer-build
|
||||||
|
|
||||||
|
INSTALLATION_PATH=${OSM_RENDERER_SOURCE}/ThirdParties
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
# ==============================================================================
|
||||||
|
# -- Download and build libosmscout --------------------------------------------
|
||||||
|
# ==============================================================================
|
||||||
|
echo "Cloning libosmscout."
|
||||||
|
echo ${CARLA_BUILD_FOLDER}
|
||||||
|
if [ ! -d ${LIBOSMSCOUT_SOURCE_FOLDER} ] ; then
|
||||||
|
git clone ${LIBOSMSCOUT_REPO} ${LIBOSMSCOUT_SOURCE_FOLDER}
|
||||||
|
fi
|
||||||
|
|
||||||
|
mkdir -p ${LIBOSMSCOUT_BUILD_FOLDER}
|
||||||
|
cd ${LIBOSMSCOUT_BUILD_FOLDER}
|
||||||
|
|
||||||
|
cmake ${LIBOSMSCOUT_SOURCE_FOLDER} \
|
||||||
|
-DCMAKE_INSTALL_PREFIX=${INSTALLATION_PATH}
|
||||||
|
|
||||||
|
make
|
||||||
|
make install
|
||||||
|
|
||||||
|
# ==============================================================================
|
||||||
|
# -- Download and build lunasvg ------------------------------------------------
|
||||||
|
# ==============================================================================
|
||||||
|
echo "Cloning luna-svg"
|
||||||
|
if [ ! -d ${LUNASVG_SOURCE_FOLDER} ] ; then
|
||||||
|
git clone ${LUNASVG_REPO} ${LUNASVG_SOURCE_FOLDER}
|
||||||
|
fi
|
||||||
|
|
||||||
|
mkdir -p ${LUNASVG_BUILD_FOLDER}
|
||||||
|
cd ${LUNASVG_BUILD_FOLDER}
|
||||||
|
|
||||||
|
cmake ${LUNASVG_SOURCE_FOLDER} \
|
||||||
|
-DCMAKE_INSTALL_PREFIX=${INSTALLATION_PATH}
|
||||||
|
|
||||||
|
make
|
||||||
|
make install
|
||||||
|
|
||||||
|
|
||||||
|
# ==============================================================================
|
||||||
|
# -- Build osm-map-renderer tool -----------------------------------------------
|
||||||
|
# ==============================================================================
|
||||||
|
echo "Building osm-map-renderer"
|
||||||
|
|
||||||
|
mkdir -p ${OSM_RENDERER_BUILD}
|
||||||
|
cd ${OSM_RENDERER_BUILD}
|
||||||
|
|
||||||
|
cmake -DCMAKE_CXX_FLAGS="-std=c++17 -g -pthread -I${CARLA_BUILD_FOLDER}/boost-1.80.0-c10-install/include" \
|
||||||
|
${OSM_RENDERER_SOURCE}
|
||||||
|
make
|
||||||
|
|
||||||
|
echo "SUCCESS! Finishing setting up renderer."
|
|
@ -150,3 +150,6 @@ build.utils: PythonAPI
|
||||||
|
|
||||||
osm2odr:
|
osm2odr:
|
||||||
@${CARLA_BUILD_TOOLS_FOLDER}/BuildOSM2ODR.sh --build $(ARGS)
|
@${CARLA_BUILD_TOOLS_FOLDER}/BuildOSM2ODR.sh --build $(ARGS)
|
||||||
|
|
||||||
|
osmrenderer:
|
||||||
|
@${CARLA_BUILD_TOOLS_FOLDER}/BuildOSMRenderer.sh
|
||||||
|
|
|
@ -82,3 +82,6 @@ deploy:
|
||||||
|
|
||||||
osm2odr:
|
osm2odr:
|
||||||
@"${CARLA_BUILD_TOOLS_FOLDER}/BuildOSM2ODR.bat" --build $(ARGS)
|
@"${CARLA_BUILD_TOOLS_FOLDER}/BuildOSM2ODR.bat" --build $(ARGS)
|
||||||
|
|
||||||
|
osmrenderer:
|
||||||
|
@"${CARLA_BUILD_TOOLS_FOLDER}/BuildOSMRenderer.bat"
|
||||||
|
|
|
@ -0,0 +1,15 @@
|
||||||
|
diff --git a/Source/HoudiniEngineEditor/Private/HoudiniEngineDetails.cpp b/Source/HoudiniEngineEditor/Private/HoudiniEngineDetails.cpp
|
||||||
|
index 36c9bf5cd..d9d6dbfdb 100755
|
||||||
|
--- a/Source/HoudiniEngineEditor/Private/HoudiniEngineDetails.cpp
|
||||||
|
+++ b/Source/HoudiniEngineEditor/Private/HoudiniEngineDetails.cpp
|
||||||
|
@@ -1131,8 +1131,8 @@ FHoudiniEngineDetails::CreateAssetOptionsWidgets(
|
||||||
|
|
||||||
|
auto IsCheckedParameterChangedLambda = [MainHAC]()
|
||||||
|
{
|
||||||
|
- if (!IsValidWeakPointer(MainHAC))
|
||||||
|
- return ECheckBoxState::Unchecked;
|
||||||
|
+ if (!IsValidWeakPointer(MainHAC))
|
||||||
|
+ return ECheckBoxState::Unchecked;
|
||||||
|
|
||||||
|
return MainHAC->bCookOnParameterChange ? ECheckBoxState::Checked : ECheckBoxState::Unchecked;
|
||||||
|
};
|
|
@ -0,0 +1,2 @@
|
||||||
|
build/
|
||||||
|
ThirdParties/
|
|
@ -0,0 +1,19 @@
|
||||||
|
cmake_minimum_required(VERSION 3.5.1)
|
||||||
|
project(OsmMapRenderer)
|
||||||
|
|
||||||
|
# Libosmscout and Luna SVG Library
|
||||||
|
include_directories(ThirdParties/include)
|
||||||
|
link_directories(ThirdParties/lib)
|
||||||
|
|
||||||
|
# Source Files
|
||||||
|
add_library(OsmRenderer OsmRenderer/src/OsmRenderer.cpp)
|
||||||
|
target_sources(OsmRenderer PRIVATE OsmRenderer/src/MapDrawer.cpp)
|
||||||
|
target_sources(OsmRenderer PRIVATE OsmRenderer/src/MapRasterizer.cpp)
|
||||||
|
target_include_directories( OsmRenderer PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/OsmRenderer/include)
|
||||||
|
|
||||||
|
add_executable(osm-world-renderer OsmRenderer/main.cpp)
|
||||||
|
target_link_libraries(osm-world-renderer OsmRenderer)
|
||||||
|
target_link_libraries(osm-world-renderer osmscout)
|
||||||
|
target_link_libraries(osm-world-renderer osmscout_map)
|
||||||
|
target_link_libraries(osm-world-renderer osmscout_map_svg)
|
||||||
|
target_link_libraries(osm-world-renderer lunasvg)
|
|
@ -0,0 +1,58 @@
|
||||||
|
#ifndef MAP_DRAWE_H
|
||||||
|
#define MAP_DRAWE_H
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
#include <string>
|
||||||
|
#include <memory>
|
||||||
|
|
||||||
|
#include "MapRasterizer.h"
|
||||||
|
|
||||||
|
#include <osmscout/GeoCoord.h>
|
||||||
|
#include <osmscout/Database.h>
|
||||||
|
#include <osmscoutmap/MapService.h>
|
||||||
|
#include <osmscout/BasemapDatabase.h>
|
||||||
|
|
||||||
|
class MapDrawer
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
void PreLoad(std::vector<std::string>& Args);
|
||||||
|
|
||||||
|
void Draw(std::uint8_t* OutMap, osmscout::GeoCoord Coords, double ZoomValue);
|
||||||
|
|
||||||
|
inline const int GetImgSizeSqr()
|
||||||
|
{
|
||||||
|
return Size * Size;
|
||||||
|
};
|
||||||
|
|
||||||
|
osmscout::GeoCoord GetBottomLeftCoord();
|
||||||
|
osmscout::GeoCoord GetTopRightCoord();
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Rastering
|
||||||
|
std::unique_ptr<MapRasterizer> Rasterizer;
|
||||||
|
|
||||||
|
// Arguments
|
||||||
|
std::string DataBasePath;
|
||||||
|
std::string StyleSheetPath;
|
||||||
|
int Size;
|
||||||
|
|
||||||
|
// Entities
|
||||||
|
osmscout::DatabaseParameter DbParameter;
|
||||||
|
osmscout::DatabaseRef Database;
|
||||||
|
osmscout::MapServiceRef MapService;
|
||||||
|
osmscout::StyleConfigRef StyleSheet;
|
||||||
|
|
||||||
|
osmscout::MercatorProjection Projection;
|
||||||
|
osmscout::MapData MapData;
|
||||||
|
osmscout::MapParameter DrawParameter;
|
||||||
|
osmscout::AreaSearchParameter SearchParameter;
|
||||||
|
//GeoCoord CenterCoords;
|
||||||
|
|
||||||
|
void LoadDatabaseData();
|
||||||
|
void SetDrawParameters();
|
||||||
|
|
||||||
|
void DrawMap(std::uint8_t* OutMap);
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,15 @@
|
||||||
|
#ifndef MAP_RASTERIZER_H
|
||||||
|
#define MAP_RASTERIZER_H
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
class MapRasterizer
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
void RasterizeSVG(std::uint8_t* OutMap, std::string SvgString, int Size);
|
||||||
|
|
||||||
|
private:
|
||||||
|
int BackgroundColor = 0x00000000;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,43 @@
|
||||||
|
#ifndef OSM_RENDERER_H
|
||||||
|
#define OSM_RENDERER_H
|
||||||
|
|
||||||
|
#include <boost/asio.hpp>
|
||||||
|
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
#include <memory>
|
||||||
|
#include "MapDrawer.h"
|
||||||
|
|
||||||
|
|
||||||
|
class OsmRenderer
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
// Boost socket
|
||||||
|
boost::asio::io_service io_service;
|
||||||
|
std::unique_ptr<boost::asio::ip::tcp::acceptor> SocketAcceptorPtr;
|
||||||
|
std::unique_ptr<boost::asio::ip::tcp::socket> SocketPtr;
|
||||||
|
|
||||||
|
|
||||||
|
// Map Drawer
|
||||||
|
std::unique_ptr<MapDrawer> Drawer;
|
||||||
|
|
||||||
|
void RunCmd(std::string Cmd);
|
||||||
|
|
||||||
|
std::vector<std::string> SplitCmd (std::string s, std::string delimiter);
|
||||||
|
|
||||||
|
// Command Handlers
|
||||||
|
void RenderMapCmd(std::vector<std::string> CmdArgs, uint8_t* OutMap);
|
||||||
|
void ConfigMapCmd(std::vector<std::string> CmdArgs);
|
||||||
|
void SendLatLonCmd(std::vector<std::string> CmdArgs);
|
||||||
|
|
||||||
|
|
||||||
|
public:
|
||||||
|
std::string GetOsmRendererString() const;
|
||||||
|
|
||||||
|
void InitRenderer();
|
||||||
|
void StartLoop();
|
||||||
|
|
||||||
|
void ShutDown();
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,17 @@
|
||||||
|
#define CMD_INDEX 0
|
||||||
|
|
||||||
|
#define C_CMD_DATABASE_PATH 1
|
||||||
|
#define C_CMD_STYLESHEET_PATH 2
|
||||||
|
#define C_CMD_IMG_SIZE 3
|
||||||
|
|
||||||
|
#define R_CMD_LATITUDE 1
|
||||||
|
#define R_CMD_LONGITUDE 2
|
||||||
|
#define R_CMD_ZOOM 3
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
#define DEFAULT_FONT_FILE "C:\\Windows\\Fonts\\arial.ttf"
|
||||||
|
#else
|
||||||
|
#define DEFAULT_FONT_FILE "/usr/share/fonts/TTF/LiberationSans-Regular.ttf"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define LOG_PRFX "├ "
|
|
@ -0,0 +1,28 @@
|
||||||
|
#include <iostream>
|
||||||
|
|
||||||
|
#include "include/OsmRenderer.h"
|
||||||
|
|
||||||
|
int main()
|
||||||
|
{
|
||||||
|
//std::locale::global(std::locale("C.UTF-8"));
|
||||||
|
//std::locale::global(std::locale("es_ES.utf8"));
|
||||||
|
// std::locale::global(std::locale("en_US.utf8"));
|
||||||
|
|
||||||
|
std::cout << " Starting renderer " << std::locale().name() << std::endl;
|
||||||
|
OsmRenderer Renderer;
|
||||||
|
try
|
||||||
|
{
|
||||||
|
Renderer.InitRenderer();
|
||||||
|
Renderer.StartLoop();
|
||||||
|
}
|
||||||
|
catch(std::exception& e)
|
||||||
|
{
|
||||||
|
std::cerr << "ERROR:: " << e.what() << std::endl;
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
Renderer.ShutDown();
|
||||||
|
std::cout << "Shutting down renderer. Bye! " << Renderer.GetOsmRendererString() << std::endl;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -0,0 +1,123 @@
|
||||||
|
#include "MapDrawer.h"
|
||||||
|
#include "OsmRendererMacros.h"
|
||||||
|
#include "MapRasterizer.h"
|
||||||
|
|
||||||
|
#include "osmscoutmapsvg/MapPainterSVG.h"
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
//#include <fstream>
|
||||||
|
#include <sstream>
|
||||||
|
#include <list>
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
void MapDrawer::PreLoad(vector<string>& Args)
|
||||||
|
{
|
||||||
|
// Open Database
|
||||||
|
std::cout << "Begining" << std::endl;
|
||||||
|
DataBasePath = Args[C_CMD_DATABASE_PATH];
|
||||||
|
StyleSheetPath = Args[C_CMD_STYLESHEET_PATH];
|
||||||
|
std::cout << "Before stoi" << std::endl;
|
||||||
|
Size = stoi(Args[C_CMD_IMG_SIZE]);
|
||||||
|
|
||||||
|
Database = std::make_shared<osmscout::Database>(DbParameter);
|
||||||
|
|
||||||
|
std::cout << "Before opening database" << std::endl;
|
||||||
|
|
||||||
|
if(!Database->Open(DataBasePath))
|
||||||
|
{
|
||||||
|
std::cerr << "ERROR Opening Database in " << DataBasePath << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::cout << "After opening database" << std::endl;
|
||||||
|
|
||||||
|
MapService = std::make_shared<osmscout::MapService>(Database);
|
||||||
|
|
||||||
|
StyleSheet = std::make_shared<osmscout::StyleConfig>(Database->GetTypeConfig());
|
||||||
|
if(!StyleSheet->Load(StyleSheetPath))
|
||||||
|
{
|
||||||
|
std::cerr << "ERROR Opening Stylesheet in " << DataBasePath << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
Rasterizer = std::make_unique<MapRasterizer>();
|
||||||
|
}
|
||||||
|
|
||||||
|
void MapDrawer::Draw(std::uint8_t* OutMap, osmscout::GeoCoord Coords, double ZoomValue)
|
||||||
|
{
|
||||||
|
osmscout::Magnification Zoom;
|
||||||
|
Zoom.SetMagnification(ZoomValue);
|
||||||
|
Projection.Set(Coords, Zoom, 96.0f, Size, Size);
|
||||||
|
|
||||||
|
LoadDatabaseData();
|
||||||
|
SetDrawParameters();
|
||||||
|
|
||||||
|
DrawMap(OutMap);
|
||||||
|
}
|
||||||
|
|
||||||
|
osmscout::GeoCoord MapDrawer::GetBottomLeftCoord()
|
||||||
|
{
|
||||||
|
osmscout::GeoCoord PixelCoord;
|
||||||
|
if(Projection.PixelToGeo(0, Size-1, PixelCoord))
|
||||||
|
return PixelCoord;
|
||||||
|
else
|
||||||
|
return osmscout::GeoCoord(0,0);
|
||||||
|
}
|
||||||
|
|
||||||
|
osmscout::GeoCoord MapDrawer::GetTopRightCoord()
|
||||||
|
{
|
||||||
|
osmscout::GeoCoord PixelCoord;
|
||||||
|
if(Projection.PixelToGeo(Size-1, 0, PixelCoord))
|
||||||
|
return PixelCoord;
|
||||||
|
else
|
||||||
|
return osmscout::GeoCoord(0,0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MapDrawer::LoadDatabaseData()
|
||||||
|
{
|
||||||
|
// Load Database
|
||||||
|
std::list<osmscout::TileRef> Tiles;
|
||||||
|
|
||||||
|
MapData.ClearDBData();
|
||||||
|
|
||||||
|
MapService->LookupTiles(Projection, Tiles);
|
||||||
|
MapService->LoadMissingTileData(SearchParameter, *StyleSheet, Tiles);
|
||||||
|
MapService->AddTileDataToMapData(Tiles, MapData);
|
||||||
|
MapService->GetGroundTiles(Projection, MapData.groundTiles);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void MapDrawer::SetDrawParameters()
|
||||||
|
{
|
||||||
|
DrawParameter.SetFontName(DEFAULT_FONT_FILE);
|
||||||
|
|
||||||
|
//DrawParameter.SetFontSize(args.fontSize);
|
||||||
|
DrawParameter.SetRenderSeaLand(true);
|
||||||
|
DrawParameter.SetRenderUnknowns(false);
|
||||||
|
DrawParameter.SetRenderBackground(false);
|
||||||
|
//DrawParameter.SetRenderContourLines(args.renderContourLines);
|
||||||
|
//DrawParameter.SetRenderHillShading(args.renderHillShading);
|
||||||
|
|
||||||
|
//DrawParameter.SetIconMode(args.iconMode);
|
||||||
|
//DrawParameter.SetIconPaths(args.iconPaths);
|
||||||
|
|
||||||
|
//DrawParameter.SetDebugData(args.debug);
|
||||||
|
//DrawParameter.SetDebugPerformance(args.debug);
|
||||||
|
|
||||||
|
DrawParameter.SetLabelLineMinCharCount(15);
|
||||||
|
DrawParameter.SetLabelLineMaxCharCount(30);
|
||||||
|
DrawParameter.SetLabelLineFitToArea(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MapDrawer::DrawMap(std::uint8_t* OutMap)
|
||||||
|
{
|
||||||
|
std::stringstream OutSvgStream;
|
||||||
|
if (!OutSvgStream) {
|
||||||
|
std::cerr << "Cannot open '" << "' for writing!" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
osmscout::MapPainterSVG Painter(StyleSheet);
|
||||||
|
Painter.DrawMap(Projection, DrawParameter, MapData, OutSvgStream);
|
||||||
|
|
||||||
|
Rasterizer->RasterizeSVG(OutMap, OutSvgStream.str(), Size);
|
||||||
|
}
|
|
@ -0,0 +1,38 @@
|
||||||
|
#include "MapRasterizer.h"
|
||||||
|
#include "OsmRendererMacros.h"
|
||||||
|
|
||||||
|
//#define STB_IMAGE_WRITE_IMPLEMENTATION
|
||||||
|
|
||||||
|
#include "lunasvg.h"
|
||||||
|
//#include "stb_image_write.h"
|
||||||
|
|
||||||
|
#include <iostream>
|
||||||
|
#include <string>
|
||||||
|
#include <cstring>
|
||||||
|
|
||||||
|
using namespace lunasvg;
|
||||||
|
|
||||||
|
void MapRasterizer::RasterizeSVG(std::uint8_t* OutMap, std::string SvgString, int Size)
|
||||||
|
{
|
||||||
|
auto SvgDocument = Document::loadFromData(SvgString);
|
||||||
|
|
||||||
|
if(!SvgDocument)
|
||||||
|
{
|
||||||
|
std::cerr << "ERROR: Rasterizer could not load Svg data." << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
Bitmap RasterizedBitmap = SvgDocument->renderToBitmap(Size, Size, BackgroundColor);
|
||||||
|
if(!RasterizedBitmap.valid())
|
||||||
|
{
|
||||||
|
std::cerr << LOG_PRFX << "ERROR: No valid Bitmap" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
std::cout << LOG_PRFX << "Bitmap VALID" << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
RasterizedBitmap.convertToRGBA();
|
||||||
|
std::memcpy(OutMap, RasterizedBitmap.data(), Size*Size*4*sizeof(uint8_t));
|
||||||
|
}
|
|
@ -0,0 +1,151 @@
|
||||||
|
#include "OsmRenderer.h"
|
||||||
|
|
||||||
|
#include "OsmRendererMacros.h"
|
||||||
|
#include "MapDrawer.h"
|
||||||
|
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <iostream>
|
||||||
|
#include <string.h>
|
||||||
|
#include <chrono>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
|
#define PORT 5000
|
||||||
|
#define BUFFER_SIZE 1024
|
||||||
|
|
||||||
|
using namespace std;
|
||||||
|
|
||||||
|
namespace Asio = boost::asio;
|
||||||
|
using AsioStreamBuf = boost::asio::streambuf;
|
||||||
|
using AsioTCP = boost::asio::ip::tcp;
|
||||||
|
using AsioSocket = boost::asio::ip::tcp::socket;
|
||||||
|
using AsioAcceptor = boost::asio::ip::tcp::acceptor;
|
||||||
|
using AsioEndpoint = boost::asio::ip::tcp::endpoint;
|
||||||
|
|
||||||
|
|
||||||
|
string OsmRenderer::GetOsmRendererString() const
|
||||||
|
{
|
||||||
|
return "Renderer speaking here";
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::InitRenderer()
|
||||||
|
{
|
||||||
|
SocketAcceptorPtr = make_unique<AsioAcceptor>(io_service, AsioEndpoint(AsioTCP::v4(), PORT));
|
||||||
|
SocketPtr = make_unique<AsioSocket>(io_service);
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::StartLoop()
|
||||||
|
{
|
||||||
|
std::cout << "┌ Waiting Command..." << std::endl;
|
||||||
|
SocketAcceptorPtr->accept(*SocketPtr);
|
||||||
|
if(!SocketPtr->is_open())
|
||||||
|
{
|
||||||
|
throw runtime_error("Connection not accepted. Socket is not opened.");
|
||||||
|
}
|
||||||
|
while(true)
|
||||||
|
{
|
||||||
|
AsioStreamBuf Buffer;
|
||||||
|
Asio::read(*SocketPtr, Buffer, Asio::transfer_at_least(2));
|
||||||
|
|
||||||
|
string BufferStr = Asio::buffer_cast<const char*>(Buffer.data());
|
||||||
|
|
||||||
|
std::cout << LOG_PRFX << "Received message: " << BufferStr << std::endl;
|
||||||
|
|
||||||
|
RunCmd(BufferStr);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::ShutDown()
|
||||||
|
{
|
||||||
|
// TODO Shutdown socket and clear pointers
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::RunCmd(string Cmd)
|
||||||
|
{
|
||||||
|
string CmdStr = Cmd;
|
||||||
|
vector<string> CmdVector = SplitCmd(CmdStr, " ");
|
||||||
|
|
||||||
|
string CmdType = CmdVector[CMD_INDEX];
|
||||||
|
|
||||||
|
if(CmdType == "-R") // Render Command
|
||||||
|
{
|
||||||
|
std::uint8_t* RenderedMap = new uint8_t[Drawer->GetImgSizeSqr() * 4];
|
||||||
|
RenderMapCmd(CmdVector, RenderedMap);
|
||||||
|
|
||||||
|
Asio::write(*SocketPtr, Asio::buffer(RenderedMap, (Drawer->GetImgSizeSqr() * 4 * sizeof(uint8_t))));
|
||||||
|
|
||||||
|
// TODO: delete RenderedMap after is sent
|
||||||
|
}
|
||||||
|
else if(CmdType == "-C")// Configuration Command
|
||||||
|
{
|
||||||
|
ConfigMapCmd(CmdVector);
|
||||||
|
}
|
||||||
|
else if(CmdType == "-X")// Exit command
|
||||||
|
{
|
||||||
|
std::cout << "└ Bye!" << std::endl;
|
||||||
|
exit(EXIT_SUCCESS);
|
||||||
|
}
|
||||||
|
else if(CmdType == "-L")
|
||||||
|
{
|
||||||
|
SendLatLonCmd(CmdVector);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
vector<string> OsmRenderer::SplitCmd (string s, string delimiter) {
|
||||||
|
size_t pos_start = 0, pos_end, delim_len = delimiter.length();
|
||||||
|
string token;
|
||||||
|
vector<string> res;
|
||||||
|
|
||||||
|
while ((pos_end = s.find (delimiter, pos_start)) != string::npos) {
|
||||||
|
token = s.substr (pos_start, pos_end - pos_start);
|
||||||
|
pos_start = pos_end + delim_len;
|
||||||
|
res.push_back (token);
|
||||||
|
}
|
||||||
|
|
||||||
|
res.push_back (s.substr (pos_start));
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::RenderMapCmd(vector<string> CmdArgs, uint8_t* OutMap)
|
||||||
|
{
|
||||||
|
std::cout << LOG_PRFX << "Rendering map at [" << stof(CmdArgs[R_CMD_LATITUDE]) << ", "
|
||||||
|
<< stof(CmdArgs[R_CMD_LONGITUDE]) << "] with zoom: " << CmdArgs[R_CMD_ZOOM] << std::endl;
|
||||||
|
|
||||||
|
auto start = std::chrono::high_resolution_clock::now();
|
||||||
|
osmscout::GeoCoord Coord(stof(CmdArgs[R_CMD_LATITUDE]), stof(CmdArgs[R_CMD_LONGITUDE]));
|
||||||
|
Drawer->Draw(OutMap, Coord, stod(CmdArgs[R_CMD_ZOOM]));
|
||||||
|
auto stop = std::chrono::high_resolution_clock::now();
|
||||||
|
|
||||||
|
auto ElapsedTime = std::chrono::duration_cast<std::chrono::milliseconds>(stop - start);
|
||||||
|
std::cout << LOG_PRFX << "Elapsed Rendering time: " << ElapsedTime.count() << "ms." << std::endl;
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::ConfigMapCmd(vector<string> CmdArgs)
|
||||||
|
{
|
||||||
|
std::cout << LOG_PRFX << "Configuring Renderer:: DATABASE:"
|
||||||
|
<< CmdArgs[C_CMD_DATABASE_PATH] << " STYLESHEET: "
|
||||||
|
<< CmdArgs[C_CMD_STYLESHEET_PATH] << " SIZE: " << CmdArgs[C_CMD_IMG_SIZE]<< std::endl;
|
||||||
|
Drawer = std::make_unique<MapDrawer>();
|
||||||
|
Drawer->PreLoad(CmdArgs);
|
||||||
|
|
||||||
|
if(!Drawer)
|
||||||
|
{
|
||||||
|
std::cout << LOG_PRFX << "--> ERROR creating Drawer" << std::endl;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void OsmRenderer::SendLatLonCmd(vector<string> CmdArgs)
|
||||||
|
{
|
||||||
|
osmscout::GeoCoord TopRightCoord = Drawer->GetTopRightCoord();
|
||||||
|
osmscout::GeoCoord BottomLeftCoord = Drawer->GetBottomLeftCoord();
|
||||||
|
|
||||||
|
std::cout << LOG_PRFX << "TOP: " << TopRightCoord.GetLat() << " -- " << TopRightCoord.GetLon() << std::endl;
|
||||||
|
std::cout << LOG_PRFX << "BOTTOM: " << BottomLeftCoord.GetLat() << " -- " << BottomLeftCoord.GetLon() << std::endl;
|
||||||
|
|
||||||
|
string CoordsStr = to_string(TopRightCoord.GetLat()) + "&" + to_string(TopRightCoord.GetLon()) +
|
||||||
|
"&" + to_string(BottomLeftCoord.GetLat()) + "&" + to_string(BottomLeftCoord.GetLon()) + "&";
|
||||||
|
|
||||||
|
std::cout << LOG_PRFX << "Sending [" << CoordsStr << "] Size: " << CoordsStr.size() << std::endl;
|
||||||
|
|
||||||
|
Asio::write(*SocketPtr, Asio::buffer(CoordsStr));
|
||||||
|
}
|
|
@ -0,0 +1,20 @@
|
||||||
|
BUILD_DIR=build/
|
||||||
|
|
||||||
|
if [ -d $BUILD_DIR ];
|
||||||
|
then
|
||||||
|
echo "Deleting existing ${BUILD_DIR} directory."
|
||||||
|
rm -r $BUILD_DIR
|
||||||
|
fi
|
||||||
|
|
||||||
|
echo "Creating ${BUILD_DIR} directory."
|
||||||
|
mkdir $BUILD_DIR
|
||||||
|
cd $BUILD_DIR
|
||||||
|
|
||||||
|
LIB_LIBOSMSCOUT_INCLUDE=/home/aollero/Downloads/libosmcout/libosmscout-master/libosmscout-map-svg/include/
|
||||||
|
LIB_LIBOSMSCOUT_LIBS=/home/aollero/Downloads/libosmcout/libosmscout-master/build/libosmscout-map-svg
|
||||||
|
|
||||||
|
|
||||||
|
cmake -DCMAKE_CXX_FLAGS="-std=c++17 -g -Og" ..
|
||||||
|
make
|
||||||
|
|
||||||
|
./osm-world-renderer
|
|
@ -0,0 +1,24 @@
|
||||||
|
import socket
|
||||||
|
|
||||||
|
def client_program():
|
||||||
|
host = socket.gethostname() # as both code is running on same pc
|
||||||
|
port = 5000 # socket server port number
|
||||||
|
|
||||||
|
client_socket = socket.socket() # instantiate
|
||||||
|
client_socket.connect((host, port)) # connect to the server
|
||||||
|
|
||||||
|
message = input(" -> ") # take input
|
||||||
|
|
||||||
|
while message.lower().strip() != 'bye':
|
||||||
|
client_socket.send(message.encode()) # send message
|
||||||
|
data = client_socket.recv(1024).decode() # receive response
|
||||||
|
|
||||||
|
print('Received from server: ' + data) # show in terminal
|
||||||
|
|
||||||
|
message = input(" -> ") # again take input
|
||||||
|
|
||||||
|
client_socket.close() # close the connection
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
client_program()
|
Loading…
Reference in New Issue