CARLA
 
载入中...
搜索中...
未找到
CarlaEpisode.h
浏览该文件的文档.
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
18
19#include "GameFramework/Pawn.h"
20#include "Materials/MaterialParameterCollectionInstance.h"
21
25#include <carla/ros2/ROS2.h>
26#include <carla/rpc/Actor.h>
31
32#include "CarlaEpisode.generated.h"
33
34/// 模拟剧集。
35///
36/// 每次重新启动关卡时,都会创建一个新的剧集。
37UCLASS(BlueprintType, Blueprintable)
38class CARLA_API UCarlaEpisode : public UObject
39{
40 GENERATED_BODY()
41
42 // ===========================================================================
43 // -- 构造 函数 ------------------------------------------------------------
44 // ===========================================================================
45
46public:
47/// @brief 构造函数,接受一个 `FObjectInitializer` 类型的参数,用于初始化对象的相关属性,按照UE4的对象初始化机制进行操作。
48 UCarlaEpisode(const FObjectInitializer &ObjectInitializer);
49
50 // ===========================================================================
51 // -- 加载新剧集 -----------------------------------------------------
52 // ===========================================================================
53
54 /// 加载新地图并开始新剧集。
55 ///
56 /// If @a MapString is empty, the current map is reloaded.
57 /// @brief 加载新的地图并启动一个新的模拟情节。
58 /// @param MapString 表示要加载的地图名称的字符串,如果为空字符串,则重新加载当前地图。
59 /// @param ResetSettings 一个布尔值,默认为 `true`,表示是否重置情节设置,若为 `true`,则使用默认或预设的情节设置来启动新情节。
60 /// @return 如果地图加载成功并成功启动新情节,则返回 `true`;否则返回 `false`。
61 UFUNCTION(BlueprintCallable)
62 bool LoadNewEpisode(const FString &MapString, bool ResetSettings = true);
63
64 ///加载从 OpenDRIVE 数据生成网格的新地图,然后
65 ///开始新剧集。
66 ///
67 /// If @a MapString is empty, it fails.
68 bool LoadNewOpendriveEpisode(
69 const FString &OpenDriveString,
70 const carla::rpc::OpendriveGenerationParameters &Params);
71
72 // ===========================================================================
73 // -- 剧集设置 -------------------------------------------------------
74 // ===========================================================================
75/// @brief 获取当前模拟情节的设置信息,返回一个常量引用,确保不会意外修改设置内容,外部只能读取当前的设置情况。
76 UFUNCTION(BlueprintCallable)
77 UFUNCTION(BlueprintCallable)
78 const FEpisodeSettings &GetSettings() const
79 {
80 return EpisodeSettings;
81 }
82/// @brief 应用给定的情节设置信息到当前模拟情节中,用于更新情节的各种参数配置,比如改变地图、Actor生成规则等设置。
83 UFUNCTION(BlueprintCallable)
84 void ApplySettings(const FEpisodeSettings &Settings);
85
86 // ===========================================================================
87 // -- 检索有关此剧集的信息---------------------------------------
88 // ===========================================================================
89
90 /// 返回此剧集的唯一 ID。
91 auto GetId() const
92 {
93 return Id;
94 }
95
96 ///返回本集中加载的地图的名称。
97 UFUNCTION(BlueprintCallable)
98 const FString &GetMapName() const
99 {
100 return MapName;
101 }
102
103 /// 游戏秒数。
104 double GetElapsedGameTime() const
105 {
106 return ElapsedGameTime;
107 }
108
109 /// 视觉游戏秒
110 double GetVisualGameTime() const
111 {
112 return VisualGameTime;
113 }
114/// @brief 设置视觉游戏时间,同时会更新材质参数中的对应时间参数确保相关视觉效果能根据新设置的时间进行更新。
115 /// @param Time 要设置的视觉游戏时间值(以秒为单位)。
116 void SetVisualGameTime(double Time)
117 {
118 VisualGameTime = Time;
119 // Material Parameters 中的更新时间
120 if (MaterialParameters)
121 {
122 MaterialParameters->SetScalarParameterValue(FName("VisualTime"), VisualGameTime);
123 }
124 }
125 /// @brief 返回在本情节中可生成的Actor定义列表,用于了解当前情节下能够创建哪些类型的Actor。
126
127 UFUNCTION(BlueprintCallable)
128 const TArray<FActorDefinition> &GetActorDefinitions() const
129 {
130 return ActorDispatcher->GetActorDefinitions();
131 }
132
133 ///返回推荐的载具重生点列表。
134 UFUNCTION(BlueprintCallable)
135 TArray<FTransform> GetRecommendedSpawnPoints() const;
136
137 /// 返回加载的地图的 GeoLocation 点
138 const carla::geom::GeoLocation &GetGeoReference() const
139 {
140 return MapGeoReference;
141 }
142
143 // ===========================================================================
144 // -- 检索特殊演员 ------------------------------------------------
145 // ===========================================================================
146/// @brief 获取当前模拟情节中的旁观者Pawn
147 UFUNCTION(BlueprintCallable)
148 APawn *GetSpectatorPawn() const
149 {
150 return Spectator;
151 }
152/// @brief 获取当前模拟情节中的天气对象
153 UFUNCTION(BlueprintCallable)
154 AWeather *GetWeather() const
155 {
156 return Weather;
157 }
158/// @brief 获取Actor注册信息的常量引用
159 const FActorRegistry &GetActorRegistry() const
160 {
161 return ActorDispatcher->GetActorRegistry();
162 }
163/// @brief 获取Actor注册信息的引用
164 FActorRegistry &GetActorRegistry()
165 {
166 return ActorDispatcher->GetActorRegistry();
167 }
168
169 // ===========================================================================
170 // -- Actor 查找方法 --------------------------------------------------
171 // ===========================================================================
172
173 ///按 id 查找 Carla 演员。
174 ///
175 /// 如果未找到 actor 或正在等待 kill,则返回的视图为
176 ///无效。
178 {
179 return ActorDispatcher->GetActorRegistry().FindCarlaActor(ActorId);
180 }
181 /// 找到 @a Actor 的 actor 视图。
182 ///
183 /// 如果未找到 actor 或正在等待 kill,则返回的视图为
184 ///无效。
186 {
187 return ActorDispatcher->GetActorRegistry().FindCarlaActor(Actor);
188 }
189
190 ///使用特定流 ID 获取 Carla actor (sensor) 的描述。
191 ///
192 /// 如果未找到 actor,则返回空字符串
193 FString GetActorDescriptionFromStream(carla::streaming::detail::stream_id_type StreamId)
194 {
195 return ActorDispatcher->GetActorRegistry().GetDescriptionFromStream(StreamId);
196 }
197
198 // ===========================================================================
199 // -- Actor处理方法相关部分 -------------------------------------------------
200 // ===========================================================================
201
202 /// @brief 在给定的变换信息(`Transform`)位置
203 /// @param thisActorDescription 描述要创建的Actor的详细信息
204 /// @param DesiredId 可选的期望Actor标识符,默认为0
205 /// @return 返回一个 `TPair` 类型对象
206 TPair<EActorSpawnResultStatus, FCarlaActor*> SpawnActorWithInfo(
207 const FTransform &Transform,
208 FActorDescription thisActorDescription,
209 FCarlaActor::IdType DesiredId = 0);
210
211 /// @brief 在给定的变换信息(`Transform`)位置,根据给定的 `ActorDescription` 重新创建一个Actor
212 /// @param Transform 表示Actor生成位置和姿态的变换信息
213 /// @param thisActorDescription 描述要创建的Actor的详细信息
214 /// @return 返回指向重新创建的Actor的指针(`AActor*` 类型),如果创建失败则返回 `nullptr`。
215 AActor* ReSpawnActorWithInfo(
216 AActor* ReSpawnActorWithInfo(
217 const FTransform &Transform,
218 FActorDescription thisActorDescription)
219 {
220 FTransform NewTransform = Transform;
221 auto result = ActorDispatcher->ReSpawnActor(NewTransform, thisActorDescription);
222 if (Recorder->IsEnabled())
223 {
224 // 这里可能后续需要添加一些针对录制功能的操作,比如记录Actor重新生成的事件等,但目前代码中没有具体实现,只是预留了位置。
225 }
226
227 return result;
228 }
229
230 /// @brief 在给定的变换信息(`Transform`)位置,根据给定的 `ActorDescription` 创建一个Actor,这是一个供蓝图调用的函数版本
231 /// @param Transform 表示Actor生成位置和姿态的变换信息,以 `FTransform` 类型传递
232 /// @param ActorDescription 描述要创建的Actor的详细信息,用于确定创建何种Actor。
233 /// @return 返回指向创建的Actor的指针(`AActor*` 类型),如果创建失败则返回 `nullptr`。
234 UFUNCTION(BlueprintCallable)
235 UFUNCTION(BlueprintCallable)
236 AActor *SpawnActor(
237 const FTransform &Transform,
238 FActorDescription ActorDescription)
239 {
240 // 调用 `SpawnActorWithInfo` 函数来实际创建Actor,传入 `Transform` 和移动后的 `ActorDescription`(使用 `std::move` 进行右值引用传递,避免不必要的拷贝开销,提高性能),
241 // 然后获取返回结果中的 `Value`(这可能是 `TPair` 类型返回值中的实际Actor相关部分,根据前面 `SpawnActorWithInfo` 的定义推测),再通过 `GetActor` 函数(具体实现应该在相关类中定义)获取最终指向创建的Actor的指针并返回。
242 return SpawnActorWithInfo(Transform, std::move(ActorDescription)).Value->GetActor();
243 }
244
245 // 以下这个宏声明了一个函数,使其可以在UE4的蓝图系统中被调用
246 void AttachActors(
247 AActor *Child,// 参数 `Child`,指向要附着的子Actor的指针
248 AActor *Child,
249 AActor *Parent,// 参数 `InAttachmentType`,用于指定附着的类型,默认值为 `EAttachmentType::Rigid`
250 EAttachmentType InAttachmentType = EAttachmentType::Rigid, // 参数 `SocketName`,用于指定附着的具体插槽名称
251 const FString& SocketName = "");
252
253// 以下这个宏声明了一个函数,使其可以在UE4的蓝图系统中被调用
254 UFUNCTION(BlueprintCallable)
255 bool DestroyActor(AActor *Actor)
256 {
257 FCarlaActor* CarlaActor = FindCarlaActor(Actor);//根据传入的 `Actor` 指针查找对应的 `CarlaActor`
258 // 如果找到了对应的 `CarlaActor`,则获取其Actor标识符
259 if (CarlaActor)
260 {
261 carla::rpc::ActorId ActorId = CarlaActor->GetActorId();
262 return DestroyActor(ActorId);
263 }
264 // 如果没有找到对应的 `CarlaActor`,则直接返回 `false`,表示销毁操作失败。
265 return false;
266 }
267//执行具体的销毁逻辑并处理相关的记录。
268 bool DestroyActor(carla::rpc::ActorId ActorId)
269 {
270 // 如果当前对象是主服务器添加一个表示Actor删除的事件
271 if (bIsPrimaryServer)
272 {
273 GetFrameData().AddEvent(
275 }
276 // 如果录制器(`Recorder`)处于启用状态,则创建一个表示Actor删除的事件对象
277 if (Recorder->IsEnabled())
278 {
279 // recorder event
281 Recorder->AddEvent(std::move(RecEvent));
282 }
283
284 return ActorDispatcher->DestroyActor(ActorId);
285 }
286// 函数用于将指定的Actor设置为睡眠状态
288 {
289 ActorDispatcher->PutActorToSleep(ActorId, this);
290 }
291// 函数用于唤醒指定的处于睡眠状态的Actor
292 void WakeActorUp(carla::rpc::ActorId ActorId)
293 {
294 ActorDispatcher->WakeActorUp(ActorId, this);
295 }
296
297 // ===========================================================================
298 // --Other methods(其他方法)相关部分 ----------------------------------------------------------
299 // ===========================================================================
300
301 // 函数用于创建一个可序列化的对象
302 carla::rpc::Actor SerializeActor(FCarlaActor* CarlaActor) const;
303
304 ///创建一个描述角色的可序列化对象。
305///可以用来序列化注册表中没有的actor
306 carla::rpc::Actor SerializeActor(AActor* Actor) const;
307
308 // ===========================================================================
309 // -- Private methods and members(私有方法和成员变量)相关部分 --------------------------------------------
310 // ===========================================================================
311// 函数用于获取当前的 `ACarlaRecorder` 对象返回一个常量指针外部只能通过这个函数获取该对象进行读取相关信息,不能修改其内容。
312 ACarlaRecorder *GetRecorder() const
313 {
314 return Recorder;
315 }
316// 函数用于设置当前的 `ACarlaRecorder` 对象
317 void SetRecorder(ACarlaRecorder *Rec)
318 {
319 Recorder = Rec;
320 }
321// 函数用于获取与当前录制器(`Recorder`)关联的回放器(`CarlaReplayer`)对象
322 CarlaReplayer *GetReplayer() const
323 {
324 return Recorder->GetReplayer();
325 }
326// 启动录制器
327 std::string StartRecorder(std::string name, bool AdditionalData);
328//获取当前地图的原点信息
329 FIntVector GetCurrentMapOrigin() const { return CurrentMapOrigin; }
330//设置当前地图的原点信息
331 void SetCurrentMapOrigin(const FIntVector& NewOrigin) { CurrentMapOrigin = NewOrigin; }
332//获取当前的帧数据
333 FFrameData& GetFrameData() { return FrameData; }
334//获取当前的传感器管理器
335 FSensorManager& GetSensorManager() { return SensorManager; }
336//表示当前对象是否是主服务器
337 bool bIsPrimaryServer = true;
338
339private:
340
341 friend class ACarlaGameModeBase;// 将 `ACarlaGameModeBase` 类声明为友元类
342 friend class FCarlaEngine;// 将 `FCarlaEngine` 类声明为友元类
343
344 void InitializeAtBeginPlay()//进行初始化相关的操作
345
346 void EndPlay();//执行清理、资源释放等操作
347
348 void RegisterActorFactory(ACarlaActorFactory &ActorFactory)//用于注册一个Actor工厂
349 {
350 ActorDispatcher->Bind(ActorFactory);
351 }
352//尝试创建一个用于回放的Actor对象
353 std::pair<int, FCarlaActor&> TryToCreateReplayerActor(
354 FVector &Location,
355 FVector &Rotation,
356 FActorDescription &ActorDesc,
357 unsigned int desiredId);
358//设置给定的 `CarlaActor` 的物理模拟状态
359 bool SetActorSimulatePhysics(FCarlaActor &CarlaActor, bool bEnabled);
360//设置给定的 `CarlaActor` 的碰撞属性
361 bool SetActorCollisions(FCarlaActor &CarlaActor, bool bEnabled);
362//更新游戏中的各种定时器相关信息
363 // 声明一个函数,用于设置Actor的状态为死亡,具体实现未提供
364bool SetActorDead(FCarlaActor &CarlaActor);
365
366// 每个Tick调用的函数,用于更新计时器
367void TickTimers(float DeltaSeconds)
368{
369 // 累加游戏时间
370 ElapsedGameTime += DeltaSeconds;
371 // 更新视觉游戏时间,用于确保云和其他特效的确定性
372 SetVisualGameTime(VisualGameTime + DeltaSeconds);
373 #if defined(WITH_ROS2) // 如果定义了WITH_ROS2宏,表示支持ROS2集成
374 auto ROS2 = carla::ros2::ROS2::GetInstance(); // 获取ROS2实例
375 if (ROS2->IsEnabled()) // 如果ROS2实例已启用
376 ROS2->SetTimestamp(GetElapsedGameTime()); // 设置ROS2的时间戳
377 #endif
378}
379
380// 一个常量,用于标识ID,初始值设置为0
381const uint64 Id = 0u;
382
383// 累积的游戏时间,用于跟踪仿真的总时间
384double ElapsedGameTime = 0.0;
385
386// 视觉游戏时间,用于云和其他需要确定性效果的元素
387double VisualGameTime = 0.0;
388
389// 可从任何地方访问的属性,存储当前地图的名称
390UPROPERTY(VisibleAnywhere)
391FString MapName;
392
393// 可从任何地方访问的属性,存储当前的Episode设置
394UPROPERTY(VisibleAnywhere)
395FEpisodeSettings EpisodeSettings;
396
397// 可从任何地方访问的属性,存储Actor调度器的指针
398UPROPERTY(VisibleAnywhere)
399UActorDispatcher *ActorDispatcher = nullptr;
400
401// 可从任何地方访问的属性,存储观察者Pawn的指针
402UPROPERTY(VisibleAnywhere)
403APawn *Spectator = nullptr;
404
405// 可从任何地方访问的属性,存储天气控制器的指针
406UPROPERTY(VisibleAnywhere)
407AWeather *Weather = nullptr;
408
409// 可从任何地方访问的属性,存储材质参数集合实例的指针
410UPROPERTY(VisibleAnywhere)
411UMaterialParameterCollectionInstance *MaterialParameters = nullptr;
412
413// 录像机的指针,用于记录和回放仿真
414ACarlaRecorder *Recorder = nullptr;
415
416// 地图的地理参考信息
417carla::geom::GeoLocation MapGeoReference;
418
419// 当前地图的原点位置
420FIntVector CurrentMapOrigin;
421
422// 存储帧数据的结构
423FFrameData FrameData;
424
425// 传感器管理器,用于管理仿真中的传感器
426FSensorManager SensorManager;
427
428// 将语义标签转换为字符串的函数,用于获取相关的标签描述
429FString CarlaGetRelevantTagAsString(const TSet<crp::CityObjectLabel> &SemanticTags);
EAttachmentType
return true
FString CarlaGetRelevantTagAsString(const TSet< crp::CityObjectLabel > &SemanticTags)
const FCarlaActor * FindCarlaActor(const AActor *Actor) const
void WakeActorUp(IdType Id, UCarlaEpisode *CarlaEpisode)
void PutActorToSleep(IdType Id, UCarlaEpisode *CarlaEpisode)
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld Actor
CARLA Game Mode 的基类。
Recorder for the simulation
所有Carla角色的注册表
查看一个参与者和它的属性
Definition CarlaActor.h:23
uint32 IdType
Definition CarlaActor.h:25
IdType GetActorId() const
Definition CarlaActor.h:67
负责将ActorDefinitions绑定到生成函数,以及 维护所有已生成参与者的注册表
static std::shared_ptr< ROS2 > GetInstance()
Definition ROS2.h:51
geom::Transform Transform
uint32_t ActorId
Definition ActorId.h:20
uint32_t stream_id_type
流ID的类型定义。
Definition Types.h:33
CARLA模拟器的主命名空间。
Definition Carla.cpp:139