CARLA
 
载入中...
搜索中...
未找到
CarlaGameModeBase.cpp
浏览该文件的文档.
1// Copyright (c) 2017 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"
13#include "Engine/DecalActor.h"
14#include "Engine/LevelStreaming.h"
15#include "Engine/LocalPlayer.h"
16#include "Materials/MaterialInstanceDynamic.h"
17#include "Engine/StaticMeshActor.h"
20#include "EngineUtils.h"
21
27#include <carla/rpc/MapLayer.h>
29
30#include "Async/ParallelFor.h"
31#include "DynamicRHI.h"
32
33#include "DrawDebugHelpers.h"
34#include "Kismet/KismetSystemLibrary.h"
35
36namespace cr = carla::road;
37namespace crp = carla::rpc;
38namespace cre = carla::road::element;
39
40ACarlaGameModeBase::ACarlaGameModeBase(const FObjectInitializer& ObjectInitializer)
41 : Super(ObjectInitializer)
42{
43 PrimaryActorTick.bCanEverTick = true;
44 PrimaryActorTick.TickGroup = TG_PrePhysics;
45 bAllowTickBeforeBeginPlay = false;
46
47 Episode = CreateDefaultSubobject<UCarlaEpisode>(TEXT("Episode"));
48
49 Recorder = CreateDefaultSubobject<ACarlaRecorder>(TEXT("Recorder"));
50
51 ObjectRegister = CreateDefaultSubobject<UObjectRegister>(TEXT("ObjectRegister"));
52
53 // HUD
54 HUDClass = ACarlaHUD::StaticClass();
55
56 TaggerDelegate = CreateDefaultSubobject<UTaggerDelegate>(TEXT("TaggerDelegate"));
57 CarlaSettingsDelegate = CreateDefaultSubobject<UCarlaSettingsDelegate>(TEXT("CarlaSettingsDelegate"));
58}
59
61{
62 UWorld* World = GetWorld();
63 TSoftObjectPtr<UWorld> AssetPtr (World);
64 FString Path = FPaths::GetPath(AssetPtr.GetLongPackageName());
65 Path.RemoveFromStart("/Game/");
66 return Path;
67}
68
70{
71 FString Path = GetRelativeMapPath();
72 return FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()) + Path;
73}
74
76 const FString &MapName,
77 const FString &Options,
78 FString &ErrorMessage)
79{
80 TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaGameModeBase::InitGame);
81 Super::InitGame(MapName, Options, ErrorMessage);
82
83 UWorld* World = GetWorld();
84 check(World != nullptr);
85 FString InMapName(MapName);
86
87 checkf(
88 Episode != nullptr,
89 TEXT("Missing episode, can't continue without an episode!"));
90
91 AActor* LMManagerActor =
92 UGameplayStatics::GetActorOfClass(GetWorld(), ALargeMapManager::StaticClass());
93 LMManager = Cast<ALargeMapManager>(LMManagerActor);
94 if (LMManager) {
95 if (LMManager->GetNumTiles() == 0)
96 {
98 }
99 InMapName = LMManager->LargeMapName;
100 }
101
102#if WITH_EDITOR
103 {
104 // When playing in editor the map name gets an extra prefix, here we
105 // remove it.
106 FString CorrectedMapName = InMapName;
107 constexpr auto PIEPrefix = TEXT("UEDPIE_0_");
108 CorrectedMapName.RemoveFromStart(PIEPrefix);
109 UE_LOG(LogCarla, Log, TEXT("Corrected map name from %s to %s"), *InMapName, *CorrectedMapName);
110 Episode->MapName = CorrectedMapName;
111 }
112#else
113 Episode->MapName = InMapName;
114#endif // WITH_EDITOR
115
116 GameInstance = Cast<UCarlaGameInstance>(GetGameInstance());
117 checkf(
118 GameInstance != nullptr,
119 TEXT("GameInstance is not a UCarlaGameInstance, did you forget to set "
120 "it in the project settings?"));
121
122 if (TaggerDelegate != nullptr) {
124 } else {
125 UE_LOG(LogCarla, Error, TEXT("Missing TaggerDelegate!"));
126 }
127
128 if(CarlaSettingsDelegate != nullptr) {
131 } else {
132 UE_LOG(LogCarla, Error, TEXT("Missing CarlaSettingsDelegate!"));
133 }
134
135 AActor* WeatherActor =
136 UGameplayStatics::GetActorOfClass(GetWorld(), AWeather::StaticClass());
137 if (WeatherActor != nullptr) {
138 UE_LOG(LogCarla, Log, TEXT("Existing weather actor. Doing nothing then!"));
139 Episode->Weather = static_cast<AWeather*>(WeatherActor);
140 }
141 else if (WeatherClass != nullptr) {
142 Episode->Weather = World->SpawnActor<AWeather>(WeatherClass);
143 } else {
144 UE_LOG(LogCarla, Error, TEXT("Missing weather class!"));
145 }
146
148
150 this,
152
154
155 // make connection between Episode and Recorder
158
160
161 if(Map.has_value())
162 {
164 }
165}
166
168{
169 if (CarlaSettingsDelegate != nullptr)
170 {
172 }
173
174 Super::RestartPlayer(NewPlayer);
175}
176
178{
179 Super::BeginPlay();
180
181 UWorld* World = GetWorld();
182 check(World != nullptr);
183
186
187 if (true) { /// @todo If semantic segmentation enabled.
188 ATagger::TagActorsInLevel(*World, true);
190 }
191
192 // HACK: fix transparency see-through issues
193 // The problem: transparent objects are visible through walls.
194 // This is due to a weird interaction between the SkyAtmosphere component,
195 // the shadows of a directional light (the sun)
196 // and the custom depth set to 3 used for semantic segmentation
197 // The solution: Spawn a Decal.
198 // It just works!
199 World->SpawnActor<ADecalActor>(
200 FVector(0,0,-1000000), FRotator(0,0,0), FActorSpawnParameters());
201
203 Manager->InitializeTrafficLights();
204
207
208 if (Episode->Weather != nullptr)
209 {
211 }
212
213 /// @todo Recorder should not tick here, FCarlaEngine should do it.
214 // check if replayer is waiting to autostart
215 if (Recorder)
216 {
218 }
219
221 {
223 }
224
225 if (LMManager) {
228 }
229
230 // Manually run begin play on lights as it may not run on sublevels
231 TArray<AActor*> FoundActors;
232 UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);
233 for(AActor* Actor : FoundActors)
234 {
235 TArray<UCarlaLight*> Lights;
236 Actor->GetComponents(Lights, false);
237 for(UCarlaLight* Light : Lights)
238 {
239 Light->RegisterLight();
240 }
241 }
243}
244
246{
247 TArray<FString> Names;
248 TArray<AActor*> Actors;
249 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), Actors);
250 for (AActor* Actor : Actors)
251 {
252 TArray<UStaticMeshComponent*> StaticMeshes;
253 Actor->GetComponents(StaticMeshes);
254 if (StaticMeshes.Num())
255 {
256 Names.Add(Actor->GetName());
257 }
258 }
259 return Names;
260}
261
263{
264 TArray<AActor*> Actors;
265 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), Actors);
266 for (AActor* Actor : Actors)
267 {
268 if(Actor->GetName() == ActorName)
269 {
270 return Actor;
271 break;
272 }
273 }
274 return nullptr;
275}
276
278{
279 FlushRenderingCommands();
280 TArray<FColor> Colors;
281 for (uint32_t y = 0; y < Texture.GetHeight(); y++)
282 {
283 for (uint32_t x = 0; x < Texture.GetWidth(); x++)
284 {
285 auto& Color = Texture.At(x,y);
286 Colors.Add(FColor(Color.r, Color.g, Color.b, Color.a));
287 }
288 }
289 UTexture2D* UETexture = UTexture2D::CreateTransient(Texture.GetWidth(), Texture.GetHeight(), EPixelFormat::PF_B8G8R8A8);
290 FTexture2DMipMap& Mip = UETexture->PlatformData->Mips[0];
291 void* Data = Mip.BulkData.Lock( LOCK_READ_WRITE );
292 FMemory::Memcpy( Data,
293 &Colors[0],
294 Texture.GetWidth()*Texture.GetHeight()*sizeof(FColor));
295 Mip.BulkData.Unlock();
296 UETexture->UpdateResource();
297 return UETexture;
298}
299
301{
302 FlushRenderingCommands();
303 TArray<FFloat16Color> Colors;
304 for (uint32_t y = 0; y < Texture.GetHeight(); y++)
305 {
306 for (uint32_t x = 0; x < Texture.GetWidth(); x++)
307 {
308 auto& Color = Texture.At(x,y);
309 Colors.Add(FLinearColor(Color.r, Color.g, Color.b, Color.a));
310 }
311 }
312 UTexture2D* UETexture = UTexture2D::CreateTransient(Texture.GetWidth(), Texture.GetHeight(), EPixelFormat::PF_FloatRGBA);
313 FTexture2DMipMap& Mip = UETexture->PlatformData->Mips[0];
314 void* Data = Mip.BulkData.Lock( LOCK_READ_WRITE );
315 FMemory::Memcpy( Data,
316 &Colors[0],
317 Texture.GetWidth()*Texture.GetHeight()*sizeof(FFloat16Color));
318 Mip.BulkData.Unlock();
319 UETexture->UpdateResource();
320 return UETexture;
321}
322
324 AActor* Actor,
325 UTexture2D* Texture,
326 const carla::rpc::MaterialParameter& TextureParam)
327{
328 namespace cr = carla::rpc;
329 TArray<UStaticMeshComponent*> StaticMeshes;
330 Actor->GetComponents(StaticMeshes);
331 for (UStaticMeshComponent* Mesh : StaticMeshes)
332 {
333 for (int i = 0; i < Mesh->GetNumMaterials(); ++i)
334 {
335 UMaterialInterface* OriginalMaterial = Mesh->GetMaterial(i);
336 UMaterialInstanceDynamic* DynamicMaterial = Cast<UMaterialInstanceDynamic>(OriginalMaterial);
337 if(!DynamicMaterial)
338 {
339 DynamicMaterial = UMaterialInstanceDynamic::Create(OriginalMaterial, NULL);
340 Mesh->SetMaterial(i, DynamicMaterial);
341 }
342
343 switch(TextureParam)
344 {
345 case cr::MaterialParameter::Tex_Diffuse:
346 DynamicMaterial->SetTextureParameterValue("BaseColor", Texture);
347 DynamicMaterial->SetTextureParameterValue("Difuse", Texture);
348 DynamicMaterial->SetTextureParameterValue("Difuse 2", Texture);
349 DynamicMaterial->SetTextureParameterValue("Difuse 3", Texture);
350 DynamicMaterial->SetTextureParameterValue("Difuse 4", Texture);
351 break;
352 case cr::MaterialParameter::Tex_Normal:
353 DynamicMaterial->SetTextureParameterValue("Normal", Texture);
354 DynamicMaterial->SetTextureParameterValue("Normal 2", Texture);
355 DynamicMaterial->SetTextureParameterValue("Normal 3", Texture);
356 DynamicMaterial->SetTextureParameterValue("Normal 4", Texture);
357 break;
358 case cr::MaterialParameter::Tex_Emissive:
359 DynamicMaterial->SetTextureParameterValue("Emissive", Texture);
360 break;
361 case cr::MaterialParameter::Tex_Ao_Roughness_Metallic_Emissive:
362 DynamicMaterial->SetTextureParameterValue("AO / Roughness / Metallic / Emissive", Texture);
363 DynamicMaterial->SetTextureParameterValue("ORMH", Texture);
364 DynamicMaterial->SetTextureParameterValue("ORMH 2", Texture);
365 DynamicMaterial->SetTextureParameterValue("ORMH 3", Texture);
366 DynamicMaterial->SetTextureParameterValue("ORMH 4", Texture);
367 break;
368 }
369 }
370 }
371}
372
373void ACarlaGameModeBase::Tick(float DeltaSeconds)
374{
375 Super::Tick(DeltaSeconds);
376
377 /// @todo Recorder should not tick here, FCarlaEngine should do it.
378 if (Recorder)
379 {
380 Recorder->Tick(DeltaSeconds);
381 }
382}
383
384void ACarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
385{
387
388 Episode->EndPlay();
390
391 Super::EndPlay(EndPlayReason);
392
393 if ((CarlaSettingsDelegate != nullptr) && (EndPlayReason != EEndPlayReason::EndPlayInEditor))
394 {
396 }
397}
398
400{
401 auto *World = GetWorld();
402 check(World != nullptr);
403
404 for (auto &FactoryClass : ActorFactories)
405 {
406 if (FactoryClass != nullptr)
407 {
408 auto *Factory = World->SpawnActor<ACarlaActorFactory>(FactoryClass);
409 if (Factory != nullptr)
410 {
411 Episode->RegisterActorFactory(*Factory);
412 ActorFactoryInstances.Add(Factory);
413 }
414 else
415 {
416 UE_LOG(LogCarla, Error, TEXT("Failed to spawn actor spawner"));
417 }
418 }
419 }
420}
421
423{
424 for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It)
425 {
426 SpawnPointsTransforms.Add(It->GetActorTransform());
427 }
428
429 if(SpawnPointsTransforms.Num() == 0)
430 {
432 }
433
434 UE_LOG(LogCarla, Log, TEXT("There are %d SpawnPoints in the map"), SpawnPointsTransforms.Num());
435}
436
438{
439 UE_LOG(LogCarla, Log, TEXT("Generating SpawnPoints ..."));
440 std::vector<std::pair<carla::road::element::Waypoint, carla::road::element::Waypoint>> Topology = Map->GenerateTopology();
441 UWorld* World = GetWorld();
442 for(auto& Pair : Topology)
443 {
444 carla::geom::Transform CarlaTransform = Map->ComputeTransform(Pair.first);
445 FTransform Transform(CarlaTransform);
446 Transform.AddToTranslation(FVector(0.f, 0.f, 50.0f));
447 SpawnPointsTransforms.Add(Transform);
448 }
449}
450
452{
453 std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::GetXODR(GetWorld()));
455 if (!Map.has_value()) {
456 UE_LOG(LogCarla, Error, TEXT("Invalid Map"));
457 }
458 else
459 {
460 Episode->MapGeoReference = Map->GetGeoReference();
461 }
462}
463
465{
467 {
468 UWorld* World = GetWorld();
469 AActor* TrafficLightManagerActor = UGameplayStatics::GetActorOfClass(World, ATrafficLightManager::StaticClass());
470 if(TrafficLightManagerActor == nullptr)
471 {
472 FActorSpawnParameters SpawnParams;
473 SpawnParams.OverrideLevel = GetULevelFromName("TrafficLights");
474 TrafficLightManager = World->SpawnActor<ATrafficLightManager>(SpawnParams);
475 }
476 else
477 {
478 TrafficLightManager = Cast<ATrafficLightManager>(TrafficLightManagerActor);
479 }
480 }
481 return TrafficLightManager;
482}
483
485{
486 TArray<AActor*> WorldActors;
487 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AStaticMeshActor::StaticClass(), WorldActors);
488
489 for (AActor *Actor : WorldActors)
490 {
491 AStaticMeshActor *MeshActor = CastChecked<AStaticMeshActor>(Actor);
492 if (MeshActor->GetStaticMeshComponent()->GetStaticMesh() == NULL)
493 {
494 UE_LOG(LogTemp, Error, TEXT("The object : %s has no mesh"), *MeshActor->GetFullName());
495 }
496 }
497}
498
500{
501 TArray<AActor*> WorldActors;
502 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AStaticMeshActor::StaticClass(), WorldActors);
503
504 for(AActor *Actor : WorldActors)
505 {
506 AStaticMeshActor *MeshActor = CastChecked<AStaticMeshActor>(Actor);
507 if(MeshActor->GetStaticMeshComponent()->GetStaticMesh() != NULL)
508 {
509 auto MeshTag = ATagger::GetTagOfTaggedComponent(*MeshActor->GetStaticMeshComponent());
510 namespace crp = carla::rpc;
511 if (MeshTag != crp::CityObjectLabel::Roads &&
512 MeshTag != crp::CityObjectLabel::Sidewalks &&
513 MeshTag != crp::CityObjectLabel::RoadLines &&
514 MeshTag != crp::CityObjectLabel::Ground &&
515 MeshTag != crp::CityObjectLabel::Terrain &&
516 MeshActor->GetStaticMeshComponent()->GetGenerateOverlapEvents() == false)
517 {
518 MeshActor->GetStaticMeshComponent()->SetGenerateOverlapEvents(true);
519 }
520 }
521 }
522}
523
525{
526
527 auto World = GetWorld();
528 check(World != nullptr);
529
530 if(!Map)
531 {
532 return;
533 }
534
535 if(!enable)
536 {
537 UKismetSystemLibrary::FlushDebugStrings(World);
538 UKismetSystemLibrary::FlushPersistentDebugLines(World);
539 return;
540 }
541
542 //const std::unordered_map<carla::road::SignId, std::unique_ptr<carla::road::Signal>>
543 const auto& Signals = Map->GetSignals();
544 const auto& Controllers = Map->GetControllers();
545
546 for(const auto& Signal : Signals) {
547 const auto& ODSignal = Signal.second;
548 const FTransform Transform = ODSignal->GetTransform();
549 const FVector Location = Transform.GetLocation();
550 const FQuat Rotation = Transform.GetRotation();
551 const FVector Up = Rotation.GetUpVector();
552 DrawDebugSphere(
553 World,
554 Location,
555 50.0f,
556 10,
557 FColor(0, 255, 0),
558 true
559 );
560 }
561
562 TArray<const cre::RoadInfoSignal*> References;
563 auto waypoints = Map->GenerateWaypointsOnRoadEntries();
564 std::unordered_set<cr::RoadId> ExploredRoads;
565 for (auto & waypoint : waypoints)
566 {
567 // Check if we already explored this road
568 if (ExploredRoads.count(waypoint.road_id) > 0)
569 {
570 continue;
571 }
572 ExploredRoads.insert(waypoint.road_id);
573
574 // Multiple times for same road (performance impact, not in behavior)
575 auto SignalReferences = Map->GetLane(waypoint).
576 GetRoad()->GetInfos<cre::RoadInfoSignal>();
577 for (auto *SignalReference : SignalReferences)
578 {
579 References.Add(SignalReference);
580 }
581 }
582 for (auto& Reference : References)
583 {
584 auto RoadId = Reference->GetRoadId();
585 const auto* SignalReference = Reference;
586 const FTransform SignalTransform = SignalReference->GetSignal()->GetTransform();
587 for(auto &validity : SignalReference->GetValidities())
588 {
589 for(auto lane : carla::geom::Math::GenerateRange(validity._from_lane, validity._to_lane))
590 {
591 if(lane == 0)
592 continue;
593
594 auto signal_waypoint = Map->GetWaypoint(
595 RoadId, lane, SignalReference->GetS()).get();
596
597 if(Map->GetLane(signal_waypoint).GetType() != cr::Lane::LaneType::Driving)
598 continue;
599
600 FTransform ReferenceTransform = Map->ComputeTransform(signal_waypoint);
601
602 DrawDebugSphere(
603 World,
604 ReferenceTransform.GetLocation(),
605 50.0f,
606 10,
607 FColor(0, 0, 255),
608 true
609 );
610
611 DrawDebugLine(
612 World,
613 ReferenceTransform.GetLocation(),
614 SignalTransform.GetLocation(),
615 FColor(0, 0, 255),
616 true
617 );
618 }
619 }
620 }
621
622}
623
624TArray<FBoundingBox> ACarlaGameModeBase::GetAllBBsOfLevel(uint8 TagQueried) const
625{
626 UWorld* World = GetWorld();
627
628 // Get all actors of the level
629 TArray<AActor*> FoundActors;
630 UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);
631
632 TArray<FBoundingBox> BoundingBoxes;
633 BoundingBoxes = UBoundingBoxCalculator::GetBoundingBoxOfActors(FoundActors, TagQueried);
634
635 return BoundingBoxes;
636}
637
639{
640 // Get all actors of the level
641 TArray<AActor*> FoundActors;
642 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), FoundActors);
643 ObjectRegister->RegisterObjects(FoundActors);
644}
645
647 const TSet<uint64>& EnvObjectIds,
648 bool Enable)
649{
650 ObjectRegister->EnableEnvironmentObjects(EnvObjectIds, Enable);
651}
652
654{
655 const UWorld* World = GetWorld();
656 UGameplayStatics::FlushLevelStreaming(World);
657
658 TArray<FName> LevelsToLoad;
659 ConvertMapLayerMaskToMapNames(MapLayers, LevelsToLoad);
660
661 FLatentActionInfo LatentInfo;
662 LatentInfo.CallbackTarget = this;
663 LatentInfo.ExecutionFunction = "OnLoadStreamLevel";
664 LatentInfo.Linkage = 0;
665 LatentInfo.UUID = LatentInfoUUID;
666
667 PendingLevelsToLoad = LevelsToLoad.Num();
668
669 for(FName& LevelName : LevelsToLoad)
670 {
672 UGameplayStatics::LoadStreamLevel(World, LevelName, true, true, LatentInfo);
673 LatentInfo.UUID = LatentInfoUUID;
674 UGameplayStatics::FlushLevelStreaming(World);
675 }
676}
677
679{
680 const UWorld* World = GetWorld();
681
682 TArray<FName> LevelsToUnLoad;
683 ConvertMapLayerMaskToMapNames(MapLayers, LevelsToUnLoad);
684
685 FLatentActionInfo LatentInfo;
686 LatentInfo.CallbackTarget = this;
687 LatentInfo.ExecutionFunction = "OnUnloadStreamLevel";
688 LatentInfo.UUID = LatentInfoUUID;
689 LatentInfo.Linkage = 0;
690
691 PendingLevelsToUnLoad = LevelsToUnLoad.Num();
692
693 for(FName& LevelName : LevelsToUnLoad)
694 {
696 UGameplayStatics::UnloadStreamLevel(World, LevelName, LatentInfo, false);
697 LatentInfo.UUID = LatentInfoUUID;
698 UGameplayStatics::FlushLevelStreaming(World);
699 }
700
701}
702
703void ACarlaGameModeBase::ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray<FName>& OutLevelNames)
704{
705 UWorld* World = GetWorld();
706 const TArray <ULevelStreaming*> Levels = World->GetStreamingLevels();
707 TArray<FString> LayersToLoad;
708
709 // Get all the requested layers
710 int32 LayerMask = 1;
711 int32 AllLayersMask = static_cast<crp::MapLayerType>(crp::MapLayer::All);
712
713 while(LayerMask > 0)
714 {
715 // Convert enum to FString
716 FString LayerName = UTF8_TO_TCHAR(MapLayerToString(static_cast<crp::MapLayer>(LayerMask)).c_str());
717 bool included = static_cast<crp::MapLayerType>(MapLayer) & LayerMask;
718 if(included)
719 {
720 LayersToLoad.Emplace(LayerName);
721 }
722 LayerMask = (LayerMask << 1) & AllLayersMask;
723 }
724
725 // Get all the requested level maps
726 for(ULevelStreaming* Level : Levels)
727 {
728 TArray<FString> StringArray;
729 FString FullSubMapName = Level->GetWorldAssetPackageFName().ToString();
730 // Discard full path, we just need the umap name
731 FullSubMapName.ParseIntoArray(StringArray, TEXT("/"), false);
732 FString SubMapName = StringArray[StringArray.Num() - 1];
733 for(FString LayerName : LayersToLoad)
734 {
735 if(SubMapName.Contains(LayerName))
736 {
737 OutLevelNames.Emplace(FName(*SubMapName));
738 break;
739 }
740 }
741 }
742
743}
744
746{
747 ULevel* OutLevel = nullptr;
748 UWorld* World = GetWorld();
749 const TArray <ULevelStreaming*> Levels = World->GetStreamingLevels();
750
751 for(ULevelStreaming* Level : Levels)
752 {
753 FString FullSubMapName = Level->GetWorldAssetPackageFName().ToString();
754 if(FullSubMapName.Contains(LevelName))
755 {
756 OutLevel = Level->GetLoadedLevel();
757 if(!OutLevel)
758 {
759 UE_LOG(LogCarla, Warning, TEXT("%s has not been loaded"), *LevelName);
760 }
761 break;
762 }
763 }
764
765 return OutLevel;
766}
767
769{
771
772 // Register new actors and tag them
774 {
776 ATagger::TagActorsInLevel(*GetWorld(), true);
777 }
778}
779
781{
783 // Update stored registered objects (discarding the deleted objects)
785 {
787 }
788}
789
Base class for Carla actor factories.
TSubclassOf< AWeather > WeatherClass
The class of Weather to spawn.
boost::optional< carla::road::Map > Map
void UnLoadMapLayer(int32 MapLayers)
TArray< FTransform > SpawnPointsTransforms
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
TArray< ACarlaActorFactory * > ActorFactoryInstances
void DebugShowSignals(bool enable)
void BeginPlay() override
UCarlaGameInstance * GameInstance
UCarlaSettingsDelegate * CarlaSettingsDelegate
AActor * FindActorByName(const FString &ActorName)
void LoadMapLayer(int32 MapLayers)
void InitGame(const FString &MapName, const FString &Options, FString &ErrorMessage) override
void ApplyTextureToActor(AActor *Actor, UTexture2D *Texture, const carla::rpc::MaterialParameter &TextureParam)
const FString GetFullMapPath() const
ALargeMapManager * LMManager
void RestartPlayer(AController *NewPlayer) override
ACarlaRecorder * Recorder
void EndPlay(const EEndPlayReason::Type EndPlayReason) override
ULevel * GetULevelFromName(FString LevelName)
FDelegateHandle OnEpisodeSettingsChangeHandle
const FString GetRelativeMapPath() const
void ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray< FName > &OutLevelNames)
UTaggerDelegate * TaggerDelegate
ATrafficLightManager * TrafficLightManager
UObjectRegister * ObjectRegister
void OnEpisodeSettingsChanged(const FEpisodeSettings &Settings)
ATrafficLightManager * GetTrafficLightManager()
TArray< FString > GetNamesOfAllActors()
UCarlaEpisode * Episode
void Tick(float DeltaSeconds) override
TArray< FBoundingBox > GetAllBBsOfLevel(uint8 TagQueried=0xFF) const
ACarlaGameModeBase(const FObjectInitializer &ObjectInitializer)
TSet< TSubclassOf< ACarlaActorFactory > > ActorFactories
List of actor spawners that will be used to define and spawn the actors available in game.
UTexture2D * CreateUETexture(const carla::rpc::TextureColor &Texture)
CarlaReplayer * GetReplayer(void)
void SetEpisode(UCarlaEpisode *ThisEpisode)
int GetNumTiles() const
void ConsiderSpectatorAsEgo(bool _SpectatorAsEgo)
static crp::CityObjectLabel GetTagOfTaggedComponent(const UPrimitiveComponent &Component)
Retrieve the tag of an already tagged component.
Definition Tagger.h:52
static void TagActorsInLevel(UWorld &World, bool bTagForSemanticSegmentation)
Set the tag of every actor in level.
Definition Tagger.cpp:223
Class In charge of creating and assigning traffic light groups, controllers and components.
void ApplyWeather(const FWeatherParameters &WeatherParameters)
Update the weather parameters and notifies it to the blueprint's event
Definition Weather.cpp:49
void CheckPlayAfterMapLoaded(void)
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
static TArray< FBoundingBox > GetBoundingBoxOfActors(const TArray< AActor * > &Actors, uint8 InTagQueried=0xFF)
AWeather * Weather
void RegisterActorFactory(ACarlaActorFactory &ActorFactory)
carla::geom::GeoLocation MapGeoReference
const FEpisodeSettings & GetSettings() const
void SetRecorder(ACarlaRecorder *Rec)
void InitializeAtBeginPlay()
void NotifyBeginEpisode(UCarlaEpisode &Episode)
int32 GetCurrentMapLayer() const
void ApplyQualityLevelPreRestart()
Before loading a level, apply the current settings.
void ApplyQualityLevelPostRestart()
After loading a level, apply the current settings.
void Reset()
Reset settings to default.
void SetAllActorsDrawDistance(UWorld *world, float max_draw_distance) const
void RegisterSpawnHandler(UWorld *World)
Create the event trigger handler for all the newly spawned actors to be processed with a custom funct...
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
void RegisterObjects(TArray< AActor * > Actors)
static FString GetXODR(const UWorld *World)
Return the OpenDrive XML associated to MapName, or empty if the file is not found.
void SetSemanticSegmentationEnabled(bool Enable=true)
void RegisterSpawnHandler(UWorld *World)
static std::vector< int > GenerateRange(int a, int b)
Definition Math.cpp:151
Vector3D GetUpVector() const
Definition Rotation.h:60
static boost::optional< road::Map > Load(const std::string &opendrive)
T & At(uint32_t x, uint32_t y)
Definition Texture.h:43
uint32_t GetWidth() const
Definition Texture.h:29
uint32_t GetHeight() const
Definition Texture.h:33
uint16_t MapLayerType
Definition MapLayer.h:16