CARLA
 
载入中...
搜索中...
未找到
CarlaEngine.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" // 包含CARLA的主头文件,提供CARLA基本功能和接口
8#include "Carla/Game/CarlaEngine.h" // 包含CARLA游戏引擎的头文件,管理游戏世界和仿真
9
10#include "Carla/Game/CarlaEpisode.h" // 包含CARLA游戏环节的头文件,代表一个仿真会话
11#include "Carla/Game/CarlaStaticDelegates.h" // 包含CARLA静态委托的头文件,用于注册和管理事件
12#include "Carla/Game/CarlaStatics.h" // 包含CARLA静态变量和函数的头文件,提供全局访问点
13#include "Carla/Lights/CarlaLightSubsystem.h" // 包含CARLA灯光子系统的头文件,管理游戏世界的灯光
14#include "Carla/Recorder/CarlaRecorder.h" // 包含CARLA录制器的头文件,用于记录和回放仿真
15#include "Carla/Settings/CarlaSettings.h" // 包含CARLA设置的头文件,定义仿真的配置参数
16#include "Carla/Settings/EpisodeSettings.h" // 包含CARLA游戏环节设置的头文件,定义环节特定的配置
17
18#include "Runtime/Core/Public/Misc/App.h" // 包含Unreal Engine应用框架的头文件,提供应用程序接口
19#include "PhysicsEngine/PhysicsSettings.h" // 包含物理引擎设置的头文件,定义物理仿真参数
20#include "Carla/MapGen/LargeMapManager.h" // 包含CARLA大地图管理器的头文件,管理大型开放世界地图
21
22#include <compiler/disable-ue4-macros.h> // 禁用Unreal Engine的宏,防止与CARLA代码冲突
23#include <carla/Logging.h> // 包含CARLA日志系统的头文件,提供日志记录功能
24#include <carla/multigpu/primaryCommands.h> // 包含CARLA多GPU主命令的头文件,用于跨GPU通信
25#include <carla/multigpu/commands.h> // 包含CARLA多GPU命令的头文件,用于跨GPU通信
26#include <carla/multigpu/secondary.h> // 包含CARLA多GPU次要功能的头文件,用于跨GPU通信
27#include <carla/multigpu/secondaryCommands.h> // 包含CARLA多GPU次要命令的头文件,用于跨GPU通信
28#include <carla/ros2/ROS2.h> // 包含CARLA ROS 2接口的头文件,提供ROS 2集成功能
29#include <carla/streaming/EndPoint.h> // 包含CARLA流媒体端点的头文件,提供流媒体传输功能
30#include <carla/streaming/Server.h> // 包含CARLA流媒体服务器的头文件,提供流媒体传输服务
31#include <compiler/enable-ue4-macros.h> // 启用Unreal Engine的宏
32
33#include <thread> // 包含C++标准库线程的头文件,提供线程管理功能
34
35// =============================================================================
36// -- Static local methods -----------------------------------------------------
37// =============================================================================
38
39// 初始化静态变量,用于计数帧数
41
42// 静态函数,用于获取RPC服务器的线程数
44{
45 // 返回硬件支持的线程数与4的最大值,然后减去2,确保有足够的线程处理其他任务
46 return std::max(std::thread::hardware_concurrency(), 4u) - 2u;
47}
48
49// 静态函数,用于获取固定的仿真时间间隔
50static TOptional<double> FCarlaEngine_GetFixedDeltaSeconds()
51{
52 // 如果正在基准测试,则返回固定的仿真时间间隔,否则返回空值
53 return FApp::IsBenchmarking() ? FApp::GetFixedDeltaTime() : TOptional<double>{};
54}
55
56// 静态函数,用于设置固定的仿真时间间隔
57static void FCarlaEngine_SetFixedDeltaSeconds(TOptional<double> FixedDeltaSeconds)
58{
59 // 如果提供了固定的时间间隔,则设置基准测试模式和固定的时间间隔,否则不进行设置
60 FApp::SetBenchmarking(FixedDeltaSeconds.IsSet());
61 FApp::SetFixedDeltaTime(FixedDeltaSeconds.Get(0.0));
62}
63
64// =============================================================================
65// -- FCarlaEngine -------------------------------------------------------------
66// =============================================================================
67
68// FCarlaEngine类的析构函数,负责清理资源和结束仿真
70{
71 // 检查成员变量bIsRunning是否为true,表示引擎是否正在运行
72 // 如果正在运行,则需要执行清理操作,例如结束仿真、释放资源等
73}
74
75 if (bIsRunning)
76 {
77 // 如果定义了WITH_ROS2宏,表示项目配置了ROS2(Robot Operating System 2)支持
78 #if defined(WITH_ROS2)
80 // 检查ROS2是否已启用
81 if (ROS2->IsEnabled())
82 ROS2->Shutdown();
83 #endif
84 FWorldDelegates::OnWorldTickStart.Remove(OnPreTickHandle);
85 FWorldDelegates::OnWorldPostActorTick.Remove(OnPostTickHandle);
86 FCarlaStaticDelegates::OnEpisodeSettingsChange.Remove(OnEpisodeSettingsChangeHandle);
87 }
88}
89
91{
92 TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
93 if (!bIsRunning)
94 {
95 const auto StreamingPort = Settings.StreamingPort;
96 const auto SecondaryPort = Settings.SecondaryPort;
97 const auto PrimaryIP = Settings.PrimaryIP;
98 const auto PrimaryPort = Settings.PrimaryPort;
99
100 auto BroadcastStream = Server.Start(Settings.RPCPort, StreamingPort, SecondaryPort);
102
103 WorldObserver.SetStream(BroadcastStream);
104
105 OnPreTickHandle = FWorldDelegates::OnWorldTickStart.AddRaw(
106 this,
108 OnPostTickHandle = FWorldDelegates::OnWorldPostActorTick.AddRaw(
109 this,
112 this,
114
115 bIsRunning = true;
116
117 // 将此作为备用服务器转换进行检查
118 if (!PrimaryIP.empty())
119 {
120 // 我们是备用服务器,正在连接到主服务器
121 bIsPrimaryServer = false;
122
123 // 当命令来自主服务器时,命令执行器是指负责处理和执行这些命令的组件或模块
124 auto CommandExecutor = [=](carla::multigpu::MultiGPUCommand Id, carla::Buffer Data) {
125 struct CarlaStreamBuffer : public std::streambuf
126 {
127 CarlaStreamBuffer(char *buf, std::size_t size) { setg(buf, buf, buf + size); }
128 };
129 switch (Id) {
131 {
133 {
134 TRACE_CPUPROFILER_EVENT_SCOPE_STR("MultiGPUCommand::SEND_FRAME");
135 // 将缓冲区中的帧数据转换为输入流
136 CarlaStreamBuffer TempStream((char *) Data.data(), Data.size());
137 std::istream InStream(&TempStream);
138 GetCurrentEpisode()->GetFrameData().Read(InStream);
139 {
140 TRACE_CPUPROFILER_EVENT_SCOPE_STR("FramesToProcess.emplace_back");
141 std::lock_guard<std::mutex> Lock(FrameToProcessMutex);
142 FramesToProcess.emplace_back(GetCurrentEpisode()->GetFrameData());
143 }
144 }
145 // 强制进行一次进行单位时间操作
146 Server.Tick();
147 break;
148 }
150 {
151 FString FinalPath((char *) Data.data());
153 {
154 UGameplayStatics::OpenLevel(GetCurrentEpisode()->GetWorld(), *FinalPath, true);
155 }
156
157 break;
158 }
160 {
161 // 获取传感器 ID
162 auto sensor_id = *(reinterpret_cast<carla::streaming::detail::stream_id_type *>(Data.data()));
163 // 查询调度器
165 carla::Buffer buf(reinterpret_cast<unsigned char *>(&token), (size_t) sizeof(token));
166 carla::log_info("responding with a token for port ", token.get_port());
167 Secondary->Write(std::move(buf));
168 break;
169 }
171 {
172 std::string msg("Yes, I'm alive");
173 carla::Buffer buf((unsigned char *) msg.c_str(), (size_t) msg.size());
174 carla::log_info("responding is alive command");
175 Secondary->Write(std::move(buf));
176 break;
177 }
179 {
180 // 获取传感器 ID
181 auto sensor_id = *(reinterpret_cast<carla::streaming::detail::stream_id_type *>(Data.data()));
182 // 查询调度器
184 // 返回一个 'true'
185 bool res = true;
186 carla::Buffer buf(reinterpret_cast<unsigned char *>(&res), (size_t) sizeof(bool));
187 carla::log_info("responding ENABLE_ROS with a true");
188 Secondary->Write(std::move(buf));
189 break;
190 }
192 {
193 // 获取传感器 ID
194 auto sensor_id = *(reinterpret_cast<carla::streaming::detail::stream_id_type *>(Data.data()));
195 // 查询调度器
197 // 返回一个 'true'
198 bool res = true;
199 carla::Buffer buf(reinterpret_cast<unsigned char *>(&res), (size_t) sizeof(bool));
200 carla::log_info("responding DISABLE_ROS with a true");
201 Secondary->Write(std::move(buf));
202 break;
203 }
205 {
206 // 获取传感器 ID
207 auto sensor_id = *(reinterpret_cast<carla::streaming::detail::stream_id_type *>(Data.data()));
208 // 查询调度器
209 bool res = Server.GetStreamingServer().IsEnabledForROS(sensor_id);
210 carla::Buffer buf(reinterpret_cast<unsigned char *>(&res), (size_t) sizeof(bool));
211 carla::log_info("responding IS_ENABLED_ROS with: ", res);
212 Secondary->Write(std::move(buf));
213 break;
214 }
215 }
216 };
217
218 Secondary = std::make_shared<carla::multigpu::Secondary>(PrimaryIP, PrimaryPort, CommandExecutor);
219 Secondary->Connect();
220 // 将此服务器设置为同步模式
221 bSynchronousMode = true;
222 }
223 else
224 {
225 // 我们是主服务器,正在启动服务器
226 bIsPrimaryServer = true;
228 SecondaryServer->SetNewConnectionCallback([this]()
229 {
230 this->bNewConnection = true;
231 UE_LOG(LogCarla, Log, TEXT("New secondary connection detected"));
232 });
233 }
234 }
235
236 //创建 ROS2 管理器
237 #if defined(WITH_ROS2)
238 if (Settings.ROS2)
239 {
240 auto ROS2 = carla::ros2::ROS2::GetInstance();
241 ROS2->Enable(true);
242 }
243 #endif
244
245 bMapChanged = true;
246}
247
248void FCarlaEngine::NotifyBeginEpisode(UCarlaEpisode &Episode)
249{
250 TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
251 Episode.EpisodeSettings.FixedDeltaSeconds = FCarlaEngine_GetFixedDeltaSeconds();
252 CurrentEpisode = &Episode;
253
254 // 重置地图设置
255 UWorld* World = CurrentEpisode->GetWorld();
257 if (LargeMapManager)
258 {
261 }
262
263 if (!bIsPrimaryServer)
264 {
265 // 将此次要服务器设置为无渲染模式
267 }
268
269 CurrentEpisode->ApplySettings(CurrentSettings);
270
271 ResetFrameCounter(GFrameNumber);
272
273 // 建立Episode和Recorder之间的连接
274 if (Recorder)
275 {
276 Recorder->SetEpisode(&Episode);
277 Episode.SetRecorder(Recorder);
279 }
280
281 Server.NotifyBeginEpisode(Episode);
282
283 Episode.bIsPrimaryServer = bIsPrimaryServer;
284}
285
291
292void FCarlaEngine::OnPreTick(UWorld *, ELevelTick TickType, float DeltaSeconds)
293{
294 TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
295 if (TickType == ELevelTick::LEVELTICK_All)
296 {
297
299 {
300 if (CurrentEpisode && !bSynchronousMode && SecondaryServer->HasClientsConnected())
301 {
302 // 设置为同步模式。
306 CurrentEpisode->ApplySettings(CurrentSettings);
307 }
308
309 // 处理RPC命令
310 do
311 {
312 Server.RunSome(1u);
313 }
315 }
316 else
317 {
318 // 处理帧数据
319 do
320 {
321 Server.RunSome(1u);
322 }
323 while (!FramesToProcess.size());
324 }
325
326 // 更新帧计数器
328
329 if (CurrentEpisode)
330 {
331 CurrentEpisode->TickTimers(DeltaSeconds);
332
333 if (!bIsPrimaryServer)
334 {
335 if (FramesToProcess.size())
336 {
337 TRACE_CPUPROFILER_EVENT_SCOPE_STR("FramesToProcess.PlayFrameData");
338 std::lock_guard<std::mutex> Lock(FrameToProcessMutex);
339 FramesToProcess.front().PlayFrameData(CurrentEpisode, MappedId);
340 FramesToProcess.erase(FramesToProcess.begin()); // 移除第一个元素
341 }
342 }
343 }
344 }
345}
346
347
348void FCarlaEngine::OnPostTick(UWorld *World, ELevelTick TickType, float DeltaSeconds)
349{
350 TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
351 // 标记录制/回放系统
352 if (GetCurrentEpisode())
353 {
355 {
356 if (SecondaryServer->HasClientsConnected()) {
357 GetCurrentEpisode()->GetFrameData().GetFrameData(GetCurrentEpisode(), true, bNewConnection);
358 bNewConnection = false;
359 std::ostringstream OutStream;
360 GetCurrentEpisode()->GetFrameData().Write(OutStream);
361
362 // 将帧数据发送到次级服务器
363 std::string Tmp(OutStream.str());
364 SecondaryServer->GetCommander().SendFrameData(carla::Buffer(std::move((unsigned char *) Tmp.c_str()), (size_t) Tmp.size()));
365
366 GetCurrentEpisode()->GetFrameData().Clear();
367 }
368 }
369
370 auto* EpisodeRecorder = GetCurrentEpisode()->GetRecorder();
371 if (EpisodeRecorder)
372 {
373 EpisodeRecorder->Ticking(DeltaSeconds);
374 }
375 }
376
377 if ((TickType == ELevelTick::LEVELTICK_All) && (CurrentEpisode != nullptr))
378 {
379 // 查找光子系统
380 bool LightUpdatePending = false;
381 if (World)
382 {
383 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
384 if (CarlaLightSubsystem)
385 {
386 LightUpdatePending = CarlaLightSubsystem->IsUpdatePending();
387 }
388 }
389
390 // 发送 worldsnapshot
391 //worldsnapshot:
392 //1·游戏开发:在游戏中,"world snapshot" 可以用来记录游戏的状态,保存玩家的位置、状态、物品等信息,以便后续恢复。
393 //2·虚拟现实和增强现实:在这些环境中,世界快照可以帮助记录用户的位置和交互,便于分析和重现体验。
394 WorldObserver.BroadcastTick(*CurrentEpisode, DeltaSeconds, bMapChanged, LightUpdatePending);
395 CurrentEpisode->GetSensorManager().PostPhysTick(World, TickType, DeltaSeconds);
397 }
398}
399
401{
403
405
406 if (GEngine && GEngine->GameViewport)
407 {
408 GEngine->GameViewport->bDisableWorldRendering = Settings.bNoRenderingMode;
409 }
410
412
413 // 为物理子步设置参数
414 UPhysicsSettings* PhysSett = UPhysicsSettings::Get();
415 PhysSett->bSubstepping = Settings.bSubstepping;
416 PhysSett->MaxSubstepDeltaTime = Settings.MaxSubstepDeltaTime;
417 PhysSett->MaxSubsteps = Settings.MaxSubsteps;
418
419 UWorld* World = CurrentEpisode->GetWorld();
421 if (LargeMapManager)
422 {
423 LargeMapManager->SetLayerStreamingDistance(Settings.TileStreamingDistance);
424 LargeMapManager->SetActorStreamingDistance(Settings.ActorActiveDistance);
425 }
426}
427
UE_LOG(LogCarla, Log, TEXT("UActorDispatcher::Destroying actor: '%s' %x"), *Id, Actor)
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld * World
static void FCarlaEngine_SetFixedDeltaSeconds(TOptional< double > FixedDeltaSeconds)
static uint32 FCarlaEngine_GetNumberOfThreadsForRPCServer()
static TOptional< double > FCarlaEngine_GetFixedDeltaSeconds()
CarlaReplayer * GetReplayer(void)
void SetEpisode(UCarlaEpisode *ThisEpisode)
float GetLayerStreamingDistance() const
void SetActorStreamingDistance(float Distance)
void SetLayerStreamingDistance(float Distance)
float GetActorStreamingDistance() const
void CheckPlayAfterMapLoaded(void)
void OnEpisodeSettingsChanged(const FEpisodeSettings &Settings)
FDelegateHandle OnEpisodeSettingsChangeHandle
std::shared_ptr< carla::multigpu::Router > SecondaryServer
std::mutex FrameToProcessMutex
void OnPreTick(UWorld *World, ELevelTick TickType, float DeltaSeconds)
static uint64_t FrameCounter
Definition CarlaEngine.h:35
void ResetSimulationState()
FWorldObserver WorldObserver
FCarlaServer Server
static void ResetFrameCounter(uint64_t Value=0)
Definition CarlaEngine.h:86
void NotifyEndEpisode()
std::unordered_map< uint32_t, uint32_t > MappedId
FEpisodeSettings CurrentSettings
bool bNewConnection
static uint64_t UpdateFrameCounter()
Definition CarlaEngine.h:74
UCarlaEpisode * CurrentEpisode
std::vector< FFrameData > FramesToProcess
void NotifyBeginEpisode(UCarlaEpisode &Episode)
void NotifyInitGame(const UCarlaSettings &Settings)
ACarlaRecorder * Recorder
bool bIsPrimaryServer
bool bSynchronousMode
FDelegateHandle OnPreTickHandle
FDelegateHandle OnPostTickHandle
std::shared_ptr< carla::multigpu::Secondary > Secondary
UCarlaEpisode * GetCurrentEpisode()
Definition CarlaEngine.h:56
void OnPostTick(UWorld *World, ELevelTick TickType, float DeltaSeconds)
bool TickCueReceived()
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
void RunSome(uint32 Milliseconds)
carla::streaming::Server & GetStreamingServer()
void NotifyEndEpisode()
void NotifyBeginEpisode(UCarlaEpisode &Episode)
FDataMultiStream Start(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
void AsyncRun(uint32 NumberOfWorkerThreads)
static FOnEpisodeSettingsChange OnEpisodeSettingsChange
void SetStream(FDataMultiStream InStream)
Replace the Stream associated with this sensor.
void BroadcastTick(const UCarlaEpisode &Episode, float DeltaSeconds, bool MapChange, bool PendingLightUpdate)
Send a message to every connected client with the info about the given Episode.
Carla 的全局设置
uint32 StreamingPort
流媒体端口的设置。
std::string PrimaryIP
设置要连接的主服务器的IP和端口。
uint32 RPCPort
用于监听客户端连接的世界端口。
uint32 SecondaryPort
辅助服务器端口的设置。
static ALargeMapManager * GetLargeMapManager(const UObject *WorldContextObject)
一块原始数据。 请注意,如果需要更多容量,则会分配一个新的内存块,并 删除旧的内存块。这意味着默认情况下,缓冲区只能增长。要释放内存,使用 clear 或 pop。
static std::shared_ptr< ROS2 > GetInstance()
Definition ROS2.h:51
token_type GetToken(stream_id sensor_id)
bool IsEnabledForROS(stream_id sensor_id)
void EnableForROS(stream_id sensor_id)
void DisableForROS(stream_id sensor_id)
静态断言,用于确保token_data结构体的大小与Token::data的大小相同。
auto get_port() const
获取端口号。
uint32_t stream_id_type
流ID的类型定义。
Definition Types.h:33
static void log_info(Args &&... args)
Definition Logging.h:86