CARLA
 
载入中...
搜索中...
未找到
OpenDriveGenerator.cpp
浏览该文件的文档.
1// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma
2// de Barcelona (UAB).
3//
4// This work is licensed under the terms of the MIT license.
5// For a copy, see <https://opensource.org/licenses/MIT>.
6
7#include "Carla.h"
12
15#include <carla/rpc/String.h>
17
18#include "Engine/Classes/Interfaces/Interface_CollisionDataProvider.h"
19#include "PhysicsCore/Public/BodySetupEnums.h"
20
22{
23 PrimaryActorTick.bCanEverTick = false;
24 MeshComponent = CreateDefaultSubobject<UProceduralMeshComponent>(TEXT("RootComponent"));
25 RootComponent = MeshComponent;
26}
27
28AOpenDriveGenerator::AOpenDriveGenerator(const FObjectInitializer &ObjectInitializer)
29 : Super(ObjectInitializer)
30{
31 PrimaryActorTick.bCanEverTick = false;
32 RootComponent = CreateDefaultSubobject<USceneComponent>(TEXT("SceneComponent"));
33 SetRootComponent(RootComponent);
34 RootComponent->Mobility = EComponentMobility::Static;
35}
36
37bool AOpenDriveGenerator::LoadOpenDrive(const FString &OpenDrive)
38{
39 using OpenDriveLoader = carla::opendrive::OpenDriveParser;
40
41 if (OpenDrive.IsEmpty())
42 {
43 UE_LOG(LogCarla, Error, TEXT("The OpenDrive is empty"));
44 return false;
45 }
46
47 OpenDriveData = OpenDrive;
48 return true;
49}
50
52{
53 return OpenDriveData;
54}
55
57{
58 return UCarlaStatics::GetGameMode(GetWorld())->GetMap().has_value();
59}
60
62{
63 if (!IsOpenDriveValid())
64 {
65 UE_LOG(LogCarla, Error, TEXT("The OpenDrive has not been loaded"));
66 return;
67 }
68
70 UCarlaGameInstance * GameInstance = UCarlaStatics::GetGameInstance(GetWorld());
71 if(GameInstance)
72 {
73 Parameters = GameInstance->GetOpendriveGenerationParameters();
74 }
75 else
76 {
77 carla::log_warning("Missing game instance");
78 }
79
80 auto& CarlaMap = UCarlaStatics::GetGameMode(GetWorld())->GetMap();
81 const auto Meshes = CarlaMap->GenerateChunkedMesh(Parameters);
82 for (const auto &Mesh : Meshes) {
83 if (!Mesh->GetVertices().size())
84 {
85 continue;
86 }
87 AProceduralMeshActor* TempActor = GetWorld()->SpawnActor<AProceduralMeshActor>();
88 UProceduralMeshComponent *TempPMC = TempActor->MeshComponent;
89 TempPMC->bUseAsyncCooking = true;
90 TempPMC->bUseComplexAsSimpleCollision = true;
91 TempPMC->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
92
93 const FProceduralCustomMesh MeshData = *Mesh;
94 TempPMC->CreateMeshSection_LinearColor(
95 0,
96 MeshData.Vertices,
97 MeshData.Triangles,
98 MeshData.Normals,
99 TArray<FVector2D>(), // UV0
100 TArray<FLinearColor>(), // VertexColor
101 TArray<FProcMeshTangent>(), // Tangents
102 true); // Create collision
103
104 ActorMeshList.Add(TempActor);
105 }
106
107 if(!Parameters.enable_mesh_visibility)
108 {
109 for(AActor * actor : ActorMeshList)
110 {
111 actor->SetActorHiddenInGame(true);
112 }
113 }
114
115 // // Build collision data
116 // FTriMeshCollisionData CollisitonData;
117 // CollisitonData.bDeformableMesh = false;
118 // CollisitonData.bDisableActiveEdgePrecompute = false;
119 // CollisitonData.bFastCook = false;
120 // CollisitonData.bFlipNormals = false;
121 // CollisitonData.Indices = TriIndices;
122 // CollisitonData.Vertices = Vertices;
123
124 // RoadMesh->ContainsPhysicsTriMeshData(true);
125 // bool Success = RoadMesh->GetPhysicsTriMeshData(&CollisitonData, true);
126 // if (!Success)
127 // {
128 // UE_LOG(LogCarla, Error, TEXT("The road collision mesh could not be generated!"));
129 // }
130}
131
133{
134 if (!IsOpenDriveValid())
135 {
136 UE_LOG(LogCarla, Error, TEXT("The OpenDrive has not been loaded"));
137 return;
138 }
139 /// TODO: To implement
140}
141
143{
144 if (!IsOpenDriveValid())
145 {
146 UE_LOG(LogCarla, Error, TEXT("The OpenDrive has not been loaded"));
147 return;
148 }
149 auto& CarlaMap = UCarlaStatics::GetGameMode(GetWorld())->GetMap();
150 const auto Waypoints = CarlaMap->GenerateWaypointsOnRoadEntries();
151 for (const auto &Wp : Waypoints)
152 {
153 const FTransform Trans = CarlaMap->ComputeTransform(Wp);
154 AVehicleSpawnPoint *Spawner = GetWorld()->SpawnActor<AVehicleSpawnPoint>();
155 Spawner->SetActorRotation(Trans.GetRotation());
156 Spawner->SetActorLocation(Trans.GetTranslation() + FVector(0.f, 0.f, SpawnersHeight));
157 VehicleSpawners.Add(Spawner);
158 }
159}
160
167
169{
170 Super::BeginPlay();
171
172 const FString XodrContent = UOpenDrive::GetXODR(GetWorld());
173 LoadOpenDrive(XodrContent);
174
175 GenerateAll();
176
177 auto World = GetWorld();
178 check(World != nullptr);
179
180 // Autogenerate signals
181 AActor* TrafficLightManagerActor = UGameplayStatics::GetActorOfClass(World, ATrafficLightManager::StaticClass());
182 if(TrafficLightManagerActor == nullptr) {
183 World->SpawnActor<ATrafficLightManager>();
184 }
185}
const boost::optional< carla::road::Map > & GetMap() const
bool LoadOpenDrive(const FString &OpenDrive)
Set the OpenDRIVE information as string and generates the queryable map structure.
TArray< AVehicleSpawnPoint * > VehicleSpawners
const FString & GetOpenDrive() const
Get the OpenDRIVE information as string.
AOpenDriveGenerator(const FObjectInitializer &ObjectInitializer)
void GeneratePoles()
Generates pole meshes based on the OpenDRIVE information.
void GenerateRoadMesh()
Generates the road and sidewalk mesh based on the OpenDRIVE information.
virtual void BeginPlay() override
TArray< AActor * > ActorMeshList
float SpawnersHeight
Determine the height where the spawners will be placed, relative to each RoutePlanner
void GenerateSpawnPoints()
Generates spawn points along the road.
bool IsOpenDriveValid() const
Checks if the OpenDrive has been loaded and it's valid.
UProceduralMeshComponent * MeshComponent
Class In charge of creating and assigning traffic light groups, controllers and components.
Base class for spawner locations for walkers.
The game instance contains elements that must be kept alive in between levels.
const carla::rpc::OpendriveGenerationParameters & GetOpendriveGenerationParameters() const
static UCarlaGameInstance * GetGameInstance(const UObject *WorldContextObject)
static ACarlaGameModeBase * GetGameMode(const UObject *WorldContextObject)
static FString GetXODR(const UWorld *World)
Return the OpenDrive XML associated to MapName, or empty if the file is not found.
static void log_warning(Args &&... args)
Definition Logging.h:96
A definition of a Carla Mesh.
Seting for map generation from opendrive without additional geometry