24#include "Engine/StaticMeshActor.h"
25#include "EngineUtils.h"
26#include "GameFramework/SpectatorPawn.h"
27#include "GenericPlatform/GenericPlatformProcess.h"
28#include "Kismet/GameplayStatics.h"
29#include "Materials/MaterialParameterCollection.h"
30#include "Materials/MaterialParameterCollectionInstance.h"
31#include "Misc/FileHelper.h"
32#include "Misc/Paths.h"
40 case TSS::TrafficLightRed:
41 case TSS::TrafficLightYellow:
42 case TSS::TrafficLightGreen:
43 return TEXT(
"traffic.traffic_light");
44 case TSS::SpeedLimit_30:
45 return TEXT(
"traffic.speed_limit.30");
46 case TSS::SpeedLimit_40:
47 return TEXT(
"traffic.speed_limit.40");
48 case TSS::SpeedLimit_50:
49 return TEXT(
"traffic.speed_limit.50");
50 case TSS::SpeedLimit_60:
51 return TEXT(
"traffic.speed_limit.60");
52 case TSS::SpeedLimit_90:
53 return TEXT(
"traffic.speed_limit.90");
54 case TSS::SpeedLimit_100:
55 return TEXT(
"traffic.speed_limit.100");
56 case TSS::SpeedLimit_120:
57 return TEXT(
"traffic.speed_limit.120");
58 case TSS::SpeedLimit_130:
59 return TEXT(
"traffic.speed_limit.130");
61 return TEXT(
"traffic.stop");
63 return TEXT(
"traffic.yield");
65 return TEXT(
"traffic.unknown");
70UCarlaEpisode::UCarlaEpisode(
const FObjectInitializer &ObjectInitializer)
71 : Super(ObjectInitializer),
74 ActorDispatcher = CreateDefaultSubobject<UActorDispatcher>(TEXT(
"ActorDispatcher"));
75 FrameData.SetEpisode(
this);
78bool UCarlaEpisode::LoadNewEpisode(
const FString &MapString,
bool ResetSettings)
80 bool bIsFileFound =
false;
82 FString FinalPath = MapString.IsEmpty() ? GetMapName() : MapString;
83 FinalPath += !MapString.EndsWith(
".umap") ?
".umap" :
"";
85 if (MapString.StartsWith(
"/Game"))
88 FinalPath.RemoveFromStart(TEXT(
"/Game/"));
89 FinalPath = FPaths::ProjectContentDir() + FinalPath;
90 FinalPath = IFileManager::Get().ConvertToAbsolutePathForExternalAppForRead(*FinalPath);
92 if (FPaths::FileExists(FinalPath)) {
94 FinalPath = MapString;
99 if (MapString.Contains(
"/"))
return false;
102 TArray<FString> TempStrArray, PathList;
103 IFileManager::Get().FindFilesRecursive(PathList, *FPaths::ProjectContentDir(), *FinalPath,
true,
false,
false);
104 if (PathList.Num() > 0)
106 FinalPath = PathList[0];
107 FinalPath.ParseIntoArray(TempStrArray, TEXT(
"Content/"),
true);
108 FinalPath = TempStrArray[1];
109 FinalPath.ParseIntoArray(TempStrArray, TEXT(
"."),
true);
110 FinalPath =
"/Game/" + TempStrArray[0];
112 return LoadNewEpisode(FinalPath, ResetSettings);
118 UE_LOG(LogCarla, Warning, TEXT(
"Loading a new episode: %s"), *FinalPath);
119 UGameplayStatics::OpenLevel(GetWorld(), *FinalPath,
true);
124 if (bIsPrimaryServer)
131 if (SecondaryServer->HasClientsConnected())
133 SecondaryServer->GetCommander().SendLoadMap(std::string(TCHAR_TO_UTF8(*FinalPath)));
145 const FString RecastToolName =
"RecastBuilder.exe";
147 const FString RecastToolName =
"RecastBuilder";
152 const FString AbsoluteRecastBuilderPath = FPaths::ConvertRelativePathToFull(
153 FPaths::RootDir() +
"Tools/" + RecastToolName);
155 const FString AbsoluteRecastBuilderPath = FPaths::ConvertRelativePathToFull(
156 FPaths::ProjectDir() +
"../../Util/DockerUtils/dist/" + RecastToolName);
158 return AbsoluteRecastBuilderPath;
161bool UCarlaEpisode::LoadNewOpendriveEpisode(
162 const FString &OpenDriveString,
165 if (OpenDriveString.IsEmpty())
167 UE_LOG(LogCarla, Error, TEXT(
"The OpenDrive string is empty."));
173 carla::rpc::FromLongFString(OpenDriveString));
176 if (!CarlaMap.has_value())
178 UE_LOG(LogCarla, Error, TEXT(
"The OpenDrive string is invalid or not supported"));
184 const auto CrosswalksMesh = CarlaMap->GetAllCrosswalkMesh();
185 const auto RecastOBJ = (RoadMesh + CrosswalksMesh).GenerateOBJForRecast();
187 const FString AbsoluteOBJPath = FPaths::ConvertRelativePathToFull(
188 FPaths::ProjectContentDir() +
"Carla/Maps/Nav/OpenDriveMap.obj");
191 FFileHelper::SaveStringToFile(
192 carla::rpc::ToLongFString(RecastOBJ),
194 FFileHelper::EEncodingOptions::ForceUTF8,
195 &IFileManager::Get());
197 const FString AbsoluteXODRPath = FPaths::ConvertRelativePathToFull(
198 FPaths::ProjectContentDir() +
"Carla/Maps/OpenDrive/OpenDriveMap.xodr");
201 FFileHelper::SaveStringToFile(
204 FFileHelper::EEncodingOptions::ForceUTF8,
205 &IFileManager::Get());
207 if (!FPaths::FileExists(AbsoluteXODRPath))
209 UE_LOG(LogCarla, Error, TEXT(
"ERROR: XODR not copied!"));
225 if (FPaths::FileExists(AbsoluteRecastBuilderPath) &&
230 FPlatformProcess::CreateProc(
231 *AbsoluteRecastBuilderPath, *AbsoluteOBJPath,
232 true,
true,
true,
nullptr, 0,
nullptr,
nullptr);
236 UE_LOG(LogCarla, Warning, TEXT(
"'RecastBuilder' not present under '%s', "
237 "the binaries for pedestrian navigation will not be created."),
238 *AbsoluteRecastBuilderPath);
246 EpisodeSettings = Settings;
247 if(EpisodeSettings.ActorActiveDistance > EpisodeSettings.TileStreamingDistance)
249 UE_LOG(LogCarla, Warning, TEXT(
"Setting ActorActiveDistance is smaller that TileStreamingDistance, TileStreamingDistance will be increased"));
250 EpisodeSettings.TileStreamingDistance = EpisodeSettings.ActorActiveDistance;
255TArray<FTransform> UCarlaEpisode::GetRecommendedSpawnPoints()
const
271 Actor.parent_id = ParentId;
276 UE_LOG(LogCarla, Warning, TEXT(
"Trying to serialize invalid actor"));
286 return SerializeActor(CarlaActor);
291 SerializedActor.
id = 0u;
293 TSet<crp::CityObjectLabel> SemanticTags;
299 for (
auto &&Tag : SemanticTags)
301 using tag_t =
decltype(SerializedActor.
semantic_tags)::value_type;
302 SerializedActor.
semantic_tags.emplace_back(
static_cast<tag_t
>(Tag));
304 return SerializedActor;
308void UCarlaEpisode::AttachActors(
312 const FString& SocketName)
314 Child->AddActorWorldOffset(FVector(CurrentMapOrigin));
318 if (bIsPrimaryServer)
320 GetFrameData().AddEvent(
326 if (Recorder->IsEnabled())
333 Recorder->AddEvent(std::move(RecEvent));
337void UCarlaEpisode::InitializeAtBeginPlay()
339 auto World = GetWorld();
340 check(
World !=
nullptr);
341 auto PlayerController = UGameplayStatics::GetPlayerController(
World, 0);
342 if (PlayerController ==
nullptr)
344 UE_LOG(LogCarla, Error, TEXT(
"Can't find player controller!"));
347 Spectator = PlayerController->GetPawn();
348 if (Spectator !=
nullptr)
351 Description.
Id = TEXT(
"spectator");
352 Description.
Class = Spectator->GetClass();
353 ActorDispatcher->RegisterActor(*Spectator, Description);
357 UE_LOG(LogCarla, Error, TEXT(
"Can't find spectator!"));
361 UMaterialParameterCollection *Collection = LoadObject<UMaterialParameterCollection>(
nullptr, TEXT(
"/Game/Carla/Blueprints/Game/CarlaParameters.CarlaParameters"),
nullptr, LOAD_None,
nullptr);
362 if (Collection !=
nullptr)
364 MaterialParameters =
World->GetParameterCollectionInstance(Collection);
365 if (MaterialParameters ==
nullptr)
367 UE_LOG(LogCarla, Error, TEXT(
"Can't find CarlaParameters instance!"));
372 UE_LOG(LogCarla, Error, TEXT(
"Can't find CarlaParameters asset!"));
375 for (TActorIterator<ATrafficSignBase> It(
World); It; ++It)
378 check(
Actor !=
nullptr);
382 ActorDispatcher->RegisterActor(*
Actor, Description);
386 auto Definitions = GetActorDefinitions();
387 uint32 StaticMeshUId = 0;
388 for (
auto& Definition : Definitions)
390 if (Definition.Id ==
"static.prop.mesh")
392 StaticMeshUId = Definition.UId;
397 for (TActorIterator<AStaticMeshActor> It(
World); It; ++It)
400 check(
Actor !=
nullptr);
401 auto MeshComponent =
Actor->GetStaticMeshComponent();
402 check(MeshComponent !=
nullptr);
403 if (MeshComponent->Mobility == EComponentMobility::Movable)
406 Description.
Id = TEXT(
"static.prop.mesh");
407 Description.
UId = StaticMeshUId;
411 MeshComponent->GetStaticMesh()->GetPathName()});
414 FString::SanitizeFloat(MeshComponent->GetMass())});
415 ActorDispatcher->RegisterActor(*
Actor, Description);
420void UCarlaEpisode::EndPlay(
void)
426 if (Recorder->GetReplayer()->IsEnabled())
428 Recorder->GetReplayer()->Stop();
433std::string UCarlaEpisode::StartRecorder(std::string Name,
bool AdditionalData)
439 result = Recorder->Start(Name, MapName, AdditionalData);
443 result =
"Recorder is not ready";
449TPair<EActorSpawnResultStatus, FCarlaActor*> UCarlaEpisode::SpawnActorWithInfo(
450 const FTransform &Transform,
462 auto result = ActorDispatcher->SpawnActor(LocalTransform, thisActorDescription, DesiredId);
463 if (result.Key == EActorSpawnResultStatus::Success && bIsPrimaryServer)
465 if (Recorder->IsEnabled())
467 Recorder->CreateRecorderEventAdd(
468 result.Value->GetActorId(),
469 static_cast<uint8_t
>(result.Value->GetActorType()),
474 if (bIsPrimaryServer)
476 GetFrameData().CreateRecorderEventAdd(
477 result.Value->GetActorId(),
478 static_cast<uint8_t
>(result.Value->GetActorType()),
480 std::move(thisActorDescription));
UE_LOG(LogCarla, Log, TEXT("UActorDispatcher::Destroying actor: '%s' %x"), *Id, Actor)
FString CarlaGetRelevantTagAsString(const TSet< crp::CityObjectLabel > &SemanticTags)
const FCarlaActor * FindCarlaActor(const AActor *Actor) const
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld * World
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld Actor
static FString UCarlaEpisode_GetTrafficSignId(ETrafficSignState State)
static FString BuildRecastBuilderFile()
const TArray< FTransform > & GetSpawnPointsTransforms() const
FTransform GlobalToLocalTransform(const FTransform &InTransform) const
static void GetTagsOfTaggedActor(const AActor &Actor, TSet< crp::CityObjectLabel > &Tags)
检索已标记的角色的标记。CityObjectLabel::None 为 未添加到数组中。
const FActorInfo * GetActorInfo() const
IdType GetActorId() const
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType, const FString &SocketName="")
static FBoundingBox GetActorBoundingBox(const AActor *Actor, uint8 InTagQueried=0xFF)
计算给定 Carla actor 的边界框。
FCarlaEngine * GetCarlaEngine()
void SetOpendriveGenerationParameters(const carla::rpc::OpendriveGenerationParameters &Parameters)
static UCarlaGameInstance * GetGameInstance(const UObject *WorldContextObject)
static ALargeMapManager * GetLargeMapManager(const UObject *WorldContextObject)
static ACarlaGameModeBase * GetGameMode(const UObject *WorldContextObject)
static boost::optional< road::Map > Load(const std::string &opendrive)
std::vector< uint8_t > semantic_tags
ActorDescription description
geom::BoundingBox bounding_box
geom::Transform Transform
static void log_warning(Args &&... args)
An actor attribute, may be an intrinsic (non-modifiable) attribute of the actor or an user-defined ac...
TMap< FString, FActorAttribute > Variations
用户选择了参与者的变化版本。请注意,此时是 由不可修改的属性表示
TSubclassOf< AActor > Class
要生成的参与者类
crp::Actor SerializedData
Seting for map generation from opendrive without additional geometry
bool enable_pedestrian_navigation