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)//构造函数,它接收一个FObjectInitializer对象作为参数,并将其传递给父类的构造函数。这是Unreal Engine中常见的初始化模式。
41 : Super(ObjectInitializer)
42{
43 PrimaryActorTick.bCanEverTick = true;//设置主Actor(Primary Actor)可以被tick(即定期更新)
44 PrimaryActorTick.TickGroup = TG_PrePhysics;//设置主Actor的tick组为TG_PrePhysics,意味着这个Actor会在物理计算之前被更新。
45 bAllowTickBeforeBeginPlay = false;//禁止在游戏正式开始之前(BeginPlay方法调用之前)对Actor进行tick。
46
47 Episode = CreateDefaultSubobject<UCarlaEpisode>(TEXT("Episode"));//创建一个UCarlaEpisode类型的默认子对象,用于管理模拟的某一集(Episode)
48
49 Recorder = CreateDefaultSubobject<ACarlaRecorder>(TEXT("Recorder"));//创建一个ACarlaRecorder类型的默认子对象,用于记录模拟过程中的数据。
50
51 ObjectRegister = CreateDefaultSubobject<UObjectRegister>(TEXT("ObjectRegister"));//创建一个UObjectRegister类型的默认子对象,用于注册和管理模拟中的对象
52
53 // HUD
54 HUDClass = ACarlaHUD::StaticClass();
55
56 TaggerDelegate = CreateDefaultSubobject<UTaggerDelegate>(TEXT("TaggerDelegate"));
57 CarlaSettingsDelegate = CreateDefaultSubobject<UCarlaSettingsDelegate>(TEXT("CarlaSettingsDelegate"));
58}
59
60const FString ACarlaGameModeBase::GetRelativeMapPath() const//一个常量方法,返回一个FString类型的值,表示当前地图的相对路径
61{
62 UWorld* World = GetWorld();//获取当前游戏世界(World)的指针
63 TSoftObjectPtr<UWorld> AssetPtr (World);//创建一个指向当前世界的软指针(Soft Pointer),用于安全地引用资源
64 FString Path = FPaths::GetPath(AssetPtr.GetLongPackageName());//通过软指针获取世界的完整包名,并从中提取路径
65 Path.RemoveFromStart("/Game/");//从路径中移除前缀"/Game/",以获取相对于游戏目录的路径
66 return Path;
67}
68//首先调用GetRelativeMapPath来获取地图的相对路径
69//然后,使用FPaths::ConvertRelativePathToFull函数将项目的内容目录(FPaths::ProjectContentDir())转换为绝对路径
70//最后,将这个绝对路径与相对地图路径拼接起来,形成完整的地图路径,并返回这个路径
72{
73 FString Path = GetRelativeMapPath();
74 return FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()) + Path;
75}
76
78 const FString &MapName,
79 const FString &Options,
80 FString &ErrorMessage)
81{
82 TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaGameModeBase::InitGame);
83 Super::InitGame(MapName, Options, ErrorMessage);//面向对象编程中常见的做法,用于确保父类中定义的初始化逻辑得到执行
84
85 UWorld* World = GetWorld();
86 check(World != nullptr);//用于验证 World 指针是否不为空
87 FString InMapName(MapName);
88
89 checkf(
90 Episode != nullptr,
91 TEXT("Missing episode, can't continue without an episode!"));//检查 Episode 指针是否不为空。如果 Episode 是空的,则程序将崩溃,并显示错误消息
92
93 AActor* LMManagerActor =
94 UGameplayStatics::GetActorOfClass(GetWorld(), ALargeMapManager::StaticClass());
95 LMManager = Cast<ALargeMapManager>(LMManagerActor);//验证 Episode 对象是否存在,尝试获取游戏世界中的 ALargeMapManager Actor,并将其存储在成员变量中以供后续使用
96 if (LMManager) {
97 if (LMManager->GetNumTiles() == 0)
98 {
100 }
101 InMapName = LMManager->LargeMapName;
102 }
103
104#if WITH_EDITOR
105 {
106 //在编辑器中播放时,地图名称会得到一个额外的前缀,这里我们
107 //删除它。
108 FString CorrectedMapName = InMapName;
109 constexpr auto PIEPrefix = TEXT("UEDPIE_0_");
110 CorrectedMapName.RemoveFromStart(PIEPrefix);
111 UE_LOG(LogCarla, Log, TEXT("Corrected map name from %s to %s"), *InMapName, *CorrectedMapName);
112 Episode->MapName = CorrectedMapName;
113 }
114#else
115 Episode->MapName = InMapName;
116#endif // WITH_EDITOR
117
118 GameInstance = Cast<UCarlaGameInstance>(GetGameInstance());
119 checkf(
120 GameInstance != nullptr,
121 TEXT("GameInstance is not a UCarlaGameInstance, did you forget to set "
122 "it in the project settings?"));
123
124 if (TaggerDelegate != nullptr) {
126 } else {
127 UE_LOG(LogCarla, Error, TEXT("Missing TaggerDelegate!"));
128 }
129
130 if(CarlaSettingsDelegate != nullptr) {
133 } else {
134 UE_LOG(LogCarla, Error, TEXT("Missing CarlaSettingsDelegate!"));
135 }
136
137 AActor* WeatherActor =
138 UGameplayStatics::GetActorOfClass(GetWorld(), AWeather::StaticClass());
139 if (WeatherActor != nullptr) {
140 UE_LOG(LogCarla, Log, TEXT("Existing weather actor. Doing nothing then!"));
141 Episode->Weather = static_cast<AWeather*>(WeatherActor);
142 }
143 else if (WeatherClass != nullptr) {
144 Episode->Weather = World->SpawnActor<AWeather>(WeatherClass);
145 } else {
146 UE_LOG(LogCarla, Error, TEXT("Missing weather class!"));
147 }
148
150
152 this,
154
156
157 //在 Episode 和 Recorder 之间建立连接
159 Episode->SetRecorder(Recorder);
160
162
163 if(Map.has_value())
164 {
166 }
167}
168
170{
171 if (CarlaSettingsDelegate != nullptr)
172 {
174 }
175
176 Super::RestartPlayer(NewPlayer);
177}
178
180{
181 Super::BeginPlay();
182
183 UWorld* World = GetWorld();
184 check(World != nullptr);
185
188
189 if (true) { /// @todo 如果启用了语义分割。
192 }
193
194 // HACK: 修复透明度透视问题
195 // 问题:透过墙壁可以看到透明物体。
196 // 这是由于 SkyAtmosphere 组件
197 // 定向光源 (太阳) 的阴影
198 //并将 Custom depth 设置为 3,用于语义分割
199 // 解决方案:生成一个贴花。
200 // It just works!
201 World->SpawnActor<ADecalActor>(
202 FVector(0,0,-1000000), FRotator(0,0,0), FActorSpawnParameters());
203
205 Manager->InitializeTrafficLights();
206
207 Episode->InitializeAtBeginPlay();
209
210 if (Episode->Weather != nullptr)
211 {
212 Episode->Weather->ApplyWeather(carla::rpc::WeatherParameters::Default);
213 }
214
215 /// @todoRecorder 不应该在这里打勾,FCarlaEngine 应该这样做。
216 // 检查 Replayer 是否正在等待自动启动
217 if (Recorder)
218 {
220 }
221
223 {
225 }
226
227 if (LMManager) {
229 LMManager->ConsiderSpectatorAsEgo(Episode->GetSettings().SpectatorAsEgo);
230 }
231
232 // 手动运行 begin play on lights(开始在灯光上播放),因为它可能不会在子关卡上运行
233 TArray<AActor*> FoundActors;
234 UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);
235 for(AActor* Actor : FoundActors)
236 {
237 TArray<UCarlaLight*> Lights;
238 Actor->GetComponents(Lights, false);
239 for(UCarlaLight* Light : Lights)
240 {
241 Light->RegisterLight();
242 }
243 }
245}
246
248{
249 TArray<FString> Names;
250 TArray<AActor*> Actors;
251 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), Actors);
252 for (AActor* Actor : Actors)
253 {
254 TArray<UStaticMeshComponent*> StaticMeshes;
255 Actor->GetComponents(StaticMeshes);
256 if (StaticMeshes.Num())
257 {
258 Names.Add(Actor->GetName());
259 }
260 }
261 return Names;
262}
263
265{
266 TArray<AActor*> Actors;
267 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), Actors);
268 for (AActor* Actor : Actors)
269 {
270 if(Actor->GetName() == ActorName)
271 {
272 return Actor;
273 break;
274 }
275 }
276 return nullptr;
277}
278
280{
281 FlushRenderingCommands();
282 TArray<FColor> Colors;
283 for (uint32_t y = 0; y < Texture.GetHeight(); y++)
284 {
285 for (uint32_t x = 0; x < Texture.GetWidth(); x++)
286 {
287 auto& Color = Texture.At(x,y);
288 Colors.Add(FColor(Color.r, Color.g, Color.b, Color.a));
289 }
290 }
291 UTexture2D* UETexture = UTexture2D::CreateTransient(Texture.GetWidth(), Texture.GetHeight(), EPixelFormat::PF_B8G8R8A8);
292 FTexture2DMipMap& Mip = UETexture->PlatformData->Mips[0];
293 void* Data = Mip.BulkData.Lock( LOCK_READ_WRITE );
294 FMemory::Memcpy( Data,
295 &Colors[0],
296 Texture.GetWidth()*Texture.GetHeight()*sizeof(FColor));
297 Mip.BulkData.Unlock();
298 UETexture->UpdateResource();
299 return UETexture;
300}
301
303{
304 FlushRenderingCommands();
305 TArray<FFloat16Color> Colors;
306 for (uint32_t y = 0; y < Texture.GetHeight(); y++)
307 {
308 for (uint32_t x = 0; x < Texture.GetWidth(); x++)
309 {
310 auto& Color = Texture.At(x,y);
311 Colors.Add(FLinearColor(Color.r, Color.g, Color.b, Color.a));
312 }
313 }
314 UTexture2D* UETexture = UTexture2D::CreateTransient(Texture.GetWidth(), Texture.GetHeight(), EPixelFormat::PF_FloatRGBA);
315 FTexture2DMipMap& Mip = UETexture->PlatformData->Mips[0];
316 void* Data = Mip.BulkData.Lock( LOCK_READ_WRITE );
317 FMemory::Memcpy( Data,
318 &Colors[0],
319 Texture.GetWidth()*Texture.GetHeight()*sizeof(FFloat16Color));
320 Mip.BulkData.Unlock();
321 UETexture->UpdateResource();
322 return UETexture;
323}
324
326 AActor* Actor,
327 UTexture2D* Texture,
328 const carla::rpc::MaterialParameter& TextureParam)
329{
330 namespace cr = carla::rpc;
331 TArray<UStaticMeshComponent*> StaticMeshes;
332 Actor->GetComponents(StaticMeshes);
333 for (UStaticMeshComponent* Mesh : StaticMeshes)
334 {
335 for (int i = 0; i < Mesh->GetNumMaterials(); ++i)
336 {
337 UMaterialInterface* OriginalMaterial = Mesh->GetMaterial(i);
338 UMaterialInstanceDynamic* DynamicMaterial = Cast<UMaterialInstanceDynamic>(OriginalMaterial);
339 if(!DynamicMaterial)
340 {
341 DynamicMaterial = UMaterialInstanceDynamic::Create(OriginalMaterial, NULL);
342 Mesh->SetMaterial(i, DynamicMaterial);
343 }
344
345 switch(TextureParam)
346 {
347 case cr::MaterialParameter::Tex_Diffuse:
348 DynamicMaterial->SetTextureParameterValue("BaseColor", Texture);
349 DynamicMaterial->SetTextureParameterValue("Difuse", Texture);
350 DynamicMaterial->SetTextureParameterValue("Difuse 2", Texture);
351 DynamicMaterial->SetTextureParameterValue("Difuse 3", Texture);
352 DynamicMaterial->SetTextureParameterValue("Difuse 4", Texture);
353 break;
354 case cr::MaterialParameter::Tex_Normal:
355 DynamicMaterial->SetTextureParameterValue("Normal", Texture);
356 DynamicMaterial->SetTextureParameterValue("Normal 2", Texture);
357 DynamicMaterial->SetTextureParameterValue("Normal 3", Texture);
358 DynamicMaterial->SetTextureParameterValue("Normal 4", Texture);
359 break;
360 case cr::MaterialParameter::Tex_Emissive:
361 DynamicMaterial->SetTextureParameterValue("Emissive", Texture);
362 break;
363 case cr::MaterialParameter::Tex_Ao_Roughness_Metallic_Emissive:
364 DynamicMaterial->SetTextureParameterValue("AO / Roughness / Metallic / Emissive", Texture);
365 DynamicMaterial->SetTextureParameterValue("ORMH", Texture);
366 DynamicMaterial->SetTextureParameterValue("ORMH 2", Texture);
367 DynamicMaterial->SetTextureParameterValue("ORMH 3", Texture);
368 DynamicMaterial->SetTextureParameterValue("ORMH 4", Texture);
369 break;
370 }
371 }
372 }
373}
374
375void ACarlaGameModeBase::Tick(float DeltaSeconds)
376{
377 Super::Tick(DeltaSeconds);
378
379 /// @todo Recorder 不应该在这里打勾,FCarlaEngine 应该这样做。
380 if (Recorder)
381 {
382 Recorder->Tick(DeltaSeconds);
383 }
384}
385
386void ACarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
387{
389
390 Episode->EndPlay();
392
393 Super::EndPlay(EndPlayReason);
394
395 if ((CarlaSettingsDelegate != nullptr) && (EndPlayReason != EEndPlayReason::EndPlayInEditor))
396 {
398 }
399}
400
402{
403 auto *World = GetWorld();
404 check(World != nullptr);
405
406 for (auto &FactoryClass : ActorFactories)
407 {
408 if (FactoryClass != nullptr)
409 {
410 auto *Factory = World->SpawnActor<ACarlaActorFactory>(FactoryClass);
411 if (Factory != nullptr)
412 {
413 Episode->RegisterActorFactory(*Factory);
414 ActorFactoryInstances.Add(Factory);
415 }
416 else
417 {
418 UE_LOG(LogCarla, Error, TEXT("Failed to spawn actor spawner"));
419 }
420 }
421 }
422}
423
425{
426 for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It)
427 {
428 SpawnPointsTransforms.Add(It->GetActorTransform());
429 }
430
431 if(SpawnPointsTransforms.Num() == 0)
432 {
434 }
435
436 UE_LOG(LogCarla, Log, TEXT("There are %d SpawnPoints in the map"), SpawnPointsTransforms.Num());
437}
438
440{
441 // 记录日志,表明正在生成出生点
442 UE_LOG(LogCarla, Log, TEXT("Generating SpawnPoints ..."));
443 // 从地图对象中获取拓扑结构,拓扑结构由一系列的路径点对(Waypoint pairs)组成
444 std::vector<std::pair<carla::road::element::Waypoint, carla::road::element::Waypoint>> Topology = Map->GenerateTopology();
445 // 获取当前的游戏世界对象
446 UWorld* World = GetWorld();
447 // 遍历拓扑结构中的每一对路径点
448 for(auto& Pair : Topology)
449 {
450 carla::geom::Transform CarlaTransform = Map->ComputeTransform(Pair.first);
451 FTransform Transform(CarlaTransform);
452 // 将Transform的平移部分增加50个单位的Z轴偏移量
453 // 为了将出生点放置在道路的上方一定高度,以避免与地面或其他物体碰撞
454 Transform.AddToTranslation(FVector(0.f, 0.f, 50.0f));
455 SpawnPointsTransforms.Add(Transform);
456 }
457}
458
460{
461 std::string opendrive_xml = carla::rpc::FromLongFString(UOpenDrive::GetXODR(GetWorld()));
462// 使用carla::opendrive::OpenDriveParser的Load方法来解析OpenDrive XML字符串
463// 并尝试创建一个地图对象
464 // 如果解析失败,则std::optional将不包含值
466 // 检查Map是否包含值,即检查OpenDrive XML是否成功解析
467 if (!Map.has_value()) {
468 UE_LOG(LogCarla, Error, TEXT("Invalid Map"));
469 }
470 else
471 {
472 Episode->MapGeoReference = Map->GetGeoReference();
473 }
474}
475
477{
479 {
480 UWorld* World = GetWorld();
481 AActor* TrafficLightManagerActor = UGameplayStatics::GetActorOfClass(World, ATrafficLightManager::StaticClass());
482 if(TrafficLightManagerActor == nullptr)
483 {
484 FActorSpawnParameters SpawnParams;
485 SpawnParams.OverrideLevel = GetULevelFromName("TrafficLights");
486 TrafficLightManager = World->SpawnActor<ATrafficLightManager>(SpawnParams);
487 }
488 else
489 {
490 TrafficLightManager = Cast<ATrafficLightManager>(TrafficLightManagerActor);
491 }
492 }
493 return TrafficLightManager;
494}
495
497{
498 // 创建一个AActor指针的数组,用于存储游戏世界中的所有AStaticMeshActor对象
499 TArray<AActor*> WorldActors;
500 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AStaticMeshActor::StaticClass(), WorldActors);
501
502 for (AActor *Actor : WorldActors)
503 {
504 AStaticMeshActor *MeshActor = CastChecked<AStaticMeshActor>(Actor);
505// 获取MeshActor的静态网格体组件
506// 然后检查该组件是否有关联的静态网格体资源
507 if (MeshActor->GetStaticMeshComponent()->GetStaticMesh() == NULL)
508 {
509 UE_LOG(LogTemp, Error, TEXT("The object : %s has no mesh"), *MeshActor->GetFullName());
510 }
511 }
512}
513
514//正在遍历游戏世界中的所有AStaticMeshActor对象,并检查它们的静态网格体组件是否有一个有效的静态网格体资源以及一个特定的标签
515//如果静态网格体组件没有被标记为道路、人行道、道路线、地面或地形,并且当前没有生成重叠事件,则启用这些事件
517{
518 TArray<AActor*> WorldActors;
519 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AStaticMeshActor::StaticClass(), WorldActors);
520
521 for(AActor *Actor : WorldActors)
522 {
523 AStaticMeshActor *MeshActor = CastChecked<AStaticMeshActor>(Actor);
524 if(MeshActor->GetStaticMeshComponent()->GetStaticMesh() != NULL)
525 {
526 auto MeshTag = ATagger::GetTagOfTaggedComponent(*MeshActor->GetStaticMeshComponent());
527 namespace crp = carla::rpc;
528 if (MeshTag != crp::CityObjectLabel::Roads &&
529 MeshTag != crp::CityObjectLabel::Sidewalks &&
530 MeshTag != crp::CityObjectLabel::RoadLines &&
531 MeshTag != crp::CityObjectLabel::Ground &&
532 MeshTag != crp::CityObjectLabel::Terrain &&
533 MeshActor->GetStaticMeshComponent()->GetGenerateOverlapEvents() == false)
534 {
535 MeshActor->GetStaticMeshComponent()->SetGenerateOverlapEvents(true);
536 }
537 }
538 }
539}
540
542{
543
544 auto World = GetWorld();
545 check(World != nullptr);
546
547 if(!Map)
548 {
549 return;
550 }
551
552 if(!enable)
553 {
554 UKismetSystemLibrary::FlushDebugStrings(World);
555 UKismetSystemLibrary::FlushPersistentDebugLines(World);
556 return;
557 }
558
559 //const std::unordered_map<carla::road::SignId, std::unique_ptr<carla::road::Signal>>
560 const auto& Signals = Map->GetSignals();
561 const auto& Controllers = Map->GetControllers();
562
563 for(const auto& Signal : Signals) {
564 const auto& ODSignal = Signal.second;
565 const FTransform Transform = ODSignal->GetTransform();
566 const FVector Location = Transform.GetLocation();
567 const FQuat Rotation = Transform.GetRotation();
568 const FVector Up = Rotation.GetUpVector();
569 DrawDebugSphere(
570 World,
571 Location,
572 50.0f,
573 10,
574 FColor(0, 255, 0),
575 true
576 );
577 }
578
579 TArray<const cre::RoadInfoSignal*> References;
580 auto waypoints = Map->GenerateWaypointsOnRoadEntries();
581 std::unordered_set<cr::RoadId> ExploredRoads;
582 for (auto & waypoint : waypoints)
583 {
584 // 检查我们是否已经探索过这条路
585 if (ExploredRoads.count(waypoint.road_id) > 0)
586 {
587 continue;
588 }
589 ExploredRoads.insert(waypoint.road_id);
590
591 //同一条道路多次(性能影响,而不是行为)
592 auto SignalReferences = Map->GetLane(waypoint).
593 GetRoad()->GetInfos<cre::RoadInfoSignal>();
594 for (auto *SignalReference : SignalReferences)
595 {
596 References.Add(SignalReference);
597 }
598 }
599 for (auto& Reference : References)
600 {
601 auto RoadId = Reference->GetRoadId();
602 const auto* SignalReference = Reference;
603 const FTransform SignalTransform = SignalReference->GetSignal()->GetTransform();
604 for(auto &validity : SignalReference->GetValidities())
605 {
606 for(auto lane : carla::geom::Math::GenerateRange(validity._from_lane, validity._to_lane))
607 {
608 if(lane == 0)
609 continue;
610
611 auto signal_waypoint = Map->GetWaypoint(
612 RoadId, lane, SignalReference->GetS()).get();
613
614 if(Map->GetLane(signal_waypoint).GetType() != cr::Lane::LaneType::Driving)
615 continue;
616
617 FTransform ReferenceTransform = Map->ComputeTransform(signal_waypoint);
618
619 DrawDebugSphere(
620 World,
621 ReferenceTransform.GetLocation(),
622 50.0f,
623 10,
624 FColor(0, 0, 255),
625 true
626 );
627
628 DrawDebugLine(
629 World,
630 ReferenceTransform.GetLocation(),
631 SignalTransform.GetLocation(),
632 FColor(0, 0, 255),
633 true
634 );
635 }
636 }
637 }
638
639}
640
641TArray<FBoundingBox> ACarlaGameModeBase::GetAllBBsOfLevel(uint8 TagQueried) const
642{
643 UWorld* World = GetWorld();
644
645 // 获取该级别的所有 Actor
646 TArray<AActor*> FoundActors;
647 UGameplayStatics::GetAllActorsOfClass(World, AActor::StaticClass(), FoundActors);
648
649 TArray<FBoundingBox> BoundingBoxes;
650 BoundingBoxes = UBoundingBoxCalculator::GetBoundingBoxOfActors(FoundActors, TagQueried);
651
652 return BoundingBoxes;
653}
654
656{
657 //获取该级别的所有 Actor
658 TArray<AActor*> FoundActors;
659 UGameplayStatics::GetAllActorsOfClass(GetWorld(), AActor::StaticClass(), FoundActors);
660 ObjectRegister->RegisterObjects(FoundActors);
661}
662
664 const TSet<uint64>& EnvObjectIds,
665 bool Enable)
666{
667 ObjectRegister->EnableEnvironmentObjects(EnvObjectIds, Enable);
668}
669
671{
672 const UWorld* World = GetWorld();
673 UGameplayStatics::FlushLevelStreaming(World);
674
675 TArray<FName> LevelsToLoad;
676 ConvertMapLayerMaskToMapNames(MapLayers, LevelsToLoad);
677
678 FLatentActionInfo LatentInfo;
679 LatentInfo.CallbackTarget = this;
680 LatentInfo.ExecutionFunction = "OnLoadStreamLevel";
681 LatentInfo.Linkage = 0;
682 LatentInfo.UUID = LatentInfoUUID;
683
684 PendingLevelsToLoad = LevelsToLoad.Num();
685
686 for(FName& LevelName : LevelsToLoad)
687 {
689 UGameplayStatics::LoadStreamLevel(World, LevelName, true, true, LatentInfo);
690 LatentInfo.UUID = LatentInfoUUID;
691 UGameplayStatics::FlushLevelStreaming(World);
692 }
693}
694
696{
697 const UWorld* World = GetWorld();
698
699 TArray<FName> LevelsToUnLoad;
700 ConvertMapLayerMaskToMapNames(MapLayers, LevelsToUnLoad);
701
702 FLatentActionInfo LatentInfo;
703 LatentInfo.CallbackTarget = this;
704 LatentInfo.ExecutionFunction = "OnUnloadStreamLevel";
705 LatentInfo.UUID = LatentInfoUUID;
706 LatentInfo.Linkage = 0;
707
708 PendingLevelsToUnLoad = LevelsToUnLoad.Num();
709
710 for(FName& LevelName : LevelsToUnLoad)
711 {
713 UGameplayStatics::UnloadStreamLevel(World, LevelName, LatentInfo, false);
714 LatentInfo.UUID = LatentInfoUUID;
715 UGameplayStatics::FlushLevelStreaming(World);
716 }
717
718}
719
720void ACarlaGameModeBase::ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray<FName>& OutLevelNames)
721{
722 UWorld* World = GetWorld();
723 const TArray <ULevelStreaming*> Levels = World->GetStreamingLevels();
724 TArray<FString> LayersToLoad;
725
726 // 获取所有请求的图层
727 int32 LayerMask = 1;
728 int32 AllLayersMask = static_cast<crp::MapLayerType>(crp::MapLayer::All);
729
730 while(LayerMask > 0)
731 {
732 //将枚举转换为 FString
733 FString LayerName = UTF8_TO_TCHAR(MapLayerToString(static_cast<crp::MapLayer>(LayerMask)).c_str());
734 bool included = static_cast<crp::MapLayerType>(MapLayer) & LayerMask;
735 if(included)
736 {
737 LayersToLoad.Emplace(LayerName);
738 }
739 LayerMask = (LayerMask << 1) & AllLayersMask;
740 }
741
742 // 获取所有请求的关卡地图
743 for(ULevelStreaming* Level : Levels)
744 {
745 TArray<FString> StringArray;
746 FString FullSubMapName = Level->GetWorldAssetPackageFName().ToString();
747 // 丢弃完整路径,我们只需要 umap 名称
748 FullSubMapName.ParseIntoArray(StringArray, TEXT("/"), false);
749 FString SubMapName = StringArray[StringArray.Num() - 1];
750 for(FString LayerName : LayersToLoad)
751 {
752 if(SubMapName.Contains(LayerName))
753 {
754 OutLevelNames.Emplace(FName(*SubMapName));
755 break;
756 }
757 }
758 }
759
760}
761
763{
764 ULevel* OutLevel = nullptr;
765 UWorld* World = GetWorld();
766 const TArray <ULevelStreaming*> Levels = World->GetStreamingLevels();
767
768 for(ULevelStreaming* Level : Levels)
769 {
770 FString FullSubMapName = Level->GetWorldAssetPackageFName().ToString();
771 if(FullSubMapName.Contains(LevelName))
772 {
773 OutLevel = Level->GetLoadedLevel();
774 if(!OutLevel)
775 {
776 UE_LOG(LogCarla, Warning, TEXT("%s has not been loaded"), *LevelName);
777 }
778 break;
779 }
780 }
781
782 return OutLevel;
783}
784
786{
788
789 // 注册新 actor 并标记他们
791 {
793 ATagger::TagActorsInLevel(*GetWorld(), true);
794 }
795}
796
798{
800 // 更新已存储的已注册对象(丢弃已删除的对象)
802 {
804 }
805}
806
UE_LOG(LogCarla, Log, TEXT("UActorDispatcher::Destroying actor: '%s' %x"), *Id, Actor)
TMap< IdType, AActor * > Actors
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld * World
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld Actor
TSubclassOf< AWeather > WeatherClass
要生成的 Weather 类。
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
int32 LatentInfoUUID
在同一个即时报价中
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
将用于定义和生成 actor 的 actor 生成器列表 在游戏中可用。
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)
检索已标记组件的标记。
Definition Tagger.h:52
static void TagActorsInLevel(UWorld &World, bool bTagForSemanticSegmentation)
设置 level 中每个 actor 的标签。
Definition Tagger.cpp:229
负责创建和分配交通灯组、控制器和组件的类。
FWeatherParameters Weather
Definition Weather.h:69
void CheckPlayAfterMapLoaded(void)
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
地图类的前向声明,用于在LaneInvasionSensor类中可能的引用。
static TArray< FBoundingBox > GetBoundingBoxOfActors(const TArray< AActor * > &Actors, uint8 InTagQueried=0xFF)
void NotifyBeginEpisode(UCarlaEpisode &Episode)
int32 GetCurrentMapLayer() const
void ApplyQualityLevelPreRestart()
加载关卡之前,应用当前设置
void ApplyQualityLevelPostRestart()
加载关卡后,应用当前设置
void Reset()
将设置重置为默认值
void SetAllActorsDrawDistance(UWorld *world, float max_draw_distance) const
void RegisterSpawnHandler(UWorld *World)
在此处为所有新生成的参与者创建事件触发器处理程序,以便使用自定义函数进行处理。
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
void RegisterObjects(TArray< AActor * > Actors)
static FString GetXODR(const UWorld *World)
MapNameOpenDrive XMLҲļ򷵻ؿա
void SetSemanticSegmentationEnabled(bool Enable=true)
void RegisterSpawnHandler(UWorld *World)
static std::vector< int > GenerateRange(int a, int b)
Definition Math.cpp:191
Vector3D GetUpVector() const
Definition Rotation.h:74
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
Carlaе·عܵռ
uint16_t MapLayerType
Definition MapLayer.h:17