CARLA
 
载入中...
搜索中...
未找到
CarlaEpisode.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"
10
13#include <carla/rpc/String.h>
15
16#include "Carla/Sensor/Sensor.h"
23
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"
33
35{
36 using TSS = ETrafficSignState;
37 switch (State)
38 {
39 case TSS::TrafficLightRed:
40 case TSS::TrafficLightYellow:
41 case TSS::TrafficLightGreen: return TEXT("traffic.traffic_light");
42 case TSS::SpeedLimit_30: return TEXT("traffic.speed_limit.30");
43 case TSS::SpeedLimit_40: return TEXT("traffic.speed_limit.40");
44 case TSS::SpeedLimit_50: return TEXT("traffic.speed_limit.50");
45 case TSS::SpeedLimit_60: return TEXT("traffic.speed_limit.60");
46 case TSS::SpeedLimit_90: return TEXT("traffic.speed_limit.90");
47 case TSS::SpeedLimit_100: return TEXT("traffic.speed_limit.100");
48 case TSS::SpeedLimit_120: return TEXT("traffic.speed_limit.120");
49 case TSS::SpeedLimit_130: return TEXT("traffic.speed_limit.130");
50 case TSS::StopSign: return TEXT("traffic.stop");
51 case TSS::YieldSign: return TEXT("traffic.yield");
52 default: return TEXT("traffic.unknown");
53 }
54}
55
56UCarlaEpisode::UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
57 : Super(ObjectInitializer),
58 Id(URandomEngine::GenerateRandomId())
59{
60 ActorDispatcher = CreateDefaultSubobject<UActorDispatcher>(TEXT("ActorDispatcher"));
62}
63
64bool UCarlaEpisode::LoadNewEpisode(const FString &MapString, bool ResetSettings)
65{
66 bool bIsFileFound = false;
67
68 FString FinalPath = MapString.IsEmpty() ? GetMapName() : MapString;
69 FinalPath += !MapString.EndsWith(".umap") ? ".umap" : "";
70
71 if (MapString.StartsWith("/Game"))
72 {
73 // Some conversions...
74 FinalPath.RemoveFromStart(TEXT("/Game/"));
75 FinalPath = FPaths::ProjectContentDir() + FinalPath;
76 FinalPath = IFileManager::Get().ConvertToAbsolutePathForExternalAppForRead(*FinalPath);
77
78 if (FPaths::FileExists(FinalPath)) {
79 bIsFileFound = true;
80 FinalPath = MapString;
81 }
82 }
83 else
84 {
85 if (MapString.Contains("/")) return false;
86
87 // Find the full path under Carla
88 TArray<FString> TempStrArray, PathList;
89 IFileManager::Get().FindFilesRecursive(PathList, *FPaths::ProjectContentDir(), *FinalPath, true, false, false);
90 if (PathList.Num() > 0)
91 {
92 FinalPath = PathList[0];
93 FinalPath.ParseIntoArray(TempStrArray, TEXT("Content/"), true);
94 FinalPath = TempStrArray[1];
95 FinalPath.ParseIntoArray(TempStrArray, TEXT("."), true);
96 FinalPath = "/Game/" + TempStrArray[0];
97
98 return LoadNewEpisode(FinalPath, ResetSettings);
99 }
100 }
101
102 if (bIsFileFound)
103 {
104 UE_LOG(LogCarla, Warning, TEXT("Loading a new episode: %s"), *FinalPath);
105 UGameplayStatics::OpenLevel(GetWorld(), *FinalPath, true);
106 if (ResetSettings)
108
109 // send 'LOAD_MAP' command to all secondary servers (if any)
111 {
112 UCarlaGameInstance *GameInstance = UCarlaStatics::GetGameInstance(GetWorld());
113 if(GameInstance)
114 {
115 FCarlaEngine *CarlaEngine = GameInstance->GetCarlaEngine();
116 auto SecondaryServer = CarlaEngine->GetSecondaryServer();
117 if (SecondaryServer->HasClientsConnected())
118 {
119 SecondaryServer->GetCommander().SendLoadMap(std::string(TCHAR_TO_UTF8(*FinalPath)));
120 }
121 }
122 }
123 }
124 return bIsFileFound;
125}
126
128{
129 // Define filename with extension depending on if we are on Windows or not
130#if PLATFORM_WINDOWS
131 const FString RecastToolName = "RecastBuilder.exe";
132#else
133 const FString RecastToolName = "RecastBuilder";
134#endif // PLATFORM_WINDOWS
135
136 // Define path depending on the UE4 build type (Package or Editor)
137#if UE_BUILD_SHIPPING
138 const FString AbsoluteRecastBuilderPath = FPaths::ConvertRelativePathToFull(
139 FPaths::RootDir() + "Tools/" + RecastToolName);
140#else
141 const FString AbsoluteRecastBuilderPath = FPaths::ConvertRelativePathToFull(
142 FPaths::ProjectDir() + "../../Util/DockerUtils/dist/" + RecastToolName);
143#endif
144 return AbsoluteRecastBuilderPath;
145}
146
148 const FString &OpenDriveString,
150{
151 if (OpenDriveString.IsEmpty())
152 {
153 UE_LOG(LogCarla, Error, TEXT("The OpenDrive string is empty."));
154 return false;
155 }
156
157 // Build the Map from the OpenDRIVE data
158 const auto CarlaMap = carla::opendrive::OpenDriveParser::Load(
159 carla::rpc::FromLongFString(OpenDriveString));
160
161 // Check the Map is correclty generated
162 if (!CarlaMap.has_value())
163 {
164 UE_LOG(LogCarla, Error, TEXT("The OpenDrive string is invalid or not supported"));
165 return false;
166 }
167
168 // Generate the OBJ (as string)
169 const auto RoadMesh = CarlaMap->GenerateMesh(Params.vertex_distance);
170 const auto CrosswalksMesh = CarlaMap->GetAllCrosswalkMesh();
171 const auto RecastOBJ = (RoadMesh + CrosswalksMesh).GenerateOBJForRecast();
172
173 const FString AbsoluteOBJPath = FPaths::ConvertRelativePathToFull(
174 FPaths::ProjectContentDir() + "Carla/Maps/Nav/OpenDriveMap.obj");
175
176 // Store the OBJ string to a file in order to that RecastBuilder can load it
177 FFileHelper::SaveStringToFile(
178 carla::rpc::ToLongFString(RecastOBJ),
179 *AbsoluteOBJPath,
180 FFileHelper::EEncodingOptions::ForceUTF8,
181 &IFileManager::Get());
182
183 const FString AbsoluteXODRPath = FPaths::ConvertRelativePathToFull(
184 FPaths::ProjectContentDir() + "Carla/Maps/OpenDrive/OpenDriveMap.xodr");
185
186 // Copy the OpenDrive as a file in the serverside
187 FFileHelper::SaveStringToFile(
188 OpenDriveString,
189 *AbsoluteXODRPath,
190 FFileHelper::EEncodingOptions::ForceUTF8,
191 &IFileManager::Get());
192
193 if (!FPaths::FileExists(AbsoluteXODRPath))
194 {
195 UE_LOG(LogCarla, Error, TEXT("ERROR: XODR not copied!"));
196 return false;
197 }
198
199 UCarlaGameInstance * GameInstance = UCarlaStatics::GetGameInstance(GetWorld());
200 if(GameInstance)
201 {
202 GameInstance->SetOpendriveGenerationParameters(Params);
203 }
204 else
205 {
206 carla::log_warning("Missing game instance");
207 }
208
209 const FString AbsoluteRecastBuilderPath = BuildRecastBuilderFile();
210
211 if (FPaths::FileExists(AbsoluteRecastBuilderPath) &&
213 {
214 /// @todo this can take too long to finish, clients need a method
215 /// to know if the navigation is available or not.
216 FPlatformProcess::CreateProc(
217 *AbsoluteRecastBuilderPath, *AbsoluteOBJPath,
218 true, true, true, nullptr, 0, nullptr, nullptr);
219 }
220 else
221 {
222 UE_LOG(LogCarla, Warning, TEXT("'RecastBuilder' not present under '%s', "
223 "the binaries for pedestrian navigation will not be created."),
224 *AbsoluteRecastBuilderPath);
225 }
226
227 return true;
228}
229
231{
232 EpisodeSettings = Settings;
234 {
235 UE_LOG(LogCarla, Warning, TEXT("Setting ActorActiveDistance is smaller that TileStreamingDistance, TileStreamingDistance will be increased"));
237 }
239}
240
242{
244
245 return GM->GetSpawnPointsTransforms();
246}
247
249{
250 carla::rpc::Actor Actor;
251 if (CarlaActor)
252 {
253 Actor = CarlaActor->GetActorInfo()->SerializedData;
254 auto ParentId = CarlaActor->GetParent();
255 if (ParentId)
256 {
257 Actor.parent_id = ParentId;
258 }
259 }
260 else
261 {
262 UE_LOG(LogCarla, Warning, TEXT("Trying to serialize invalid actor"));
263 }
264 return Actor;
265}
266
268{
269 FCarlaActor* CarlaActor = FindCarlaActor(Actor);
270 if (CarlaActor)
271 {
272 return SerializeActor(CarlaActor);
273 }
274 else
275 {
276 carla::rpc::Actor SerializedActor;
277 SerializedActor.id = 0u;
279 TSet<crp::CityObjectLabel> SemanticTags;
280 ATagger::GetTagsOfTaggedActor(*Actor, SemanticTags);
281 FActorDescription Description;
282 Description.Id = TEXT("static.") + CarlaGetRelevantTagAsString(SemanticTags);
283 SerializedActor.description = Description;
284 SerializedActor.semantic_tags.reserve(SemanticTags.Num());
285 for (auto &&Tag : SemanticTags)
286 {
287 using tag_t = decltype(SerializedActor.semantic_tags)::value_type;
288 SerializedActor.semantic_tags.emplace_back(static_cast<tag_t>(Tag));
289 }
290 return SerializedActor;
291 }
292}
293
295 AActor *Child,
296 AActor *Parent,
297 EAttachmentType InAttachmentType,
298 const FString& SocketName)
299{
300 Child->AddActorWorldOffset(FVector(CurrentMapOrigin));
301
302 UActorAttacher::AttachActors(Child, Parent, InAttachmentType, SocketName);
303
305 {
308 FindCarlaActor(Child)->GetActorId(),
309 FindCarlaActor(Parent)->GetActorId()});
310 }
311 // recorder event
312 if (Recorder->IsEnabled())
313 {
315 {
316 FindCarlaActor(Child)->GetActorId(),
317 FindCarlaActor(Parent)->GetActorId()
318 };
319 Recorder->AddEvent(std::move(RecEvent));
320 }
321}
322
324{
325 auto World = GetWorld();
326 check(World != nullptr);
327 auto PlayerController = UGameplayStatics::GetPlayerController(World, 0);
328 if (PlayerController == nullptr)
329 {
330 UE_LOG(LogCarla, Error, TEXT("Can't find player controller!"));
331 return;
332 }
333 Spectator = PlayerController->GetPawn();
334 if (Spectator != nullptr)
335 {
336 FActorDescription Description;
337 Description.Id = TEXT("spectator");
338 Description.Class = Spectator->GetClass();
340 }
341 else
342 {
343 UE_LOG(LogCarla, Error, TEXT("Can't find spectator!"));
344 }
345
346 // material parameters collection
347 UMaterialParameterCollection *Collection = LoadObject<UMaterialParameterCollection>(nullptr, TEXT("/Game/Carla/Blueprints/Game/CarlaParameters.CarlaParameters"), nullptr, LOAD_None, nullptr);
348 if (Collection != nullptr)
349 {
350 MaterialParameters = World->GetParameterCollectionInstance(Collection);
351 if (MaterialParameters == nullptr)
352 {
353 UE_LOG(LogCarla, Error, TEXT("Can't find CarlaParameters instance!"));
354 }
355 }
356 else
357 {
358 UE_LOG(LogCarla, Error, TEXT("Can't find CarlaParameters asset!"));
359 }
360
361 for (TActorIterator<ATrafficSignBase> It(World); It; ++It)
362 {
363 ATrafficSignBase *Actor = *It;
364 check(Actor != nullptr);
365 FActorDescription Description;
366 Description.Id = UCarlaEpisode_GetTrafficSignId(Actor->GetTrafficSignState());
367 Description.Class = Actor->GetClass();
368 ActorDispatcher->RegisterActor(*Actor, Description);
369 }
370
371 // get the definition id for static.prop.mesh
372 auto Definitions = GetActorDefinitions();
373 uint32 StaticMeshUId = 0;
374 for (auto& Definition : Definitions)
375 {
376 if (Definition.Id == "static.prop.mesh")
377 {
378 StaticMeshUId = Definition.UId;
379 break;
380 }
381 }
382
383 for (TActorIterator<AStaticMeshActor> It(World); It; ++It)
384 {
385 auto Actor = *It;
386 check(Actor != nullptr);
387 auto MeshComponent = Actor->GetStaticMeshComponent();
388 check(MeshComponent != nullptr);
389 if (MeshComponent->Mobility == EComponentMobility::Movable)
390 {
391 FActorDescription Description;
392 Description.Id = TEXT("static.prop.mesh");
393 Description.UId = StaticMeshUId;
394 Description.Class = Actor->GetClass();
395 Description.Variations.Add("mesh_path",
397 MeshComponent->GetStaticMesh()->GetPathName()});
398 Description.Variations.Add("mass",
400 FString::SanitizeFloat(MeshComponent->GetMass())});
401 ActorDispatcher->RegisterActor(*Actor, Description);
402 }
403 }
404}
405
407{
408 // stop recorder and replayer
409 if (Recorder)
410 {
411 Recorder->Stop();
413 {
415 }
416 }
417}
418
419std::string UCarlaEpisode::StartRecorder(std::string Name, bool AdditionalData)
420{
421 std::string result;
422
423 if (Recorder)
424 {
425 result = Recorder->Start(Name, MapName, AdditionalData);
426 }
427 else
428 {
429 result = "Recorder is not ready";
430 }
431
432 return result;
433}
434
435TPair<EActorSpawnResultStatus, FCarlaActor*> UCarlaEpisode::SpawnActorWithInfo(
436 const FTransform &Transform,
437 FActorDescription thisActorDescription,
438 FCarlaActor::IdType DesiredId)
439{
441 FTransform LocalTransform = Transform;
442 if(LargeMap)
443 {
444 LocalTransform = LargeMap->GlobalToLocalTransform(LocalTransform);
445 }
446
447 // NewTransform.AddToTranslation(-1.0f * FVector(CurrentMapOrigin));
448 auto result = ActorDispatcher->SpawnActor(LocalTransform, thisActorDescription, DesiredId);
449 if (result.Key == EActorSpawnResultStatus::Success && bIsPrimaryServer)
450 {
451 if (Recorder->IsEnabled())
452 {
454 result.Value->GetActorId(),
455 static_cast<uint8_t>(result.Value->GetActorType()),
456 Transform,
457 thisActorDescription
458 );
459 }
461 {
463 result.Value->GetActorId(),
464 static_cast<uint8_t>(result.Value->GetActorType()),
465 Transform,
466 std::move(thisActorDescription));
467 }
468 }
469
470 return result;
471}
EAttachmentType
static FString UCarlaEpisode_GetTrafficSignId(ETrafficSignState State)
static FString BuildRecastBuilderFile()
FString CarlaGetRelevantTagAsString(const TSet< crp::CityObjectLabel > &SemanticTags)
ETrafficSignState
Base class for the CARLA Game Mode.
const TArray< FTransform > & GetSpawnPointsTransforms() const
bool IsEnabled(void)
void AddEvent(const CarlaRecorderEventAdd &Event)
CarlaReplayer * GetReplayer(void)
std::string Start(std::string Name, FString MapName, bool AdditionalData=false)
void CreateRecorderEventAdd(uint32_t DatabaseId, uint8_t Type, const FTransform &Transform, FActorDescription ActorDescription)
FTransform GlobalToLocalTransform(const FTransform &InTransform) const
static void GetTagsOfTaggedActor(const AActor &Actor, TSet< crp::CityObjectLabel > &Tags)
Retrieve the tags of an already tagged actor.
Definition Tagger.cpp:237
bool IsEnabled(void)
void Stop(bool KeepActors=false)
A view over an actor and its properties.
Definition CarlaActor.h:25
IdType GetParent() const
Definition CarlaActor.h:121
uint32 IdType
Definition CarlaActor.h:28
const FActorInfo * GetActorInfo() const
Definition CarlaActor.h:101
IdType GetActorId() const
Definition CarlaActor.h:81
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
Definition CarlaEngine.h:91
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
void SetEpisode(UCarlaEpisode *ThisEpisode)
Definition FrameData.h:76
void AddEvent(const CarlaRecorderEventAdd &Event)
void CreateRecorderEventAdd(uint32_t DatabaseId, uint8_t Type, const FTransform &Transform, FActorDescription ActorDescription, bool bAddOtherRelatedInfo=true)
static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType, const FString &SocketName="")
FCarlaActor * RegisterActor(AActor &Actor, FActorDescription ActorDescription, FActorRegistry::IdType DesiredId=0)
Register an actor that was not created using "SpawnActor" function but that should be kept in the reg...
TPair< EActorSpawnResultStatus, FCarlaActor * > SpawnActor(const FTransform &Transform, FActorDescription ActorDescription, FCarlaActor::IdType DesiredId=0)
Spawns an actor based on ActorDescription at Transform.
static FBoundingBox GetActorBoundingBox(const AActor *Actor, uint8 InTagQueried=0xFF)
Compute the bounding box of the given Carla actor.
FFrameData & GetFrameData()
std::string StartRecorder(std::string name, bool AdditionalData)
carla::rpc::Actor SerializeActor(FCarlaActor *CarlaActor) const
Create a serializable object describing the actor.
FEpisodeSettings EpisodeSettings
UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
FIntVector CurrentMapOrigin
bool LoadNewOpendriveEpisode(const FString &OpenDriveString, const carla::rpc::OpendriveGenerationParameters &Params)
Load a new map generating the mesh from OpenDRIVE data and start a new episode.
const TArray< FActorDefinition > & GetActorDefinitions() const
Return the list of actor definitions that are available to be spawned this episode.
FCarlaActor * FindCarlaActor(FCarlaActor::IdType ActorId)
Find a Carla actor by id.
UActorDispatcher * ActorDispatcher
const FString & GetMapName() const
Return the name of the map loaded in this episode.
void ApplySettings(const FEpisodeSettings &Settings)
TPair< EActorSpawnResultStatus, FCarlaActor * > SpawnActorWithInfo(const FTransform &Transform, FActorDescription thisActorDescription, FCarlaActor::IdType DesiredId=0)
Spawns an actor based on ActorDescription at Transform.
UMaterialParameterCollectionInstance * MaterialParameters
APawn * Spectator
ACarlaRecorder * Recorder
void InitializeAtBeginPlay()
FFrameData FrameData
bool LoadNewEpisode(const FString &MapString, bool ResetSettings=true)
Load a new map and start a new episode.
TArray< FTransform > GetRecommendedSpawnPoints() const
Return the list of recommended spawn points for vehicles.
void AttachActors(AActor *Child, AActor *Parent, EAttachmentType InAttachmentType=EAttachmentType::Rigid, const FString &SocketName="")
Attach Child to Parent.
The game instance contains elements that must be kept alive in between levels.
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
Definition rpc/Actor.h:33
ActorDescription description
Definition rpc/Actor.h:29
geom::BoundingBox bounding_box
Definition rpc/Actor.h:31
static void log_warning(Args &&... args)
Definition Logging.h:96
An actor attribute, may be an intrinsic (non-modifiable) attribute of the actor or an user-defined ac...
A description of a Carla Actor with all its variation.
TMap< FString, FActorAttribute > Variations
User selected variations of the actor.
TSubclassOf< AActor > Class
Class of the actor to be spawned.
uint32 UId
UId of the definition in which this description was based.
crp::Actor SerializedData
Definition ActorInfo.h:32
Seting for map generation from opendrive without additional geometry