CARLA
CarlaEpisode.h
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 #pragma once
8 
15 #include "Carla/Weather/Weather.h"
16 #include "Carla/Game/FrameData.h"
18 
19 #include "GameFramework/Pawn.h"
20 #include "Materials/MaterialParameterCollectionInstance.h"
21 
23 #include <carla/geom/BoundingBox.h>
24 #include <carla/geom/GeoLocation.h>
25 #include <carla/ros2/ROS2.h>
26 #include <carla/rpc/Actor.h>
29 #include <carla/streaming/Server.h>
31 
32 #include "CarlaEpisode.generated.h"
33 
34 /// A simulation episode.
35 ///
36 /// Each time the level is restarted a new episode is created.
37 UCLASS(BlueprintType, Blueprintable)
38 class CARLA_API UCarlaEpisode : public UObject
39 {
40  GENERATED_BODY()
41 
42  // ===========================================================================
43  // -- Constructor ------------------------------------------------------------
44  // ===========================================================================
45 
46 public:
47 
48  UCarlaEpisode(const FObjectInitializer &ObjectInitializer);
49 
50  // ===========================================================================
51  // -- Load a new episode -----------------------------------------------------
52  // ===========================================================================
53 
54  /// Load a new map and start a new episode.
55  ///
56  /// If @a MapString is empty, the current map is reloaded.
57  UFUNCTION(BlueprintCallable)
58  bool LoadNewEpisode(const FString &MapString, bool ResetSettings = true);
59 
60  /// Load a new map generating the mesh from OpenDRIVE data and
61  /// start a new episode.
62  ///
63  /// If @a MapString is empty, it fails.
64  bool LoadNewOpendriveEpisode(
65  const FString &OpenDriveString,
67 
68  // ===========================================================================
69  // -- Episode settings -------------------------------------------------------
70  // ===========================================================================
71 
72  UFUNCTION(BlueprintCallable)
73  const FEpisodeSettings &GetSettings() const
74  {
75  return EpisodeSettings;
76  }
77 
78  UFUNCTION(BlueprintCallable)
79  void ApplySettings(const FEpisodeSettings &Settings);
80 
81  // ===========================================================================
82  // -- Retrieve info about this episode ---------------------------------------
83  // ===========================================================================
84 
85  /// Return the unique id of this episode.
86  auto GetId() const
87  {
88  return Id;
89  }
90 
91  /// Return the name of the map loaded in this episode.
92  UFUNCTION(BlueprintCallable)
93  const FString &GetMapName() const
94  {
95  return MapName;
96  }
97 
98  /// Game seconds since the start of this episode.
99  double GetElapsedGameTime() const
100  {
101  return ElapsedGameTime;
102  }
103 
104  /// Visual game seconds
105  double GetVisualGameTime() const
106  {
107  return VisualGameTime;
108  }
109 
110  void SetVisualGameTime(double Time)
111  {
112  VisualGameTime = Time;
113 
114  // update time in material parameters also
115  if (MaterialParameters)
116  {
117  MaterialParameters->SetScalarParameterValue(FName("VisualTime"), VisualGameTime);
118  }
119  }
120 
121  /// Return the list of actor definitions that are available to be spawned this
122  /// episode.
123  UFUNCTION(BlueprintCallable)
124  const TArray<FActorDefinition> &GetActorDefinitions() const
125  {
126  return ActorDispatcher->GetActorDefinitions();
127  }
128 
129  /// Return the list of recommended spawn points for vehicles.
130  UFUNCTION(BlueprintCallable)
131  TArray<FTransform> GetRecommendedSpawnPoints() const;
132 
133  /// Return the GeoLocation point of the map loaded
135  {
136  return MapGeoReference;
137  }
138 
139  // ===========================================================================
140  // -- Retrieve special actors ------------------------------------------------
141  // ===========================================================================
142 
143  UFUNCTION(BlueprintCallable)
144  APawn *GetSpectatorPawn() const
145  {
146  return Spectator;
147  }
148 
149  UFUNCTION(BlueprintCallable)
150  AWeather *GetWeather() const
151  {
152  return Weather;
153  }
154 
156  {
157  return ActorDispatcher->GetActorRegistry();
158  }
159 
161  {
162  return ActorDispatcher->GetActorRegistry();
163  }
164 
165  // ===========================================================================
166  // -- Actor look up methods --------------------------------------------------
167  // ===========================================================================
168 
169  /// Find a Carla actor by id.
170  ///
171  /// If the actor is not found or is pending kill, the returned view is
172  /// invalid.
174  {
175  return ActorDispatcher->GetActorRegistry().FindCarlaActor(ActorId);
176  }
177 
178  /// Find the actor view of @a Actor.
179  ///
180  /// If the actor is not found or is pending kill, the returned view is
181  /// invalid.
183  {
184  return ActorDispatcher->GetActorRegistry().FindCarlaActor(Actor);
185  }
186 
187  /// Get the description of the Carla actor (sensor) using specific stream id.
188  ///
189  /// If the actor is not found returns an empty string
191  {
192  return ActorDispatcher->GetActorRegistry().GetDescriptionFromStream(StreamId);
193  }
194 
195  // ===========================================================================
196  // -- Actor handling methods -------------------------------------------------
197  // ===========================================================================
198 
199  /// Spawns an actor based on @a ActorDescription at @a Transform. To properly
200  /// despawn an actor created with this function call DestroyActor.
201  ///
202  /// @return A pair containing the result of the spawn function and a view over
203  /// the actor and its properties. If the status is different of Success the
204  /// view is invalid.
205  TPair<EActorSpawnResultStatus, FCarlaActor*> SpawnActorWithInfo(
206  const FTransform &Transform,
207  FActorDescription thisActorDescription,
208  FCarlaActor::IdType DesiredId = 0);
209 
210  /// Spawns an actor based on @a ActorDescription at @a Transform.
211  ///
212  /// @return the actor to be spawned
214  const FTransform &Transform,
215  FActorDescription thisActorDescription)
216  {
217  FTransform NewTransform = Transform;
218  auto result = ActorDispatcher->ReSpawnActor(NewTransform, thisActorDescription);
219  if (Recorder->IsEnabled())
220  {
221  // do something?
222  }
223 
224  return result;
225  }
226 
227  /// Spawns an actor based on @a ActorDescription at @a Transform. To properly
228  /// despawn an actor created with this function call DestroyActor.
229  ///
230  /// @return nullptr on failure.
231  ///
232  /// @note Special overload for blueprints.
233  UFUNCTION(BlueprintCallable)
234  AActor *SpawnActor(
235  const FTransform &Transform,
236  FActorDescription ActorDescription)
237  {
238  return SpawnActorWithInfo(Transform, std::move(ActorDescription)).Value->GetActor();
239  }
240 
241  /// Attach @a Child to @a Parent.
242  ///
243  /// @pre Actors cannot be null.
244  UFUNCTION(BlueprintCallable)
245  void AttachActors(
246  AActor *Child,
247  AActor *Parent,
248  EAttachmentType InAttachmentType = EAttachmentType::Rigid);
249 
250  /// @copydoc FActorDispatcher::DestroyActor(AActor*)
251  UFUNCTION(BlueprintCallable)
252  bool DestroyActor(AActor *Actor)
253  {
254  FCarlaActor* CarlaActor = FindCarlaActor(Actor);
255  if (CarlaActor)
256  {
257  carla::rpc::ActorId ActorId = CarlaActor->GetActorId();
258  return DestroyActor(ActorId);
259  }
260  return false;
261  }
262 
264  {
265  if (bIsPrimaryServer)
266  {
267  GetFrameData().AddEvent(
268  CarlaRecorderEventDel{ActorId});
269  }
270  if (Recorder->IsEnabled())
271  {
272  // recorder event
273  CarlaRecorderEventDel RecEvent{ActorId};
274  Recorder->AddEvent(std::move(RecEvent));
275  }
276 
277  return ActorDispatcher->DestroyActor(ActorId);
278  }
279 
281  {
282  ActorDispatcher->PutActorToSleep(ActorId, this);
283  }
284 
286  {
287  ActorDispatcher->WakeActorUp(ActorId, this);
288  }
289 
290  // ===========================================================================
291  // -- Other methods ----------------------------------------------------------
292  // ===========================================================================
293 
294  /// Create a serializable object describing the actor.
295  carla::rpc::Actor SerializeActor(FCarlaActor* CarlaActor) const;
296 
297  /// Create a serializable object describing the actor.
298  /// Can be used to serialized actors that are not in the registry
299  carla::rpc::Actor SerializeActor(AActor* Actor) const;
300 
301  // ===========================================================================
302  // -- Private methods and members --------------------------------------------
303  // ===========================================================================
304 
306  {
307  return Recorder;
308  }
309 
311  {
312  Recorder = Rec;
313  }
314 
316  {
317  return Recorder->GetReplayer();
318  }
319 
320  std::string StartRecorder(std::string name, bool AdditionalData);
321 
322  FIntVector GetCurrentMapOrigin() const { return CurrentMapOrigin; }
323 
324  void SetCurrentMapOrigin(const FIntVector& NewOrigin) { CurrentMapOrigin = NewOrigin; }
325 
326  FFrameData& GetFrameData() { return FrameData; }
327 
328  FSensorManager& GetSensorManager() { return SensorManager; }
329 
330  bool bIsPrimaryServer = true;
331 
332 private:
333 
334  friend class ACarlaGameModeBase;
335  friend class FCarlaEngine;
336 
337  void InitializeAtBeginPlay();
338 
339  void EndPlay();
340 
342  {
343  ActorDispatcher->Bind(ActorFactory);
344  }
345 
346  std::pair<int, FCarlaActor&> TryToCreateReplayerActor(
347  FVector &Location,
348  FVector &Rotation,
349  FActorDescription &ActorDesc,
350  unsigned int desiredId);
351 
352  bool SetActorSimulatePhysics(FCarlaActor &CarlaActor, bool bEnabled);
353 
354  bool SetActorCollisions(FCarlaActor &CarlaActor, bool bEnabled);
355 
356  bool SetActorDead(FCarlaActor &CarlaActor);
357 
358  void TickTimers(float DeltaSeconds)
359  {
360  ElapsedGameTime += DeltaSeconds;
361  SetVisualGameTime(VisualGameTime + DeltaSeconds);
362  #if defined(WITH_ROS2)
363  auto ROS2 = carla::ros2::ROS2::GetInstance();
364  if (ROS2->IsEnabled())
365  ROS2->SetTimestamp(GetElapsedGameTime());
366  #endif
367 
368  }
369 
370  const uint64 Id = 0u;
371 
372  // simulation time
373  double ElapsedGameTime = 0.0;
374 
375  // visual time (used by clounds and other FX that need to be deterministic)
376  double VisualGameTime = 0.0;
377 
378  UPROPERTY(VisibleAnywhere)
379  FString MapName;
380 
381  UPROPERTY(VisibleAnywhere)
382  FEpisodeSettings EpisodeSettings;
383 
384  UPROPERTY(VisibleAnywhere)
385  UActorDispatcher *ActorDispatcher = nullptr;
386 
387  UPROPERTY(VisibleAnywhere)
388  APawn *Spectator = nullptr;
389 
390  UPROPERTY(VisibleAnywhere)
391  AWeather *Weather = nullptr;
392 
393  UPROPERTY(VisibleAnywhere)
394  UMaterialParameterCollectionInstance *MaterialParameters = nullptr;
395 
397 
398  carla::geom::GeoLocation MapGeoReference;
399 
400  FIntVector CurrentMapOrigin;
401 
402  FFrameData FrameData;
403 
404  FSensorManager SensorManager;
405 };
406 
407 FString CarlaGetRelevantTagAsString(const TSet<crp::CityObjectLabel> &SemanticTags);
Base class for Carla actor factories.
FCarlaActor * FindCarlaActor(FCarlaActor::IdType ActorId)
Find a Carla actor by id.
Definition: CarlaEpisode.h:173
CarlaReplayer * GetReplayer() const
Definition: CarlaEpisode.h:315
Seting for map generation from opendrive without additional geometry.
FActorRegistry & GetActorRegistry()
Definition: CarlaEpisode.h:160
FCarlaActor * FindCarlaActor(AActor *Actor) const
Find the actor view of Actor.
Definition: CarlaEpisode.h:182
A registry of all the Carla actors.
Definition: ActorRegistry.h:20
FSensorManager & GetSensorManager()
Definition: CarlaEpisode.h:328
bool DestroyActor(carla::rpc::ActorId ActorId)
Definition: CarlaEpisode.h:263
double GetElapsedGameTime() const
Game seconds since the start of this episode.
Definition: CarlaEpisode.h:99
EAttachmentType
Definition: ActorAttacher.h:20
Object in charge of binding ActorDefinitions to spawn functions, as well as keeping the registry of a...
void WakeActorUp(carla::rpc::ActorId ActorId)
Definition: CarlaEpisode.h:285
This file contains definitions of common data structures used in traffic manager. ...
Definition: Carla.cpp:133
uint32 IdType
Definition: CarlaActor.h:27
void PutActorToSleep(carla::rpc::ActorId ActorId)
Definition: CarlaEpisode.h:280
A definition of a Carla Actor with all the variation and attributes.
uint32_t stream_id_type
Definition: Types.h:18
geom::Location Location
Definition: rpc/Location.h:14
const FActorRegistry & GetActorRegistry() const
Definition: CarlaEpisode.h:155
carla::SharedPtr< cc::Actor > Actor
A simulation episode.
Definition: CarlaEpisode.h:38
Recorder for the simulation.
Definition: CarlaRecorder.h:76
ACarlaRecorder * Recorder
Definition: CarlaEngine.h:120
auto GetId() const
Return the unique id of this episode.
Definition: CarlaEpisode.h:86
A description of a Carla Actor with all its variation.
uint32_t ActorId
Definition: ActorId.h:14
FIntVector GetCurrentMapOrigin() const
Definition: CarlaEpisode.h:322
FString CarlaGetRelevantTagAsString(const TSet< crp::CityObjectLabel > &SemanticTags)
void RegisterActorFactory(ACarlaActorFactory &ActorFactory)
Definition: CarlaEpisode.h:341
ACarlaRecorder * GetRecorder() const
Definition: CarlaEpisode.h:305
void SetCurrentMapOrigin(const FIntVector &NewOrigin)
Definition: CarlaEpisode.h:324
FString GetActorDescriptionFromStream(carla::streaming::detail::stream_id_type StreamId)
Get the description of the Carla actor (sensor) using specific stream id.
Definition: CarlaEpisode.h:190
void SetRecorder(ACarlaRecorder *Rec)
Definition: CarlaEpisode.h:310
geom::Rotation Rotation
Definition: rpc/Transform.h:14
FFrameData & GetFrameData()
Definition: CarlaEpisode.h:326
const carla::geom::GeoLocation & GetGeoReference() const
Return the GeoLocation point of the map loaded.
Definition: CarlaEpisode.h:134
Base class for the CARLA Game Mode.
static std::shared_ptr< ROS2 > GetInstance()
Definition: ROS2.h:51
IdType GetActorId() const
Definition: CarlaActor.h:80
void SetVisualGameTime(double Time)
Definition: CarlaEpisode.h:110
AActor * ReSpawnActorWithInfo(const FTransform &Transform, FActorDescription thisActorDescription)
Spawns an actor based on ActorDescription at Transform.
Definition: CarlaEpisode.h:213
geom::Transform Transform
Definition: rpc/Transform.h:16
double GetVisualGameTime() const
Visual game seconds.
Definition: CarlaEpisode.h:105
void TickTimers(float DeltaSeconds)
Definition: CarlaEpisode.h:358
A view over an actor and its properties.
Definition: CarlaActor.h:23