11 #include "Engine/DecalActor.h" 12 #include "Engine/LevelStreaming.h" 13 #include "Engine/LocalPlayer.h" 14 #include "Materials/MaterialInstanceDynamic.h" 24 #include "Async/ParallelFor.h" 25 #include "DynamicRHI.h" 27 #include "DrawDebugHelpers.h" 28 #include "Kismet/KismetSystemLibrary.h" 35 : Super(ObjectInitializer)
37 PrimaryActorTick.bCanEverTick =
true;
38 PrimaryActorTick.TickGroup = TG_PrePhysics;
39 bAllowTickBeforeBeginPlay =
false;
41 Episode = CreateDefaultSubobject<UCarlaEpisode>(TEXT(
"Episode"));
43 Recorder = CreateDefaultSubobject<ACarlaRecorder>(TEXT(
"Recorder"));
45 ObjectRegister = CreateDefaultSubobject<UObjectRegister>(TEXT(
"ObjectRegister"));
48 HUDClass = ACarlaHUD::StaticClass();
50 TaggerDelegate = CreateDefaultSubobject<UTaggerDelegate>(TEXT(
"TaggerDelegate"));
51 CarlaSettingsDelegate = CreateDefaultSubobject<UCarlaSettingsDelegate>(TEXT(
"CarlaSettingsDelegate"));
56 UWorld* World = GetWorld();
57 TSoftObjectPtr<UWorld> AssetPtr (World);
58 FString
Path = FPaths::GetPath(AssetPtr.GetLongPackageName());
59 Path.RemoveFromStart(
"/Game/");
66 return FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()) +
Path;
70 const FString &MapName,
71 const FString &Options,
72 FString &ErrorMessage)
75 Super::InitGame(MapName, Options, ErrorMessage);
77 UWorld* World = GetWorld();
78 check(World !=
nullptr);
79 FString InMapName(MapName);
83 TEXT(
"Missing episode, can't continue without an episode!"));
86 UGameplayStatics::GetActorOfClass(GetWorld(), ALargeMapManager::StaticClass());
87 LMManager = Cast<ALargeMapManager>(LMManagerActor);
100 FString CorrectedMapName = InMapName;
101 constexpr
auto PIEPrefix = TEXT(
"UEDPIE_0_");
102 CorrectedMapName.RemoveFromStart(PIEPrefix);
103 UE_LOG(LogCarla, Log, TEXT(
"Corrected map name from %s to %s"), *InMapName, *CorrectedMapName);
108 #endif // WITH_EDITOR 110 GameInstance = Cast<UCarlaGameInstance>(GetGameInstance());
113 TEXT(
"GameInstance is not a UCarlaGameInstance, did you forget to set " 114 "it in the project settings?"));
119 UE_LOG(LogCarla, Error, TEXT(
"Missing TaggerDelegate!"));
126 UE_LOG(LogCarla, Error, TEXT(
"Missing CarlaSettingsDelegate!"));
132 UE_LOG(LogCarla, Error, TEXT(
"Missing weather class!"));
162 Super::RestartPlayer(NewPlayer);
169 UWorld* World = GetWorld();
170 check(World !=
nullptr);
187 World->SpawnActor<ADecalActor>(
188 FVector(0,0,-1000000), FRotator(0,0,0), FActorSpawnParameters());
191 Manager->InitializeTrafficLights();
218 TArray<AActor*> FoundActors;
219 UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);
222 TArray<UCarlaLight*> Lights;
223 Actor->GetComponents(Lights,
false);
224 for(UCarlaLight* Light : Lights)
226 Light->RegisterLight();
227 if(!Light->HasBegunPlay())
238 TArray<FString> Names;
239 TArray<AActor*> Actors;
240 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), Actors);
243 TArray<UStaticMeshComponent*> StaticMeshes;
244 Actor->GetComponents(StaticMeshes);
245 if (StaticMeshes.Num())
247 Names.Add(
Actor->GetName());
255 TArray<AActor*> Actors;
256 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), Actors);
259 if(
Actor->GetName() == ActorName)
270 FlushRenderingCommands();
271 TArray<FColor> Colors;
272 for (uint32_t y = 0; y < Texture.
GetHeight(); y++)
274 for (uint32_t x = 0; x < Texture.
GetWidth(); x++)
280 UTexture2D* UETexture = UTexture2D::CreateTransient(Texture.
GetWidth(), Texture.
GetHeight(), EPixelFormat::PF_B8G8R8A8);
281 FTexture2DMipMap& Mip = UETexture->PlatformData->Mips[0];
282 void* Data = Mip.BulkData.Lock( LOCK_READ_WRITE );
283 FMemory::Memcpy( Data,
286 Mip.BulkData.Unlock();
287 UETexture->UpdateResource();
293 FlushRenderingCommands();
294 TArray<FFloat16Color> Colors;
295 for (uint32_t y = 0; y < Texture.
GetHeight(); y++)
297 for (uint32_t x = 0; x < Texture.
GetWidth(); x++)
303 UTexture2D* UETexture = UTexture2D::CreateTransient(Texture.
GetWidth(), Texture.
GetHeight(), EPixelFormat::PF_FloatRGBA);
304 FTexture2DMipMap& Mip = UETexture->PlatformData->Mips[0];
305 void* Data = Mip.BulkData.Lock( LOCK_READ_WRITE );
306 FMemory::Memcpy( Data,
309 Mip.BulkData.Unlock();
310 UETexture->UpdateResource();
320 TArray<UStaticMeshComponent*> StaticMeshes;
321 Actor->GetComponents(StaticMeshes);
322 for (UStaticMeshComponent* Mesh : StaticMeshes)
324 for (
int i = 0; i < Mesh->GetNumMaterials(); ++i)
326 UMaterialInterface* OriginalMaterial = Mesh->GetMaterial(i);
327 UMaterialInstanceDynamic* DynamicMaterial = Cast<UMaterialInstanceDynamic>(OriginalMaterial);
330 DynamicMaterial = UMaterialInstanceDynamic::Create(OriginalMaterial, NULL);
331 Mesh->SetMaterial(i, DynamicMaterial);
336 case cr::MaterialParameter::Tex_Diffuse:
337 DynamicMaterial->SetTextureParameterValue(
"BaseColor", Texture);
338 DynamicMaterial->SetTextureParameterValue(
"Difuse", Texture);
339 DynamicMaterial->SetTextureParameterValue(
"Difuse 2", Texture);
340 DynamicMaterial->SetTextureParameterValue(
"Difuse 3", Texture);
341 DynamicMaterial->SetTextureParameterValue(
"Difuse 4", Texture);
343 case cr::MaterialParameter::Tex_Normal:
344 DynamicMaterial->SetTextureParameterValue(
"Normal", Texture);
345 DynamicMaterial->SetTextureParameterValue(
"Normal 2", Texture);
346 DynamicMaterial->SetTextureParameterValue(
"Normal 3", Texture);
347 DynamicMaterial->SetTextureParameterValue(
"Normal 4", Texture);
349 case cr::MaterialParameter::Tex_Emissive:
350 DynamicMaterial->SetTextureParameterValue(
"Emissive", Texture);
352 case cr::MaterialParameter::Tex_Ao_Roughness_Metallic_Emissive:
353 DynamicMaterial->SetTextureParameterValue(
"AO / Roughness / Metallic / Emissive", Texture);
354 DynamicMaterial->SetTextureParameterValue(
"ORMH", Texture);
355 DynamicMaterial->SetTextureParameterValue(
"ORMH 2", Texture);
356 DynamicMaterial->SetTextureParameterValue(
"ORMH 3", Texture);
357 DynamicMaterial->SetTextureParameterValue(
"ORMH 4", Texture);
366 Super::Tick(DeltaSeconds);
382 Super::EndPlay(EndPlayReason);
392 auto *World = GetWorld();
393 check(World !=
nullptr);
397 if (FactoryClass !=
nullptr)
400 if (Factory !=
nullptr)
407 UE_LOG(LogCarla, Error, TEXT(
"Failed to spawn actor spawner"));
415 for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It)
430 UE_LOG(LogCarla, Log, TEXT(
"Generating SpawnPoints ..."));
431 std::vector<std::pair<carla::road::element::Waypoint, carla::road::element::Waypoint>> Topology =
Map->GenerateTopology();
432 UWorld* World = GetWorld();
433 for(
auto& Pair : Topology)
437 Transform.AddToTranslation(FVector(0.f, 0.f, 300.0f));
446 if (!
Map.has_value()) {
447 UE_LOG(LogCarla, Error, TEXT(
"Invalid Map"));
459 UWorld* World = GetWorld();
460 AActor* TrafficLightManagerActor = UGameplayStatics::GetActorOfClass(World, ATrafficLightManager::StaticClass());
461 if(TrafficLightManagerActor ==
nullptr)
463 FActorSpawnParameters SpawnParams;
477 TArray<AActor*> WorldActors;
478 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AStaticMeshActor::StaticClass(), WorldActors);
482 AStaticMeshActor *MeshActor = CastChecked<AStaticMeshActor>(
Actor);
483 if (MeshActor->GetStaticMeshComponent()->GetStaticMesh() == NULL)
485 UE_LOG(LogTemp, Error, TEXT(
"The object : %s has no mesh"), *MeshActor->GetFullName());
492 TArray<AActor*> WorldActors;
493 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AStaticMeshActor::StaticClass(), WorldActors);
497 AStaticMeshActor *MeshActor = CastChecked<AStaticMeshActor>(
Actor);
498 if(MeshActor->GetStaticMeshComponent()->GetStaticMesh() != NULL)
500 if (MeshActor->GetStaticMeshComponent()->GetGenerateOverlapEvents() ==
false)
502 MeshActor->GetStaticMeshComponent()->SetGenerateOverlapEvents(
true);
511 auto World = GetWorld();
512 check(World !=
nullptr);
521 UKismetSystemLibrary::FlushDebugStrings(World);
522 UKismetSystemLibrary::FlushPersistentDebugLines(World);
527 const auto& Signals =
Map->GetSignals();
528 const auto& Controllers =
Map->GetControllers();
530 for(
const auto& Signal : Signals) {
531 const auto& ODSignal = Signal.second;
532 const FTransform
Transform = ODSignal->GetTransform();
533 const FVector
Location = Transform.GetLocation();
534 const FQuat
Rotation = Transform.GetRotation();
546 TArray<const cre::RoadInfoSignal*> References;
547 auto waypoints =
Map->GenerateWaypointsOnRoadEntries();
548 std::unordered_set<cr::RoadId> ExploredRoads;
549 for (
auto & waypoint : waypoints)
552 if (ExploredRoads.count(waypoint.road_id) > 0)
556 ExploredRoads.insert(waypoint.road_id);
559 auto SignalReferences =
Map->GetLane(waypoint).
561 for (
auto *SignalReference : SignalReferences)
563 References.Add(SignalReference);
566 for (
auto& Reference : References)
568 auto RoadId = Reference->GetRoadId();
569 const auto* SignalReference = Reference;
570 const FTransform SignalTransform = SignalReference->GetSignal()->GetTransform();
571 for(
auto &validity : SignalReference->GetValidities())
578 auto signal_waypoint =
Map->GetWaypoint(
579 RoadId, lane, SignalReference->GetS()).
get();
581 if(
Map->GetLane(signal_waypoint).GetType() != cr::Lane::LaneType::Driving)
584 FTransform ReferenceTransform =
Map->ComputeTransform(signal_waypoint);
588 ReferenceTransform.GetLocation(),
597 ReferenceTransform.GetLocation(),
598 SignalTransform.GetLocation(),
610 UWorld* World = GetWorld();
613 TArray<AActor*> FoundActors;
614 UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);
616 TArray<FBoundingBox> BoundingBoxes;
619 return BoundingBoxes;
625 TArray<AActor*> FoundActors;
626 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), FoundActors);
631 const TSet<uint64>& EnvObjectIds,
639 const UWorld* World = GetWorld();
640 UGameplayStatics::FlushLevelStreaming(World);
642 TArray<FName> LevelsToLoad;
645 FLatentActionInfo LatentInfo;
646 LatentInfo.CallbackTarget =
this;
647 LatentInfo.ExecutionFunction =
"OnLoadStreamLevel";
648 LatentInfo.Linkage = 0;
653 for(FName& LevelName : LevelsToLoad)
656 UGameplayStatics::LoadStreamLevel(World, LevelName,
true,
true, LatentInfo);
658 UGameplayStatics::FlushLevelStreaming(World);
664 const UWorld* World = GetWorld();
666 TArray<FName> LevelsToUnLoad;
669 FLatentActionInfo LatentInfo;
670 LatentInfo.CallbackTarget =
this;
671 LatentInfo.ExecutionFunction =
"OnUnloadStreamLevel";
673 LatentInfo.Linkage = 0;
677 for(FName& LevelName : LevelsToUnLoad)
680 UGameplayStatics::UnloadStreamLevel(World, LevelName, LatentInfo,
false);
682 UGameplayStatics::FlushLevelStreaming(World);
689 UWorld* World = GetWorld();
690 const TArray <ULevelStreaming*> Levels = World->GetStreamingLevels();
691 TArray<FString> LayersToLoad;
700 FString LayerName = UTF8_TO_TCHAR(
MapLayerToString(static_cast<crp::MapLayer>(LayerMask)).c_str());
704 LayersToLoad.Emplace(LayerName);
706 LayerMask = (LayerMask << 1) & AllLayersMask;
710 for(ULevelStreaming* Level : Levels)
712 TArray<FString> StringArray;
713 FString FullSubMapName = Level->GetWorldAssetPackageFName().ToString();
715 FullSubMapName.ParseIntoArray(StringArray, TEXT(
"/"),
false);
716 FString SubMapName = StringArray[StringArray.Num() - 1];
717 for(FString LayerName : LayersToLoad)
719 if(SubMapName.Contains(LayerName))
721 OutLevelNames.Emplace(FName(*SubMapName));
731 ULevel* OutLevel =
nullptr;
732 UWorld* World = GetWorld();
733 const TArray <ULevelStreaming*> Levels = World->GetStreamingLevels();
735 for(ULevelStreaming* Level : Levels)
737 FString FullSubMapName = Level->GetWorldAssetPackageFName().ToString();
738 if(FullSubMapName.Contains(LevelName))
740 OutLevel = Level->GetLoadedLevel();
743 UE_LOG(LogCarla, Warning, TEXT(
"%s has not been loaded"), *LevelName);
void CheckPlayAfterMapLoaded(void)
UObjectRegister * ObjectRegister
TSet< TSubclassOf< ACarlaActorFactory > > ActorFactories
List of actor spawners that will be used to define and spawn the actors available in game...
Base class for Carla actor factories.
int32 GetCurrentMapLayer() const
ACarlaRecorder * Recorder
void ApplyTextureToActor(AActor *Actor, UTexture2D *Texture, const carla::rpc::MaterialParameter &TextureParam)
ULevel * GetULevelFromName(FString LevelName)
sensor::data::Color Color
static TArray< FBoundingBox > GetBoundingBoxOfActors(const TArray< AActor *> &Actors, uint8 InTagQueried=0xFF)
void EndPlay(const EEndPlayReason::Type EndPlayReason) override
void SetEpisode(UCarlaEpisode *ThisEpisode)
void ApplyQualityLevelPostRestart()
After loading a level, apply the current settings.
bool ReadyToRegisterObjects
TArray< ACarlaActorFactory * > ActorFactoryInstances
std::vector< cg::Location > Path
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
void DebugShowSignals(bool enable)
FDelegateHandle OnEpisodeSettingsChangeHandle
void SetAllActorsDrawDistance(UWorld *world, float max_draw_distance) const
void NotifyBeginEpisode(UCarlaEpisode &Episode)
void SpawnActorFactories()
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
void CheckForEmptyMeshes()
void RegisterSpawnHandler(UWorld *World)
Create the event trigger handler for all the newly spawned actors to be processed with a custom funct...
UCarlaGameInstance * GameInstance
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
void UnLoadMapLayer(int32 MapLayers)
CarlaReplayer * GetReplayer(void)
AActor * FindActorByName(const FString &ActorName)
UTexture2D * CreateUETexture(const carla::rpc::TextureColor &Texture)
void InitGame(const FString &MapName, const FString &Options, FString &ErrorMessage) override
static boost::optional< road::Map > Load(const std::string &opendrive)
ALargeMapManager * LMManager
void RegisterEnvironmentObjects()
void LoadMapLayer(int32 MapLayers)
static void TagActorsInLevel(UWorld &World, bool bTagForSemanticSegmentation)
Set the tag of every actor in level.
carla::SharedPtr< cc::Actor > Actor
int PendingLevelsToUnLoad
void Tick(float DeltaSeconds) override
void OnUnloadStreamLevel()
std::string MapLayerToString(MapLayer MapLayerValue)
void EnableOverlapEvents()
void RegisterInitialObjects()
UTaggerDelegate * TaggerDelegate
TArray< FString > GetNamesOfAllActors()
static FString GetXODR(const UWorld *World)
Return the OpenDrive XML associated to MapName, or empty if the file is not found.
void GenerateSpawnPoints()
T & At(uint32_t x, uint32_t y)
const FString GetRelativeMapPath() const
void RegisterActorFactory(ACarlaActorFactory &ActorFactory)
static WeatherParameters Default
TArray< FTransform > SpawnPointsTransforms
void SetRecorder(ACarlaRecorder *Rec)
boost::optional< carla::road::Map > Map
carla::geom::GeoLocation MapGeoReference
TSubclassOf< AWeather > WeatherClass
The class of Weather to spawn.
static std::vector< int > GenerateRange(int a, int b)
void RestartPlayer(AController *NewPlayer) override
UCarlaSettingsDelegate * CarlaSettingsDelegate
TArray< FBoundingBox > GetAllBBsOfLevel(uint8 TagQueried=0xFF) const
uint32_t GetHeight() const
void Reset()
Reset settings to default.
void SetSemanticSegmentationEnabled(bool Enable=true)
void RegisterObjects(TArray< AActor *> Actors)
void InitializeAtBeginPlay()
Vector3D GetUpVector() const
void RegisterSpawnHandler(UWorld *World)
ATrafficLightManager * GetTrafficLightManager()
const FString GetFullMapPath() const
void ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray< FName > &OutLevelNames)
geom::Transform Transform
void ApplyWeather(const FWeatherParameters &WeatherParameters)
Update the weather parameters and notifies it to the blueprint's event.
uint32_t GetWidth() const
void ApplyQualityLevelPreRestart()
Before loading a level, apply the current settings.
void OnEpisodeSettingsChanged(const FEpisodeSettings &Settings)
ACarlaGameModeBase(const FObjectInitializer &ObjectInitializer)
ATrafficLightManager * TrafficLightManager
Class In charge of creating and assigning traffic light groups, controllers and components.
void BeginPlay() override