CARLA
CarlaEpisode.cpp
Go to the documentation of this file.
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 
56 UCarlaEpisode::UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
57  : Super(ObjectInitializer),
58  Id(URandomEngine::GenerateRandomId())
59 {
60  ActorDispatcher = CreateDefaultSubobject<UActorDispatcher>(TEXT("ActorDispatcher"));
61  FrameData.SetEpisode(this);
62 }
63 
64 bool 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)
110  if (bIsPrimaryServer)
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 
127 static FString BuildRecastBuilderFile()
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 {
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 {
299  Child->AddActorWorldOffset(FVector(CurrentMapOrigin));
300 
301  UActorAttacher::AttachActors(Child, Parent, InAttachmentType);
302 
303  if (bIsPrimaryServer)
304  {
307  FindCarlaActor(Child)->GetActorId(),
308  FindCarlaActor(Parent)->GetActorId()});
309  }
310  // recorder event
311  if (Recorder->IsEnabled())
312  {
313  CarlaRecorderEventParent RecEvent
314  {
315  FindCarlaActor(Child)->GetActorId(),
316  FindCarlaActor(Parent)->GetActorId()
317  };
318  Recorder->AddEvent(std::move(RecEvent));
319  }
320 }
321 
323 {
324  auto World = GetWorld();
325  check(World != nullptr);
326  auto PlayerController = UGameplayStatics::GetPlayerController(World, 0);
327  if (PlayerController == nullptr)
328  {
329  UE_LOG(LogCarla, Error, TEXT("Can't find player controller!"));
330  return;
331  }
332  Spectator = PlayerController->GetPawn();
333  if (Spectator != nullptr)
334  {
335  FActorDescription Description;
336  Description.Id = TEXT("spectator");
337  Description.Class = Spectator->GetClass();
338  ActorDispatcher->RegisterActor(*Spectator, Description);
339  }
340  else
341  {
342  UE_LOG(LogCarla, Error, TEXT("Can't find spectator!"));
343  }
344 
345  // material parameters collection
346  UMaterialParameterCollection *Collection = LoadObject<UMaterialParameterCollection>(nullptr, TEXT("/Game/Carla/Blueprints/Game/CarlaParameters.CarlaParameters"), nullptr, LOAD_None, nullptr);
347  if (Collection != nullptr)
348  {
349  MaterialParameters = World->GetParameterCollectionInstance(Collection);
350  if (MaterialParameters == nullptr)
351  {
352  UE_LOG(LogCarla, Error, TEXT("Can't find CarlaParameters instance!"));
353  }
354  }
355  else
356  {
357  UE_LOG(LogCarla, Error, TEXT("Can't find CarlaParameters asset!"));
358  }
359 
360  for (TActorIterator<ATrafficSignBase> It(World); It; ++It)
361  {
362  ATrafficSignBase *Actor = *It;
363  check(Actor != nullptr);
364  FActorDescription Description;
365  Description.Id = UCarlaEpisode_GetTrafficSignId(Actor->GetTrafficSignState());
366  Description.Class = Actor->GetClass();
367  ActorDispatcher->RegisterActor(*Actor, Description);
368  }
369 
370  // get the definition id for static.prop.mesh
371  auto Definitions = GetActorDefinitions();
372  uint32 StaticMeshUId = 0;
373  for (auto& Definition : Definitions)
374  {
375  if (Definition.Id == "static.prop.mesh")
376  {
377  StaticMeshUId = Definition.UId;
378  break;
379  }
380  }
381 
382  for (TActorIterator<AStaticMeshActor> It(World); It; ++It)
383  {
384  auto Actor = *It;
385  check(Actor != nullptr);
386  auto MeshComponent = Actor->GetStaticMeshComponent();
387  check(MeshComponent != nullptr);
388  if (MeshComponent->Mobility == EComponentMobility::Movable)
389  {
390  FActorDescription Description;
391  Description.Id = TEXT("static.prop.mesh");
392  Description.UId = StaticMeshUId;
393  Description.Class = Actor->GetClass();
394  Description.Variations.Add("mesh_path",
396  MeshComponent->GetStaticMesh()->GetPathName()});
397  Description.Variations.Add("mass",
399  FString::SanitizeFloat(MeshComponent->GetMass())});
400  ActorDispatcher->RegisterActor(*Actor, Description);
401  }
402  }
403 }
404 
406 {
407  // stop recorder and replayer
408  if (Recorder)
409  {
410  Recorder->Stop();
411  if (Recorder->GetReplayer()->IsEnabled())
412  {
413  Recorder->GetReplayer()->Stop();
414  }
415  }
416 }
417 
418 std::string UCarlaEpisode::StartRecorder(std::string Name, bool AdditionalData)
419 {
420  std::string result;
421 
422  if (Recorder)
423  {
424  result = Recorder->Start(Name, MapName, AdditionalData);
425  }
426  else
427  {
428  result = "Recorder is not ready";
429  }
430 
431  return result;
432 }
433 
434 TPair<EActorSpawnResultStatus, FCarlaActor*> UCarlaEpisode::SpawnActorWithInfo(
435  const FTransform &Transform,
436  FActorDescription thisActorDescription,
437  FCarlaActor::IdType DesiredId)
438 {
439  ALargeMapManager* LargeMap = UCarlaStatics::GetLargeMapManager(GetWorld());
440  FTransform LocalTransform = Transform;
441  if(LargeMap)
442  {
443  LocalTransform = LargeMap->GlobalToLocalTransform(LocalTransform);
444  }
445 
446  // NewTransform.AddToTranslation(-1.0f * FVector(CurrentMapOrigin));
447  auto result = ActorDispatcher->SpawnActor(LocalTransform, thisActorDescription, DesiredId);
448  if (result.Key == EActorSpawnResultStatus::Success && bIsPrimaryServer)
449  {
450  if (Recorder->IsEnabled())
451  {
453  result.Value->GetActorId(),
454  static_cast<uint8_t>(result.Value->GetActorType()),
455  Transform,
456  thisActorDescription
457  );
458  }
459  if (bIsPrimaryServer)
460  {
462  result.Value->GetActorId(),
463  static_cast<uint8_t>(result.Value->GetActorType()),
464  Transform,
465  std::move(thisActorDescription));
466  }
467  }
468 
469  return result;
470 }
FCarlaActor * FindCarlaActor(FCarlaActor::IdType ActorId)
Find a Carla actor by id.
Definition: CarlaEpisode.h:173
bool IsEnabled(void)
Definition: CarlaReplayer.h:65
Seting for map generation from opendrive without additional geometry.
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.
std::string Start(std::string Name, FString MapName, bool AdditionalData=false)
TPair< EActorSpawnResultStatus, FCarlaActor * > SpawnActor(const FTransform &Transform, FActorDescription ActorDescription, FCarlaActor::IdType DesiredId=0)
Spawns an actor based on ActorDescription at Transform.
FString MapName
Definition: CarlaEpisode.h:379
UActorDispatcher * ActorDispatcher
Definition: CarlaEpisode.h:385
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...
ETrafficSignState
static void AttachActors(AActor *Child, AActor *Parent, EAttachmentType AttachmentType)
EAttachmentType
Definition: ActorAttacher.h:20
The game instance contains elements that must be kept alive in between levels.
FFrameData FrameData
Definition: CarlaEpisode.h:402
carla::rpc::Actor SerializeActor(FCarlaActor *CarlaActor) const
Create a serializable object describing the actor.
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
TArray< FTransform > GetRecommendedSpawnPoints() const
Return the list of recommended spawn points for vehicles.
void AddEvent(const CarlaRecorderEventAdd &Event)
static void GetTagsOfTaggedActor(const AActor &Actor, TSet< crp::CityObjectLabel > &Tags)
Retrieve the tags of an already tagged actor.
Definition: Tagger.cpp:236
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
Definition: CarlaEngine.h:91
uint32 IdType
Definition: CarlaActor.h:27
FIntVector CurrentMapOrigin
Definition: CarlaEpisode.h:400
CarlaReplayer * GetReplayer(void)
static FString BuildRecastBuilderFile()
static T Get(carla::rpc::Response< T > &response)
ActorDescription description
Definition: rpc/Actor.h:29
static ACarlaGameModeBase * GetGameMode(const UObject *WorldContextObject)
Definition: CarlaStatics.h:58
static boost::optional< road::Map > Load(const std::string &opendrive)
const FString & GetMapName() const
Return the name of the map loaded in this episode.
Definition: CarlaEpisode.h:93
geom::BoundingBox bounding_box
Definition: rpc/Actor.h:31
FString CarlaGetRelevantTagAsString(const TSet< crp::CityObjectLabel > &SemanticTags)
void CreateRecorderEventAdd(uint32_t DatabaseId, uint8_t Type, const FTransform &Transform, FActorDescription ActorDescription)
TMap< FString, FActorAttribute > Variations
User selected variations of the actor.
std::string StartRecorder(std::string name, bool AdditionalData)
static UCarlaGameInstance * GetGameInstance(const UObject *WorldContextObject)
Definition: CarlaStatics.h:63
carla::SharedPtr< cc::Actor > Actor
crp::Actor SerializedData
Definition: ActorInfo.h:32
TPair< EActorSpawnResultStatus, FCarlaActor * > SpawnActorWithInfo(const FTransform &Transform, FActorDescription thisActorDescription, FCarlaActor::IdType DesiredId=0)
Spawns an actor based on ActorDescription at Transform.
bool LoadNewEpisode(const FString &MapString, bool ResetSettings=true)
Load a new map and start a new episode.
const TArray< FActorDefinition > & GetActorDefinitions() const
Return the list of actor definitions that are available to be spawned this episode.
Definition: CarlaEpisode.h:124
TSubclassOf< AActor > Class
Class of the actor to be spawned.
static FBoundingBox GetActorBoundingBox(const AActor *Actor, uint8 InTagQueried=0xFF)
Compute the bounding box of the given Carla actor.
A description of a Carla Actor with all its variation.
bool IsEnabled(void)
Definition: CarlaRecorder.h:86
static void log_warning(Args &&... args)
Definition: Logging.h:96
const FActorInfo * GetActorInfo() const
Definition: CarlaActor.h:100
static FString UCarlaEpisode_GetTrafficSignId(ETrafficSignState State)
void SetEpisode(UCarlaEpisode *ThisEpisode)
Definition: FrameData.h:76
bool bIsPrimaryServer
Definition: CarlaEpisode.h:330
APawn * Spectator
Definition: CarlaEpisode.h:388
std::vector< uint8_t > semantic_tags
Definition: rpc/Actor.h:33
UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
FFrameData & GetFrameData()
Definition: CarlaEpisode.h:326
void AttachActors(AActor *Child, AActor *Parent, EAttachmentType InAttachmentType=EAttachmentType::Rigid)
Attach Child to Parent.
FTransform GlobalToLocalTransform(const FTransform &InTransform) const
ACarlaRecorder * Recorder
Definition: CarlaEpisode.h:396
static ALargeMapManager * GetLargeMapManager(const UObject *WorldContextObject)
Definition: CarlaStatics.h:100
uint32 UId
UId of the definition in which this description was based.
Base class for the CARLA Game Mode.
void InitializeAtBeginPlay()
FEpisodeSettings EpisodeSettings
Definition: CarlaEpisode.h:382
void Stop(bool KeepActors=false)
ActorId parent_id
Definition: rpc/Actor.h:27
IdType GetActorId() const
Definition: CarlaActor.h:80
FCarlaEngine * GetCarlaEngine()
ETrafficSignState GetTrafficSignState() const
void SetOpendriveGenerationParameters(const carla::rpc::OpendriveGenerationParameters &Parameters)
void CreateRecorderEventAdd(uint32_t DatabaseId, uint8_t Type, const FTransform &Transform, FActorDescription ActorDescription, bool bAddOtherRelatedInfo=true)
Definition: FrameData.cpp:303
An actor attribute, may be an intrinsic (non-modifiable) attribute of the actor or an user-defined ac...
void AddEvent(const CarlaRecorderEventAdd &Event)
Definition: FrameData.cpp:592
UMaterialParameterCollectionInstance * MaterialParameters
Definition: CarlaEpisode.h:394
geom::Transform Transform
Definition: rpc/Transform.h:16
const TArray< FTransform > & GetSpawnPointsTransforms() const
A view over an actor and its properties.
Definition: CarlaActor.h:23
void ApplySettings(const FEpisodeSettings &Settings)
IdType GetParent() const
Definition: CarlaActor.h:120