CARLA
 
载入中...
搜索中...
未找到
CarlaServer.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"
11#include "EngineUtils.h"
12#include "Components/SkeletalMeshComponent.h"
13#include "Components/SkinnedMeshComponent.h"
14#include "Components/SceneComponent.h"
15#include "Engine/SkeletalMesh.h"
16#include "Engine/SkeletalMeshSocket.h"
17
26#include "GameFramework/CharacterMovementComponent.h"
27#include "Carla/Game/Tagger.h"
33#include "CarlaServerResponse.h"
35#include "Misc/FileHelper.h"
36
38#include <carla/Functional.h>
40#include <carla/Version.h>
42#include <carla/rpc/Actor.h>
46#include <carla/rpc/Command.h>
54#include <carla/rpc/MapInfo.h>
55#include <carla/rpc/MapLayer.h>
56#include <carla/rpc/Response.h>
57#include <carla/rpc/Server.h>
58#include <carla/rpc/String.h>
59#include <carla/rpc/Transform.h>
60#include <carla/rpc/Vector2D.h>
61#include <carla/rpc/Vector3D.h>
75#include <carla/rpc/Texture.h>
78
79#include <vector>
80#include <atomic>
81#include <map>
82#include <tuple>
83
84template <typename T>
86
87// =============================================================================
88// -- 静态局部函数 --------------------------------------------------------------
89// =============================================================================
90
91// 通过数组构建向量
92template <typename T, typename Other>
93static std::vector<T> MakeVectorFromTArray(const TArray<Other> &Array)
94{
95 return {Array.GetData(), Array.GetData() + Array.Num()};
96}
97
98// =============================================================================
99// -- FCarlaServer::FPimpl -----------------------------------------------
100// =============================================================================
101
103{
104public:
105
106 FPimpl(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
107 : Server(RPCPort),
108 StreamingServer(StreamingPort),
109 BroadcastStream(StreamingServer.MakeStream())
110 {
111 // 我们需要从路由中创建指向 carla::multigpu::Router 类型的智能指针 shared_ptr,以便一些处理程序能够存活
112 // 使用make_shared函数可以减少内存分配的次数,因为它会在一次内存分配中同时分配智能指针对象和指向的对象。
113 // std::make_shared函数会自动分配内存并构造对象,因此不需要手动调用new操作符
114 SecondaryServer = std::make_shared<carla::multigpu::Router>(SecondaryPort); // 从服务器
115 SecondaryServer->SetCallbacks(); // 设置从服务器的回调函数
116 BindActions();
117 }
118
119 std::shared_ptr<carla::multigpu::Router> GetSecondaryServer() {
120 return SecondaryServer;
121 }
122
123 /// 仿真中所有活动的交通管理器对 < port, ip > 的映射
124 std::map<uint16_t, std::string> TrafficManagerInfo;
125
127
129
131
132 std::shared_ptr<carla::multigpu::Router> SecondaryServer;
133
134 UCarlaEpisode *Episode = nullptr;
135
136 std::atomic_size_t TickCuesReceived { 0u }; // 收到的节拍提示
137
138private:
139
140 void BindActions();
141};
142
143// =============================================================================
144// -- 定义辅助宏 ----------------------------------------------------------------
145// =============================================================================
146// 检查当前是否在游戏线程中执行,仅在编辑器模式下有效
147#if WITH_EDITOR
148# define CARLA_ENSURE_GAME_THREAD() check(IsInGameThread());// 在编辑器中,确保代码在游戏线程中执行
149#else
150# define CARLA_ENSURE_GAME_THREAD()// 在非编辑器模式下,此宏不做任何事情
151#endif // WITH_EDITOR
152// 定义一个宏,用于记录错误消息并返回一个ResponseError对象
153#define RESPOND_ERROR(str) { \
154 UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), TEXT(str)); \
155 return carla::rpc::ResponseError(str); }
156
157// 定义一个宏,用于记录由FString表示的错误消息并返回一个ResponseError对象
158#define RESPOND_ERROR_FSTRING(fstr) { \
159 UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), *fstr); \
160 return carla::rpc::ResponseError(carla::rpc::FromFString(fstr)); }
161// 定义一个宏,用于确保有一个有效的CARLA Episode对象,并检查是否在游戏线程中
162#define REQUIRE_CARLA_EPISODE() \
163 CARLA_ENSURE_GAME_THREAD(); \
164 if (Episode == nullptr) { RESPOND_ERROR("episode not ready"); }
165// 定义一个函数,用于构造并返回一个包含函数名、错误消息和额外信息的ResponseError对象
167 const FString& FuncName,
168 const FString& ErrorMessage,
169 const FString& ExtraInfo = "")
170{
171 FString TotalMessage = "Responding error from function " + FuncName + ": " +
172 ErrorMessage + ". " + ExtraInfo;// 拼接完整的错误消息
173 UE_LOG(LogCarlaServer, Log, TEXT("%s"), *TotalMessage);// 记录完整错误消息到日志
174 return carla::rpc::ResponseError(carla::rpc::FromFString(TotalMessage)); // 返回一个包含完整错误消息的ResponseError对象
175}
176// 定义一个重载函数,用于处理ECarlaServerResponse枚举值作为错误代码的情况
178 const FString& FuncName,
179 const ECarlaServerResponse& Error,
180 const FString& ExtraInfo = "")
181{
182 return RespondError(FuncName, CarlaGetStringError(Error), ExtraInfo);
183}
184
185//将自定义函数绑定到 CARLA 模拟器中的 RPC 服务器,以响应来自模拟器的请求或事件
186//通过指定同步或异步模式,控制这些函数是如何被调用的,这对于处理实时数据或模拟中的事件非常重要
188{
189public:
190
191 constexpr ServerBinder(const char *name, carla::rpc::Server &srv, bool sync)
192 : _name(name),
193 _server(srv),
194 _sync(sync) {}
195
196 template <typename FuncT>
197 auto operator<<(FuncT func)
198 {
199 if (_sync)
200 {
201 _server.BindSync(_name, func);
202 }
203 else
204 {
205 _server.BindAsync(_name, func);
206 }
207 return func;
208 }
209
210private:
211
212 const char *_name;
213
215
216 bool _sync;
217};
218
219#define BIND_SYNC(name) auto name = ServerBinder(# name, Server, true)
220#define BIND_ASYNC(name) auto name = ServerBinder(# name, Server, false)
221
222// =============================================================================
223// -- 绑定操作 -------------------------------------------------------------
224// =============================================================================
225
227{
228 namespace cr = carla::rpc;
229 namespace cg = carla::geom;
230
231 /// 寻找运行在指定端口上的流量管理器
232 BIND_SYNC(is_traffic_manager_running) << [this] (uint16_t port) ->R<bool>
233 {
234 return (TrafficManagerInfo.find(port) != TrafficManagerInfo.end());
235 };
236
237 /// 获取一个包含流量管理器的 <IP, port> 的键值对,该流量管理器运行在指定端口上。
238 /// 如果没有流量管理器在运行,则返回的键值对为 ("", 0)。
239 BIND_SYNC(get_traffic_manager_running) << [this] (uint16_t port) ->R<std::pair<std::string, uint16_t>>
240 {
241 auto it = TrafficManagerInfo.find(port);
242 if(it != TrafficManagerInfo.end()) {
243 return std::pair<std::string, uint16_t>(it->second, it->first);
244 }
245 return std::pair<std::string, uint16_t>("",0);
246 };
247
248 /// 添加在<IP,端口>上运行的新Traffic Manager
249 BIND_SYNC(add_traffic_manager_running) << [this] (std::pair<std::string, uint16_t> trafficManagerInfo) ->R<bool>
250 {
251 uint16_t port = trafficManagerInfo.second;
252 auto it = TrafficManagerInfo.find(port);
253 if(it == TrafficManagerInfo.end()) {
254 TrafficManagerInfo.insert(
255 std::pair<uint16_t, std::string>(port, trafficManagerInfo.first));
256 return true;
257 }
258 return false;
259
260 };
261// 绑定一个同步RPC函数,用于销毁指定端口的交通管理器
262 BIND_SYNC(destroy_traffic_manager) << [this] (uint16_t port) ->R<bool>
263 {
264 // 在TrafficManagerInfo容器中查找指定端口的交通管理器信息
265 auto it = TrafficManagerInfo.find(port);
266 if(it != TrafficManagerInfo.end()) {
267 TrafficManagerInfo.erase(it);
268 return true;
269 }
270 return false;
271 };
272// 绑定一个异步RPC函数,用于获取CARLA的版本号
273 BIND_ASYNC(version) << [] () -> R<std::string>
274 {
275 return carla::version();
276 };
277
278 // ~~ 时钟周期 ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
279
280 BIND_SYNC(tick_cue) << [this]() -> R<uint64_t>
281 {
282 TRACE_CPUPROFILER_EVENT_SCOPE(TickCueReceived);
283 auto Current = FCarlaEngine::GetFrameCounter();
284 (void)TickCuesReceived.fetch_add(1, std::memory_order_release);
285 return Current + 1;
286 };
287
288 // ~~ 加载新章节 ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
289// 使用BIND_ASYNC宏来异步绑定一个函数,这里的函数是获取所有可用的地图名称
290 BIND_ASYNC(get_available_maps) << [this]() -> R<std::vector<std::string>>
291 {// 通过UCarlaStatics类的静态方法GetAllMapNames获取所有地图名称的列表
292 const auto MapNames = UCarlaStatics::GetAllMapNames();
293 // 创建一个std::vector来存储过滤后的地图名称
294 std::vector<std::string> result;
295 // 为result预留足够的空间,以提高性能(避免多次内存分配)
296 // Num()是FString或类似容器的成员函数,返回容器中元素的数量
297 result.reserve(MapNames.Num());
298 // 遍历所有地图名称
299 for (const auto &MapName : MapNames)
300 {// 如果地图名称包含"/Sublevels/",则跳过该地图(可能是子地图或层级地图)
301 if (MapName.Contains("/Sublevels/"))
302 continue;
303 if (MapName.Contains("/BaseMap/"))
304 continue;
305 if (MapName.Contains("/BaseLargeMap/"))
306 continue;
307 if (MapName.Contains("_Tile_"))
308 continue;
309// 如果地图名称通过了所有过滤条件,则将其添加到结果列表中
310// cr::FromFString是一个将FString转换为std::string的函数
311 result.emplace_back(cr::FromFString(MapName));
312 }
313 // 返回过滤后的地图名称列表
314 return result;
315 };
316
317 BIND_SYNC(load_new_episode) << [this](const std::string &map_name, const bool reset_settings, cr::MapLayer MapLayers) -> R<void>
318 {
319 REQUIRE_CARLA_EPISODE();//检查当前是否存在有效的 CARLA 场景。如果不存在,它会抛出异常或返回错误
320
321 UCarlaGameInstance* GameInstance = UCarlaStatics::GetGameInstance(Episode->GetWorld());
322 if (!GameInstance)
323 {
324 RESPOND_ERROR("unable to find CARLA game instance");
325 }
326 GameInstance->SetMapLayer(static_cast<int32>(MapLayers));
327
328 if(!Episode->LoadNewEpisode(cr::ToFString(map_name), reset_settings))
329 {
330 FString Str(TEXT("Map '"));
331 Str += cr::ToFString(map_name);
332 Str += TEXT("' not found");
334 }
335
336 return R<void>::Success();
337 };
338// 使用宏或模板函数绑定同步函数load_map_layer到下面的lambda表达式
339 BIND_SYNC(load_map_layer) << [this](cr::MapLayer MapLayers) -> R<void>
340 {
341// 检查当前是否有一个有效的CARLA模拟场景(episode)正在运行
343// 从当前运行的模拟世界中获取CARLA游戏模式(GameMode)的实例
344 // ACarlaGameModeBase是CARLA中定义的游戏模式基类
346 if (!GameMode)
347 {
348 RESPOND_ERROR("unable to find CARLA game mode");
349 }
350 // 调用游戏模式的LoadMapLayer函数,加载指定的地图层
351 // 将枚举类型转换为整型,因为函数可能需要整型参数
352 GameMode->LoadMapLayer(static_cast<int32>(MapLayers));
353 // 函数执行成功,返回成功状态的R<void>对象
354 return R<void>::Success();
355 };
356
357 BIND_SYNC(unload_map_layer) << [this](cr::MapLayer MapLayers) -> R<void>
358 {
360
362 if (!GameMode)
363 {
364 RESPOND_ERROR("unable to find CARLA game mode");
365 }
366 GameMode->UnLoadMapLayer(static_cast<int32>(MapLayers));
367
368 return R<void>::Success();
369 };
370
371 BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, cr::OpendriveGenerationParameters Params) -> R<void>
372 {
374 //使用提供的OpenDRIVE数据和参数加载一个新的模拟场景
375 // cr::ToLongFString(opendrive)将std::string转换为CARLA内部使用的FString类型
376 // Params是OpenDRIVE生成参数,用于自定义加载过程
377 if (!Episode->LoadNewOpendriveEpisode(cr::ToLongFString(opendrive), Params))
378 {
379 RESPOND_ERROR("opendrive could not be correctly parsed");
380 }
381 return R<void>::Success();
382 };
383
384 BIND_SYNC(apply_color_texture_to_objects) << [this](
385 const std::vector<std::string> &actors_name,// 场景中要应用纹理的对象名称列表
386 const cr::MaterialParameter& parameter,// 材料参数,用于定义纹理的应用方式
387 const cr::TextureColor& Texture) -> R<void>// 纹理颜色参数
388 {
389 // 这是一个lambda函数或函数对象的定义,被设计为异步执行
390
391// 返回一个R<void>类型的对象,这通常表示一个异步操作的结果
392 REQUIRE_CARLA_EPISODE();// 检查当前是否有一个有效的CARLA模拟器会话正在运行
394 if (!GameMode)
395 {
396 RESPOND_ERROR("unable to find CARLA game mode");
397 }
398 TArray<AActor*> ActorsToPaint;// 创建一个数组来存储找到的actor指针
399 for(const std::string& actor_name : actors_name)
400 {
401 AActor* ActorToPaint = GameMode->FindActorByName(cr::ToFString(actor_name));
402 if (ActorToPaint)
403 {
404 ActorsToPaint.Add(ActorToPaint);
405 }
406 }
407
408 if(!ActorsToPaint.Num())
409 {
410 RESPOND_ERROR("unable to find Actor to apply the texture");
411 }
412
413 UTexture2D* UETexture = GameMode->CreateUETexture(Texture);
414
415 for(AActor* ActorToPaint : ActorsToPaint)
416 {
417 GameMode->ApplyTextureToActor(
418 ActorToPaint,
419 UETexture,
420 parameter);
421 }
422 return R<void>::Success();
423 };
424
425 BIND_SYNC(apply_float_color_texture_to_objects) << [this](
426 const std::vector<std::string> &actors_name,
427 const cr::MaterialParameter& parameter,
428 const cr::TextureFloatColor& Texture) -> R<void>
429 {
432 if (!GameMode)
433 {
434 RESPOND_ERROR("unable to find CARLA game mode");
435 }
436 TArray<AActor*> ActorsToPaint;
437 for(const std::string& actor_name : actors_name)
438 {
439 AActor* ActorToPaint = GameMode->FindActorByName(cr::ToFString(actor_name));
440 if (ActorToPaint)
441 {
442 ActorsToPaint.Add(ActorToPaint);
443 }
444 }
445
446 if(!ActorsToPaint.Num())
447 {
448 RESPOND_ERROR("unable to find Actor to apply the texture");
449 }
450
451 UTexture2D* UETexture = GameMode->CreateUETexture(Texture);
452
453 for(AActor* ActorToPaint : ActorsToPaint)
454 {
455 GameMode->ApplyTextureToActor(
456 ActorToPaint,
457 UETexture,
458 parameter);
459 }
460 return R<void>::Success();
461 };
462
463 BIND_SYNC(get_names_of_all_objects) << [this]() -> R<std::vector<std::string>>
464 {
467 if (!GameMode)
468 {
469 RESPOND_ERROR("unable to find CARLA game mode");
470 }
471 TArray<FString> NamesFString = GameMode->GetNamesOfAllActors();
472 std::vector<std::string> NamesStd;
473 for (const FString &Name : NamesFString)
474 {
475 NamesStd.emplace_back(cr::FromFString(Name));
476 }
477 return NamesStd;
478 };
479
480 // ~~ 章节设置与信息 ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
481
482 BIND_SYNC(get_episode_info) << [this]() -> R<cr::EpisodeInfo>
483 {
485 return cr::EpisodeInfo{Episode->GetId(), BroadcastStream.token()};
486 };
487
488 BIND_SYNC(get_map_info) << [this]() -> R<cr::MapInfo>
489 {
492 const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
493 FString FullMapPath = GameMode->GetFullMapPath();
494 FString MapDir = FullMapPath.RightChop(FullMapPath.Find("Content/", ESearchCase::CaseSensitive) + 8);
495 MapDir += "/" + Episode->GetMapName();
496 return cr::MapInfo{
497 cr::FromFString(MapDir),
498 MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
499 };
500
501 BIND_SYNC(get_map_data) << [this]() -> R<std::string>
502 {
504 return cr::FromLongFString(UOpenDrive::GetXODR(Episode->GetWorld()));
505 };
506
507 BIND_SYNC(get_navigation_mesh) << [this]() -> R<std::vector<uint8_t>>
508 {
510 auto FileContents = FNavigationMesh::Load(Episode->GetMapName());
511 // 进行内存复制(从TArray到std::vector)
512 std::vector<uint8_t> Result(FileContents.Num());
513 memcpy(&Result[0], FileContents.GetData(), FileContents.Num());
514 return Result;
515 };
516
517 BIND_SYNC(get_required_files) << [this](std::string folder = "") -> R<std::vector<std::string>>
518 {
520
521 // 检查路径是否以斜杠结尾,如果没有则添加它
522 if (folder[folder.size() - 1] != '/' && folder[folder.size() - 1] != '\\') {
523 folder += "/";
524 }
525
526 // 获取地图文件夹的绝对路径,并检查它是否位于其自身的文件夹内
528 const auto mapDir = GameMode->GetFullMapPath();
529 const auto folderDir = mapDir + "/" + folder.c_str();
530 const auto fileName = mapDir.EndsWith(Episode->GetMapName()) ? "*" : Episode->GetMapName();
531
532 // 从地图中找到所有的xodr和bin文件
533 TArray<FString> Files;
534 IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName + ".xodr"), true, false, false);
535 IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName + ".bin"), true, false, false);
536
537 // 移除路径的起始部分直到内容文件夹,并将每个文件放入结果中
538 std::vector<std::string> result;
539 for (auto File : Files) {
540 File.RemoveFromStart(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
541 result.emplace_back(TCHAR_TO_UTF8(*File));
542 }
543
544 return result;
545 };
546 BIND_SYNC(request_file) << [this](std::string name) -> R<std::vector<uint8_t>>
547 {
549
550 // 获取文件的绝对路径
551 FString path(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
552 path.Append(name.c_str());
553
554 // 将文件的二进制数据复制到结果中并返回它
555 TArray<uint8_t> Content;
556 FFileHelper::LoadFileToArray(Content, *path, 0);
557 std::vector<uint8_t> Result(Content.Num());
558 memcpy(&Result[0], Content.GetData(), Content.Num());
559
560 return Result;
561 };
562
563 BIND_SYNC(get_episode_settings) << [this]() -> R<cr::EpisodeSettings>
564 {
566 return cr::EpisodeSettings{Episode->GetSettings()};
567 };
568
569 BIND_SYNC(set_episode_settings) << [this](
570 const cr::EpisodeSettings &settings) -> R<uint64_t>
571 {
573 Episode->ApplySettings(settings);
574 StreamingServer.SetSynchronousMode(settings.synchronous_mode);
575
577 if (!GameMode)
578 {
579 RESPOND_ERROR("unable to find CARLA game mode");
580 }
581 ALargeMapManager* LargeMap = GameMode->GetLMManager();
582 if (LargeMap)
583 {
584 LargeMap->ConsiderSpectatorAsEgo(settings.spectator_as_ego);
585 }
586
588 };
589
590 BIND_SYNC(get_actor_definitions) << [this]() -> R<std::vector<cr::ActorDefinition>>
591 {
593 return MakeVectorFromTArray<cr::ActorDefinition>(Episode->GetActorDefinitions());
594 };
595
596 BIND_SYNC(get_spectator) << [this]() -> R<cr::Actor>
597 {
599 FCarlaActor* CarlaActor = Episode->FindCarlaActor(Episode->GetSpectatorPawn());
600 if (!CarlaActor)
601 {
602 RESPOND_ERROR("internal error: unable to find spectator");
603 }
604 return Episode->SerializeActor(CarlaActor);
605 };
606
607 BIND_SYNC(get_all_level_BBs) << [this](uint8 QueriedTag) -> R<std::vector<cg::BoundingBox>>
608 {
610 TArray<FBoundingBox> Result;
612 if (!GameMode)
613 {
614 RESPOND_ERROR("unable to find CARLA game mode");
615 }
616 Result = GameMode->GetAllBBsOfLevel(QueriedTag);
617 ALargeMapManager* LargeMap = GameMode->GetLMManager();
618 if (LargeMap)
619 {
620 for(auto& Box : Result)
621 {
622 Box.Origin = LargeMap->LocalToGlobalLocation(Box.Origin);
623 }
624 }
625 return MakeVectorFromTArray<cg::BoundingBox>(Result);
626 };
627
628 BIND_SYNC(get_environment_objects) << [this](uint8 QueriedTag) -> R<std::vector<cr::EnvironmentObject>>
629 {
632 if (!GameMode)
633 {
634 RESPOND_ERROR("unable to find CARLA game mode");
635 }
636 TArray<FEnvironmentObject> Result = GameMode->GetEnvironmentObjects(QueriedTag);
637 ALargeMapManager* LargeMap = GameMode->GetLMManager();
638 if (LargeMap)
639 {
640 for(auto& Object : Result)
641 {
642 Object.Transform = LargeMap->LocalToGlobalTransform(Object.Transform);
643 }
644 }
645 return MakeVectorFromTArray<cr::EnvironmentObject>(Result);
646 };
647
648 BIND_SYNC(enable_environment_objects) << [this](std::vector<uint64_t> EnvObjectIds, bool Enable) -> R<void>
649 {
652 if (!GameMode)
653 {
654 RESPOND_ERROR("unable to find CARLA game mode");
655 }
656
657 TSet<uint64> EnvObjectIdsSet;
658 for(uint64 Id : EnvObjectIds)
659 {
660 EnvObjectIdsSet.Emplace(Id);
661 }
662
663 GameMode->EnableEnvironmentObjects(EnvObjectIdsSet, Enable);
664 return R<void>::Success();
665 };
666
667 // ~~ Weather ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
668
669 BIND_SYNC(get_weather_parameters) << [this]() -> R<cr::WeatherParameters>
670 {
672 auto *Weather = Episode->GetWeather();
673 if (Weather == nullptr)
674 {
675 RESPOND_ERROR("internal error: unable to find weather");
676 }
677 return Weather->GetCurrentWeather();
678 };
679
680 BIND_SYNC(set_weather_parameters) << [this](
681 const cr::WeatherParameters &weather) -> R<void>
682 {
684 auto *Weather = Episode->GetWeather();
685 if (Weather == nullptr)
686 {
687 RESPOND_ERROR("internal error: unable to find weather");
688 }
689 Weather->ApplyWeather(weather);
690 return R<void>::Success();
691 };
692
693 // -- IMUI Gravity ---------------------------------------------------------
694
695 BIND_SYNC(get_imui_gravity) << [this]() -> R<float>
696 {
699 if (GameMode == nullptr)
700 {
701 RESPOND_ERROR("get_imui_gravity error: unable to get carla gamemode");
702 }
703 return GameMode->IMUISensorGravity;
704 };
705
706 BIND_SYNC(set_imui_gravity) << [this](float newimuigravity) -> R<void>
707 {
710 if (GameMode == nullptr)
711 {
712 RESPOND_ERROR("get_imui_gravity error: unable to get carla gamemode");
713 }
714 GameMode->IMUISensorGravity = newimuigravity;
715 return R<void>::Success();
716 };
717
718 // ~~ Actor operations ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
719
720 BIND_SYNC(get_actors_by_id) << [this](
721 const std::vector<FCarlaActor::IdType> &ids) -> R<std::vector<cr::Actor>>
722 {
724 // 创建一个用于存储结果的向量,并预留足够的空间以优化性能
725 std::vector<cr::Actor> Result;
726 Result.reserve(ids.size());
727 // 遍历提供的ID列表
728 for (auto &&Id : ids)
729 {// 使用ID在场景中查找对应的CARLA对象视图
730 FCarlaActor* View = Episode->FindCarlaActor(Id);
731 if (View)
732 {
733 Result.emplace_back(Episode->SerializeActor(View));
734 }
735 }
736 return Result;
737 };
738// 绑定同步函数spawn_actor到下面的lambda表达式
739 BIND_SYNC(spawn_actor) << [this](
740 cr::ActorDescription Description,// 对象描述,包含类型、属性等信息
741 const cr::Transform &Transform) -> R<cr::Actor>// 对象的位置和朝向
742 {
743 // 检查当前是否有一个有效的CARLA模拟场景正在运行
745
746 auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
747
748 if (Result.Key != EActorSpawnResultStatus::Success)
749 {
750 UE_LOG(LogCarla, Error, TEXT("Actor not Spawned"));
752 }
753
755 if(LargeMap)
756 {
757 LargeMap->OnActorSpawned(*Result.Value);
758 }
759
760 return Episode->SerializeActor(Result.Value);
761 };
762
763 BIND_SYNC(spawn_actor_with_parent) << [this](
764 cr::ActorDescription Description,
765 const cr::Transform &Transform,
766 cr::ActorId ParentId,
767 cr::AttachmentType InAttachmentType,
768 const std::string& socket_name) -> R<cr::Actor>
769 {
771 // 尝试在模拟场景中生成一个新的actor
772 // Transform包含了新actor的位置和朝向信息
773 // Description包含了新actor的类型、属性等描述信息
774 auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
775 // 检查生成actor的结果
776 if (Result.Key != EActorSpawnResultStatus::Success)
777 {
779 }
780
781 FCarlaActor* CarlaActor = Episode->FindCarlaActor(Result.Value->GetActorId());
782 if (!CarlaActor)
783 {
784 RESPOND_ERROR("internal error: actor could not be spawned");
785 }
786
787 FCarlaActor* ParentCarlaActor = Episode->FindCarlaActor(ParentId);
788
789 if (!ParentCarlaActor)
790 {
791 RESPOND_ERROR("unable to attach actor: parent actor not found");
792 }
793
794 CarlaActor->SetParent(ParentId);
795 CarlaActor->SetAttachmentType(InAttachmentType);
796 ParentCarlaActor->AddChildren(CarlaActor->GetActorId());
797
798 #if defined(WITH_ROS2)
799 auto ROS2 = carla::ros2::ROS2::GetInstance();
800 if (ROS2->IsEnabled())
801 {
802 FCarlaActor* CurrentActor = ParentCarlaActor;
803 while(CurrentActor)
804 {
805 for (const auto &Attr : CurrentActor->GetActorInfo()->Description.Variations)
806 {
807 if (Attr.Key == "ros_name")
808 {
809 const std::string value = std::string(TCHAR_TO_UTF8(*Attr.Value.Value));
810 ROS2->AddActorParentRosName(static_cast<void*>(CarlaActor->GetActor()), static_cast<void*>(CurrentActor->GetActor()));
811 }
812 }
813 CurrentActor = Episode->FindCarlaActor(CurrentActor->GetParent());
814 }
815 }
816 #endif
817
818 // 只有在actor确实已经被生成(spawned)并且不处于休眠状态时,才能进行附加(attach)操作。
819 if(!ParentCarlaActor->IsDormant())
820 {
821 Episode->AttachActors(
822 CarlaActor->GetActor(),
823 ParentCarlaActor->GetActor(),
824 static_cast<EAttachmentType>(InAttachmentType),
825 FString(socket_name.c_str()));
826 }
827 else
828 {
829 Episode->PutActorToSleep(CarlaActor->GetActorId());
830 }
831
832 return Episode->SerializeActor(CarlaActor);
833 };
834
835 BIND_SYNC(destroy_actor) << [this](cr::ActorId ActorId) -> R<bool>
836 {
838 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
839 if ( !CarlaActor )
840 {
841 RESPOND_ERROR("unable to destroy actor: not found");
842 }
843 UE_LOG(LogCarla, Log, TEXT("CarlaServer destroy_actor %d"), ActorId);
844 // 我们需要强制改变actor的状态,因为处于休眠状态的actors会忽略FCarlaActor的销毁指令。
845 CarlaActor->SetActorState(cr::ActorState::PendingKill);
846 if (!Episode->DestroyActor(ActorId))
847 {
848 RESPOND_ERROR("internal error: unable to destroy actor");
849 }
850 return true;
851 };
852
853 BIND_SYNC(console_command) << [this](std::string cmd) -> R<bool>
854 {
856 APlayerController* PController= UGameplayStatics::GetPlayerController(Episode->GetWorld(), 0);
857 if( PController )
858 {
859 auto result = PController->ConsoleCommand(UTF8_TO_TCHAR(cmd.c_str()), true);
860 return !(
861 result.Contains(FString(TEXT("Command not recognized"))) ||
862 result.Contains(FString(TEXT("Error")))
863 );
864 }
865 return GEngine->Exec(Episode->GetWorld(), UTF8_TO_TCHAR(cmd.c_str()));
866 };
867
868 BIND_SYNC(get_sensor_token) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
870 {
872 bool ForceInPrimary = false;
873
874 // check for the world observer (always in primary server)
875 if (sensor_id == 1)
876 {
877 ForceInPrimary = true;
878 }
879
880 // collision sensor always in primary server in multi-gpu
881 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
882 if (Desc == "" || Desc == "sensor.other.collision")
883 {
884 ForceInPrimary = true;
885 }
886
887 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
888 {
889 // multi-gpu
890 UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in secondary server"), sensor_id, *Desc);
891 return SecondaryServer->GetCommander().GetToken(sensor_id);
892 }
893 else
894 {
895 // single-gpu
896 UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in primary server"), sensor_id, *Desc);
897 return StreamingServer.GetToken(sensor_id);
898 }
899 };
900
901 BIND_SYNC(enable_sensor_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
902 R<void>
903 {
905 bool ForceInPrimary = false;
906
907 // check for the world observer (always in primary server)
908 if (sensor_id == 1)
909 {
910 ForceInPrimary = true;
911 }
912
913 // collision sensor always in primary server in multi-gpu
914 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
915 if (Desc == "" || Desc == "sensor.other.collision")
916 {
917 ForceInPrimary = true;
918 }
919
920 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
921 {
922 // multi-gpu
923 SecondaryServer->GetCommander().EnableForROS(sensor_id);
924 }
925 else
926 {
927 // single-gpu
928 StreamingServer.EnableForROS(sensor_id);
929 }
930 return R<void>::Success();
931 };
932
933 BIND_SYNC(disable_sensor_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
934 R<void>
935 {
937 bool ForceInPrimary = false;
938
939 // check for the world observer (always in primary server)
940 if (sensor_id == 1)
941 {
942 ForceInPrimary = true;
943 }
944
945 // collision sensor always in primary server in multi-gpu
946 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
947 if (Desc == "" || Desc == "sensor.other.collision")
948 {
949 ForceInPrimary = true;
950 }
951
952 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
953 {
954 // multi-gpu
955 SecondaryServer->GetCommander().DisableForROS(sensor_id);
956 }
957 else
958 {
959 // single-gpu
961 }
962 return R<void>::Success();
963 };
964
965BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
966 R<bool>
967 {
969 bool ForceInPrimary = false;
970
971 // check for the world observer (always in primary server)
972 if (sensor_id == 1)
973 {
974 ForceInPrimary = true;
975 }
976
977 // collision sensor always in primary server in multi-gpu
978 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
979 if (Desc == "" || Desc == "sensor.other.collision")
980 {
981 ForceInPrimary = true;
982 }
983
984 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
985 {
986 // multi-gpu
987 return SecondaryServer->GetCommander().IsEnabledForROS(sensor_id);
988 }
989 else
990 {
991 // single-gpu
992 return StreamingServer.IsEnabledForROS(sensor_id);
993 }
994 };
995
996
997 BIND_SYNC(send) << [this](
998 cr::ActorId ActorId,
999 std::string message) -> R<void>
1000 {
1002 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1003 if (!CarlaActor)
1004 {
1005 return RespondError(
1006 "send",
1008 " Actor Id: " + FString::FromInt(ActorId));
1009 }
1010
1011 if (CarlaActor->IsDormant())
1012 {
1013 return RespondError(
1014 "send",
1016 " Actor Id: " + FString::FromInt(ActorId));
1017 }
1018 ACustomV2XSensor* Sensor = Cast<ACustomV2XSensor>(CarlaActor->GetActor());
1019 if (!Sensor)
1020 {
1021 return RespondError(
1022 "send",
1024 " Actor Id: " + FString::FromInt(ActorId));
1025 }
1026
1027 Sensor->Send(cr::ToFString(message));
1028 return R<void>::Success();
1029 };
1030
1031 // ~~ Actor physics ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1032
1033 BIND_SYNC(set_actor_location) << [this](
1034 cr::ActorId ActorId,
1035 cr::Location Location) -> R<void>
1036 {
1038 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1039 if (!CarlaActor)
1040 {
1041 return RespondError(
1042 "set_actor_location",
1044 " Actor Id: " + FString::FromInt(ActorId));
1045 }
1046
1047 CarlaActor->SetActorGlobalLocation(
1048 Location, ETeleportType::TeleportPhysics);
1049 return R<void>::Success();
1050 };
1051
1052 BIND_SYNC(set_actor_transform) << [this](
1053 cr::ActorId ActorId,
1054 cr::Transform Transform) -> R<void>
1055 {
1057 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1058 if (!CarlaActor)
1059 {
1060 return RespondError(
1061 "set_actor_transform",
1063 " Actor Id: " + FString::FromInt(ActorId));
1064 }
1065
1066 CarlaActor->SetActorGlobalTransform(
1067 Transform, ETeleportType::TeleportPhysics);
1068 return R<void>::Success();
1069 };
1070
1071 BIND_SYNC(set_walker_state) << [this] (
1072 cr::ActorId ActorId,
1073 cr::Transform Transform,
1074 float Speed) -> R<void>
1075 {
1077 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1078 if (!CarlaActor)
1079 {
1080 return RespondError(
1081 "set_walker_state",
1083 " Actor Id: " + FString::FromInt(ActorId));
1084 }
1085
1086 // apply walker transform
1087 ECarlaServerResponse Response =
1088 CarlaActor->SetWalkerState(
1089 Transform,
1090 cr::WalkerControl(
1091 Transform.GetForwardVector(), Speed, false));
1092 if (Response != ECarlaServerResponse::Success)
1093 {
1094 return RespondError(
1095 "set_walker_state",
1096 Response,
1097 " Actor Id: " + FString::FromInt(ActorId));
1098 }
1099 return R<void>::Success();
1100 };
1101// 使用BIND_SYNC宏绑定一个名为set_actor_target_velocity的同步操作
1102// 该操作接受一个actor的ID(cr::ActorId)和一个三维向量(cr::Vector3D)作为参数
1103// 并返回一个R<void>类型的响应对象,表示操作的结果
1104 BIND_SYNC(set_actor_target_velocity) << [this](
1105 cr::ActorId ActorId,// actor的唯一标识符
1106 cr::Vector3D vector) -> R<void>// actor应达到的目标速度向量
1107 {
1109 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1110 if (!CarlaActor)
1111 {
1112 return RespondError(
1113 "set_actor_target_velocity",
1115 " Actor Id: " + FString::FromInt(ActorId));
1116 }
1117 ECarlaServerResponse Response =
1118 CarlaActor->SetActorTargetVelocity(vector.ToCentimeters().ToFVector());
1119 if (Response != ECarlaServerResponse::Success)
1120 {
1121 return RespondError(
1122 "set_actor_target_velocity",
1123 Response,
1124 " Actor Id: " + FString::FromInt(ActorId));
1125 }
1126 return R<void>::Success();
1127 };
1128
1129 BIND_SYNC(set_actor_target_angular_velocity) << [this](
1130 cr::ActorId ActorId,
1131 cr::Vector3D vector) -> R<void>
1132 {
1134 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1135 if (!CarlaActor)
1136 {
1137 return RespondError(
1138 "set_actor_target_angular_velocity",
1140 " Actor Id: " + FString::FromInt(ActorId));
1141 }
1142 ECarlaServerResponse Response =
1143 CarlaActor->SetActorTargetAngularVelocity(vector.ToFVector());
1144 if (Response != ECarlaServerResponse::Success)
1145 {
1146 return RespondError(
1147 "set_actor_target_angular_velocity",
1148 Response,
1149 " Actor Id: " + FString::FromInt(ActorId));
1150 }
1151 return R<void>::Success();
1152 };
1153
1154 BIND_SYNC(enable_actor_constant_velocity) << [this](
1155 cr::ActorId ActorId,
1156 cr::Vector3D vector) -> R<void>
1157 {
1159 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1160 if (!CarlaActor)
1161 {
1162 return RespondError(
1163 "enable_actor_constant_velocity",
1165 " Actor Id: " + FString::FromInt(ActorId));
1166 }
1167
1168 ECarlaServerResponse Response =
1169 CarlaActor->EnableActorConstantVelocity(vector.ToCentimeters().ToFVector());
1170 if (Response != ECarlaServerResponse::Success)
1171 {
1172 return RespondError(
1173 "enable_actor_constant_velocity",
1174 Response,
1175 " Actor Id: " + FString::FromInt(ActorId));
1176 }
1177
1178 return R<void>::Success();
1179 };
1180
1181 BIND_SYNC(disable_actor_constant_velocity) << [this](
1182 cr::ActorId ActorId) -> R<void>
1183 {
1185 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1186 if (!CarlaActor)
1187 {
1188 return RespondError(
1189 "disable_actor_constant_velocity",
1191 " Actor Id: " + FString::FromInt(ActorId));
1192 }
1193
1194 ECarlaServerResponse Response =
1195 CarlaActor->DisableActorConstantVelocity();
1196 if (Response != ECarlaServerResponse::Success)
1197 {
1198 return RespondError(
1199 "disable_actor_constant_velocity",
1200 Response,
1201 " Actor Id: " + FString::FromInt(ActorId));
1202 }
1203
1204 return R<void>::Success();
1205 };
1206
1207 BIND_SYNC(add_actor_impulse) << [this](
1208 cr::ActorId ActorId,
1209 cr::Vector3D vector) -> R<void>
1210 {
1212 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1213 if (!CarlaActor)
1214 {
1215 return RespondError(
1216 "add_actor_impulse",
1218 " Actor Id: " + FString::FromInt(ActorId));
1219 }
1220
1221 ECarlaServerResponse Response =
1222 CarlaActor->AddActorImpulse(vector.ToCentimeters().ToFVector());
1223 if (Response != ECarlaServerResponse::Success)
1224 {
1225 return RespondError(
1226 "add_actor_impulse",
1227 Response,
1228 " Actor Id: " + FString::FromInt(ActorId));
1229 }
1230 return R<void>::Success();
1231 };
1232
1233 BIND_SYNC(add_actor_impulse_at_location) << [this](
1234 cr::ActorId ActorId,
1235 cr::Vector3D impulse,
1236 cr::Vector3D location) -> R<void>
1237 {
1239 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1240 if (!CarlaActor)
1241 {
1242 return RespondError(
1243 "add_actor_impulse_at_location",
1245 " Actor Id: " + FString::FromInt(ActorId));
1246 }
1247 FVector UELocation = location.ToCentimeters().ToFVector();
1248 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1249 ALargeMapManager* LargeMap = GameMode->GetLMManager();
1250 if (LargeMap)
1251 {
1252 UELocation = LargeMap->GlobalToLocalLocation(UELocation);
1253 }
1254 ECarlaServerResponse Response =
1255 CarlaActor->AddActorImpulseAtLocation(impulse.ToCentimeters().ToFVector(), UELocation);
1256 if (Response != ECarlaServerResponse::Success)
1257 {
1258 return RespondError(
1259 "add_actor_impulse_at_location",
1260 Response,
1261 " Actor Id: " + FString::FromInt(ActorId));
1262 }
1263
1264 return R<void>::Success();
1265 };
1266
1267 BIND_SYNC(add_actor_force) << [this](
1268 cr::ActorId ActorId,
1269 cr::Vector3D vector) -> R<void>
1270 {
1272 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1273 if (!CarlaActor)
1274 {
1275 return RespondError(
1276 "add_actor_force",
1278 " Actor Id: " + FString::FromInt(ActorId));
1279 }
1280 ECarlaServerResponse Response =
1281 CarlaActor->AddActorForce(vector.ToCentimeters().ToFVector());
1282 if (Response != ECarlaServerResponse::Success)
1283 {
1284 return RespondError(
1285 "add_actor_force",
1286 Response,
1287 " Actor Id: " + FString::FromInt(ActorId));
1288 }
1289 return R<void>::Success();
1290 };
1291
1292 BIND_SYNC(add_actor_force_at_location) << [this](
1293 cr::ActorId ActorId,
1294 cr::Vector3D force,
1295 cr::Vector3D location) -> R<void>
1296 {
1298 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1299 if (!CarlaActor)
1300 {
1301 return RespondError(
1302 "add_actor_force_at_location",
1304 " Actor Id: " + FString::FromInt(ActorId));
1305 }
1306 FVector UELocation = location.ToCentimeters().ToFVector();
1307 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1308 ALargeMapManager* LargeMap = GameMode->GetLMManager();
1309 if (LargeMap)
1310 {
1311 UELocation = LargeMap->GlobalToLocalLocation(UELocation);
1312 }
1313 ECarlaServerResponse Response =
1314 CarlaActor->AddActorForceAtLocation(UELocation, force.ToCentimeters().ToFVector());
1315 if (Response != ECarlaServerResponse::Success)
1316 {
1317 return RespondError(
1318 "add_actor_force_at_location",
1319 Response,
1320 " Actor Id: " + FString::FromInt(ActorId));
1321 }
1322 return R<void>::Success();
1323 };
1324
1325 BIND_SYNC(add_actor_angular_impulse) << [this](
1326 cr::ActorId ActorId,
1327 cr::Vector3D vector) -> R<void>
1328 {
1330 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1331 if (!CarlaActor)
1332 {
1333 return RespondError(
1334 "add_actor_angular_impulse",
1336 " Actor Id: " + FString::FromInt(ActorId));
1337 }
1338 ECarlaServerResponse Response =
1339 CarlaActor->AddActorAngularImpulse(vector.ToFVector());
1340 if (Response != ECarlaServerResponse::Success)
1341 {
1342 return RespondError(
1343 "add_actor_angular_impulse",
1344 Response,
1345 " Actor Id: " + FString::FromInt(ActorId));
1346 }
1347 return R<void>::Success();
1348 };
1349
1350 BIND_SYNC(add_actor_torque) << [this](
1351 cr::ActorId ActorId,
1352 cr::Vector3D vector) -> R<void>
1353 {
1355 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1356 if (!CarlaActor)
1357 {
1358 return RespondError(
1359 "add_actor_torque",
1361 " Actor Id: " + FString::FromInt(ActorId));
1362 }
1363 ECarlaServerResponse Response =
1364 CarlaActor->AddActorTorque(vector.ToFVector());
1365 if (Response != ECarlaServerResponse::Success)
1366 {
1367 return RespondError(
1368 "add_actor_torque",
1369 Response,
1370 " Actor Id: " + FString::FromInt(ActorId));
1371 }
1372 return R<void>::Success();
1373 };
1374
1375 BIND_SYNC(get_actor_component_world_transform) << [this](
1376 cr::ActorId ActorId,
1377 const std::string componentName) -> R<cr::Transform>
1378 {
1380 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1381 if (!CarlaActor)
1382 {
1383 return RespondError(
1384 "get_actor_component_world_transform",
1386 " Actor Id: " + FString::FromInt(ActorId));
1387 }
1388 else
1389 {
1390 TArray<UActorComponent*> Components;
1391 CarlaActor->GetActor()->GetComponents(Components);
1392
1393 USceneComponent* Component = nullptr;
1394 for(auto Cmp : Components)
1395 {
1396 if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
1397 {
1398 if(SCMP->GetName() == componentName.c_str())
1399 {
1400 Component = SCMP;
1401 break;
1402 }
1403 }
1404 }
1405
1406 if(!Component)
1407 {
1408 return RespondError(
1409 "get_actor_component_world_transform",
1411 " Component Name: " + FString(componentName.c_str()));
1412 }
1413
1414 FTransform ComponentWorldTransform = Component->GetComponentTransform();
1415 return cr::Transform(ComponentWorldTransform);
1416 }
1417 };
1418
1419 BIND_SYNC(get_actor_component_relative_transform) << [this](
1420 cr::ActorId ActorId,
1421 const std::string componentName) -> R<cr::Transform>
1422 {
1424 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1425 if (!CarlaActor)
1426 {
1427 return RespondError(
1428 "get_actor_component_relative_transform",
1430 " Actor Id: " + FString::FromInt(ActorId));
1431 }
1432 else
1433 {
1434 TArray<UActorComponent*> Components;
1435 CarlaActor->GetActor()->GetComponents(Components);
1436
1437 USceneComponent* Component = nullptr;
1438 for(auto Cmp : Components)
1439 {
1440 if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
1441 {
1442 if(SCMP->GetName() == componentName.c_str())
1443 {
1444 Component = SCMP;
1445 break;
1446 }
1447 }
1448 }
1449
1450 if(!Component)
1451 {
1452 return RespondError(
1453 "get_actor_component_world_transform",
1455 " Component Name: " + FString(componentName.c_str()));
1456 }
1457
1458 FTransform ComponentRelativeTransform = Component->GetRelativeTransform();
1459 return cr::Transform(ComponentRelativeTransform);
1460 }
1461 };
1462
1463 BIND_SYNC(get_actor_bone_world_transforms) << [this](
1464 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1465 {
1467 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1468 if (!CarlaActor)
1469 {
1470 return RespondError(
1471 "get_actor_bone_world_transforms",
1473 " Actor Id: " + FString::FromInt(ActorId));
1474 }
1475 else
1476 {
1477 TArray<FTransform> BoneWorldTransforms;
1478 TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
1479 CarlaActor->GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
1480 if(!SkinnedMeshComponents[0])
1481 {
1482 return RespondError(
1483 "get_actor_bone_world_transforms",
1485 " Component Name: SkinnedMeshComponent ");
1486 }
1487 else
1488 {
1489 for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
1490 {
1491 const int32 NumBones = SkinnedMeshComponent->GetNumBones();
1492 for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
1493 {
1494 FTransform WorldTransform = SkinnedMeshComponent->GetComponentTransform();
1495 FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, WorldTransform);
1496 BoneWorldTransforms.Add(BoneTransform);
1497 }
1498 }
1499 return MakeVectorFromTArray<cr::Transform>(BoneWorldTransforms);
1500 }
1501 }
1502 };
1503
1504 BIND_SYNC(get_actor_bone_relative_transforms) << [this](
1505 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1506 {
1508 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1509 if (!CarlaActor)
1510 {
1511 return RespondError(
1512 "get_actor_bone_relative_transforms",
1514 " Actor Id: " + FString::FromInt(ActorId));
1515 }
1516 else
1517 {
1518 TArray<FTransform> BoneRelativeTransforms;
1519 TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
1520 CarlaActor->GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
1521 if(!SkinnedMeshComponents[0])
1522 {
1523 return RespondError(
1524 "get_actor_bone_relative_transforms",
1526 " Component Name: SkinnedMeshComponent ");
1527 }
1528 else
1529 {
1530 for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
1531 {
1532 const int32 NumBones = SkinnedMeshComponent->GetNumBones();
1533 for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
1534 {
1535 FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, FTransform::Identity);
1536 BoneRelativeTransforms.Add(BoneTransform);
1537 }
1538 }
1539 return MakeVectorFromTArray<cr::Transform>(BoneRelativeTransforms);
1540 }
1541 }
1542 };
1543
1544 BIND_SYNC(get_actor_component_names) << [this](
1545 cr::ActorId ActorId) -> R<std::vector<std::string>>
1546 {
1548 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1549 if (!CarlaActor)
1550 {
1551 return RespondError(
1552 "get_actor_component_names",
1554 " Actor Id: " + FString::FromInt(ActorId));
1555 }
1556 else
1557 {
1558 TArray<UActorComponent*> Components;
1559 CarlaActor->GetActor()->GetComponents(Components);
1560 std::vector<std::string> ComponentNames;
1561 for(auto Cmp : Components)
1562 {
1563 FString ComponentName = Cmp->GetName();
1564 ComponentNames.push_back(TCHAR_TO_UTF8(*ComponentName));
1565 }
1566 return ComponentNames;
1567 }
1568 };
1569
1570 BIND_SYNC(get_actor_bone_names) << [this](
1571 cr::ActorId ActorId) -> R<std::vector<std::string>>
1572 {
1574 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1575 if (!CarlaActor)
1576 {
1577 return RespondError(
1578 "get_actor_bone_names",
1580 " Actor Id: " + FString::FromInt(ActorId));
1581 }
1582 else
1583 {
1584 USkinnedMeshComponent* SkinnedMeshComponent = CarlaActor->GetActor()->FindComponentByClass<USkinnedMeshComponent>();
1585 if(!SkinnedMeshComponent)
1586 {
1587 return RespondError(
1588 "get_actor_bone_names",
1590 " Component Name: SkinnedMeshComponent ");
1591 }
1592 else
1593 {
1594 TArray<FName> BoneNames;
1595 SkinnedMeshComponent->GetBoneNames(BoneNames);
1596 TArray<std::string> StringBoneNames;
1597 for (const FName& Name : BoneNames)
1598 {
1599 FString FBoneName = Name.ToString();
1600 std::string StringBoneName = TCHAR_TO_UTF8(*FBoneName);
1601 StringBoneNames.Add(StringBoneName);
1602 }
1603 return MakeVectorFromTArray<std::string>(StringBoneNames);
1604 }
1605 }
1606 };
1607
1608 BIND_SYNC(get_actor_socket_world_transforms) << [this](
1609 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1610 {
1612 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1613 if (!CarlaActor)
1614 {
1615 return RespondError(
1616 "get_actor_socket_world_transforms",
1618 " Actor Id: " + FString::FromInt(ActorId));
1619 }
1620 else
1621 {
1622 TArray<FTransform> SocketWorldTransforms;
1623 TArray<UActorComponent*> Components;
1624 CarlaActor->GetActor()->GetComponents(Components);
1625 for(UActorComponent* ActorComponent : Components)
1626 {
1627 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1628 {
1629 const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
1630 for (const FName& SocketName : SocketNames)
1631 {
1632 FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName);
1633 SocketWorldTransforms.Add(SocketTransform);
1634 }
1635 }
1636 }
1637 return MakeVectorFromTArray<cr::Transform>(SocketWorldTransforms);
1638 }
1639 };
1640
1641 BIND_SYNC(get_actor_socket_relative_transforms) << [this](
1642 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1643 {
1645 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1646 if (!CarlaActor)
1647 {
1648 return RespondError(
1649 "get_actor_socket_relative_transforms",
1651 " Actor Id: " + FString::FromInt(ActorId));
1652 }
1653 else
1654 {
1655 TArray<FTransform> SocketRelativeTransforms;
1656 TArray<UActorComponent*> Components;
1657 CarlaActor->GetActor()->GetComponents(Components);
1658 for(UActorComponent* ActorComponent : Components)
1659 {
1660 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1661 {
1662 const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
1663 for (const FName& SocketName : SocketNames)
1664 {
1665 FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName, ERelativeTransformSpace::RTS_Actor);
1666 SocketRelativeTransforms.Add(SocketTransform);
1667 }
1668 }
1669 }
1670 return MakeVectorFromTArray<cr::Transform>(SocketRelativeTransforms);
1671 }
1672 };
1673
1674 BIND_SYNC(get_actor_socket_names) << [this](
1675 cr::ActorId ActorId) -> R<std::vector<std::string>>
1676 {
1678 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1679 if (!CarlaActor)
1680 {
1681 return RespondError(
1682 "get_actor_socket_names",
1684 " Actor Id: " + FString::FromInt(ActorId));
1685 }
1686 else
1687 {
1688 TArray<FName> SocketNames;
1689 std::vector<std::string> StringSocketNames;
1690 TArray<UActorComponent*> Components;
1691 CarlaActor->GetActor()->GetComponents(Components);
1692 for(UActorComponent* ActorComponent : Components)
1693 {
1694 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1695 {
1696 SocketNames = SceneComponent->GetAllSocketNames();
1697 for (const FName& Name : SocketNames)
1698 {
1699 FString FSocketName = Name.ToString();
1700 std::string StringSocketName = TCHAR_TO_UTF8(*FSocketName);
1701 StringSocketNames.push_back(StringSocketName);
1702 }
1703 }
1704 }
1705 return StringSocketNames;
1706 }
1707 };
1708
1709 // 向客户端公开遥测数据
1710 BIND_SYNC(get_physics_control) << [this](
1711 cr::ActorId ActorId) -> R<cr::VehiclePhysicsControl>
1712 {
1714 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1715 if (!CarlaActor)
1716 {
1717 return RespondError(
1718 "get_physics_control",
1720 " Actor Id: " + FString::FromInt(ActorId));
1721 }
1723 ECarlaServerResponse Response =
1724 CarlaActor->GetPhysicsControl(PhysicsControl); // 获得车辆的物理控制
1725 if (Response != ECarlaServerResponse::Success)
1726 {
1727 return RespondError(
1728 "get_physics_control",
1729 Response,
1730 " Actor Id: " + FString::FromInt(ActorId));
1731 }
1732 return cr::VehiclePhysicsControl(PhysicsControl);
1733 };
1734
1735 BIND_SYNC(get_vehicle_light_state) << [this](
1736 cr::ActorId ActorId) -> R<cr::VehicleLightState>
1737 {
1739 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1740 if (!CarlaActor)
1741 {
1742 return RespondError(
1743 "get_vehicle_light_state",
1745 " Actor Id: " + FString::FromInt(ActorId));
1746 }
1748 ECarlaServerResponse Response =
1749 CarlaActor->GetVehicleLightState(LightState);
1750 if (Response != ECarlaServerResponse::Success)
1751 {
1752 return RespondError(
1753 "get_vehicle_light_state",
1754 Response,
1755 " Actor Id: " + FString::FromInt(ActorId));
1756 }
1757 return cr::VehicleLightState(LightState);
1758 };
1759
1760 BIND_SYNC(apply_physics_control) << [this](
1761 cr::ActorId ActorId,
1762 cr::VehiclePhysicsControl PhysicsControl) -> R<void>
1763 {
1765 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1766 if (!CarlaActor)
1767 {
1768 return RespondError(
1769 "apply_physics_control",
1771 " Actor Id: " + FString::FromInt(ActorId));
1772 }
1773 ECarlaServerResponse Response =
1775 if (Response != ECarlaServerResponse::Success)
1776 {
1777 return RespondError(
1778 "apply_physics_control",
1779 Response,
1780 " Actor Id: " + FString::FromInt(ActorId));
1781 }
1782 return R<void>::Success();
1783 };
1784
1785 BIND_SYNC(set_vehicle_light_state) << [this](
1786 cr::ActorId ActorId,
1787 cr::VehicleLightState LightState) -> R<void>
1788 {
1790 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1791 if (!CarlaActor)
1792 {
1793 return RespondError(
1794 "set_vehicle_light_state",
1796 " Actor Id: " + FString::FromInt(ActorId));
1797 }
1798 ECarlaServerResponse Response =
1800 if (Response != ECarlaServerResponse::Success)
1801 {
1802 return RespondError(
1803 "set_vehicle_light_state",
1804 Response,
1805 " Actor Id: " + FString::FromInt(ActorId));
1806 }
1807 return R<void>::Success();
1808 };
1809
1810
1811 BIND_SYNC(open_vehicle_door) << [this](
1812 cr::ActorId ActorId,
1813 cr::VehicleDoor DoorIdx) -> R<void>
1814 {
1816 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1817 if (!CarlaActor)
1818 {
1819 return RespondError(
1820 "open_vehicle_door",
1822 " Actor Id: " + FString::FromInt(ActorId));
1823 }
1824 ECarlaServerResponse Response =
1825 CarlaActor->OpenVehicleDoor(static_cast<EVehicleDoor>(DoorIdx));
1826 if (Response != ECarlaServerResponse::Success)
1827 {
1828 return RespondError(
1829 "open_vehicle_door",
1830 Response,
1831 " Actor Id: " + FString::FromInt(ActorId));
1832 }
1833 return R<void>::Success();
1834 };
1835
1836 BIND_SYNC(close_vehicle_door) << [this](
1837 cr::ActorId ActorId,
1838 cr::VehicleDoor DoorIdx) -> R<void>
1839 {
1841 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1842 if (!CarlaActor)
1843 {
1844 return RespondError(
1845 "close_vehicle_door",
1847 " Actor Id: " + FString::FromInt(ActorId));
1848 }
1849 ECarlaServerResponse Response =
1850 CarlaActor->CloseVehicleDoor(static_cast<EVehicleDoor>(DoorIdx));
1851 if (Response != ECarlaServerResponse::Success)
1852 {
1853 return RespondError(
1854 "close_vehicle_door",
1855 Response,
1856 " Actor Id: " + FString::FromInt(ActorId));
1857 }
1858 return R<void>::Success();
1859 };
1860
1861 BIND_SYNC(set_wheel_steer_direction) << [this](
1862 cr::ActorId ActorId,
1863 cr::VehicleWheelLocation WheelLocation,
1864 float AngleInDeg) -> R<void>
1865 {
1867 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1868 if(!CarlaActor){
1869 return RespondError(
1870 "set_wheel_steer_direction",
1872 " Actor Id: " + FString::FromInt(ActorId));
1873 }
1874 ECarlaServerResponse Response =
1875 CarlaActor->SetWheelSteerDirection(
1876 static_cast<EVehicleWheelLocation>(WheelLocation), AngleInDeg);
1877 if (Response != ECarlaServerResponse::Success)
1878 {
1879 return RespondError(
1880 "set_wheel_steer_direction",
1881 Response,
1882 " Actor Id: " + FString::FromInt(ActorId));
1883 }
1884 return R<void>::Success();
1885 };
1886
1887 BIND_SYNC(get_wheel_steer_angle) << [this](
1888 const cr::ActorId ActorId,
1889 cr::VehicleWheelLocation WheelLocation) -> R<float>
1890 {
1892 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1893 if(!CarlaActor){
1894 return RespondError(
1895 "get_wheel_steer_angle",
1897 " Actor Id: " + FString::FromInt(ActorId));
1898 }
1899 float Angle;
1900 ECarlaServerResponse Response =
1901 CarlaActor->GetWheelSteerAngle(
1902 static_cast<EVehicleWheelLocation>(WheelLocation), Angle);
1903 if (Response != ECarlaServerResponse::Success)
1904 {
1905 return RespondError(
1906 "get_wheel_steer_angle",
1907 Response,
1908 " Actor Id: " + FString::FromInt(ActorId));
1909 }
1910 return Angle;
1911 };
1912
1913 BIND_SYNC(set_actor_simulate_physics) << [this](
1914 cr::ActorId ActorId,
1915 bool bEnabled) -> R<void>
1916 {
1918 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1919 if (!CarlaActor)
1920 {
1921 return RespondError(
1922 "set_actor_simulate_physics",
1924 " Actor Id: " + FString::FromInt(ActorId));
1925 }
1926 ECarlaServerResponse Response =
1927 CarlaActor->SetActorSimulatePhysics(bEnabled);
1928 if (Response != ECarlaServerResponse::Success)
1929 {
1930 return RespondError(
1931 "set_actor_simulate_physics",
1932 Response,
1933 " Actor Id: " + FString::FromInt(ActorId));
1934 }
1935 return R<void>::Success();
1936 };
1937
1938 BIND_SYNC(set_actor_collisions) << [this](
1939 cr::ActorId ActorId,
1940 bool bEnabled) -> R<void>
1941 {
1943 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1944 if (!CarlaActor)
1945 {
1946 return RespondError(
1947 "set_actor_collisions",
1949 " Actor Id: " + FString::FromInt(ActorId));
1950 }
1951 ECarlaServerResponse Response =
1952 CarlaActor->SetActorCollisions(bEnabled);
1953 if (Response != ECarlaServerResponse::Success)
1954 {
1955 return RespondError(
1956 "set_actor_collisions",
1957 Response,
1958 " Actor Id: " + FString::FromInt(ActorId));
1959 }
1960 return R<void>::Success();
1961 };
1962
1963 BIND_SYNC(set_actor_dead) << [this](
1964 cr::ActorId ActorId) -> R<void>
1965 {
1967 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1968 if (!CarlaActor)
1969 {
1970 return RespondError(
1971 "set_actor_dead",
1973 " Actor Id: " + FString::FromInt(ActorId));
1974 }
1975 ECarlaServerResponse Response =
1976 CarlaActor->SetActorDead();
1977 if (Response != ECarlaServerResponse::Success)
1978 {
1979 return RespondError(
1980 "set_actor_dead",
1981 Response,
1982 " Actor Id: " + FString::FromInt(ActorId));
1983 }
1984 return R<void>::Success();
1985 };
1986
1987 BIND_SYNC(set_actor_enable_gravity) << [this](
1988 cr::ActorId ActorId,
1989 bool bEnabled) -> R<void>
1990 {
1992 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1993 if (!CarlaActor)
1994 {
1995 return RespondError(
1996 "set_actor_enable_gravity",
1998 " Actor Id: " + FString::FromInt(ActorId));
1999 }
2000 ECarlaServerResponse Response =
2001 CarlaActor->SetActorEnableGravity(bEnabled);
2002 if (Response != ECarlaServerResponse::Success)
2003 {
2004 return RespondError(
2005 "set_actor_enable_gravity",
2006 Response,
2007 " Actor Id: " + FString::FromInt(ActorId));
2008 }
2009 return R<void>::Success();
2010 };
2011
2012 // ~~ Apply control ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2013
2014 BIND_SYNC(apply_control_to_vehicle) << [this](
2015 cr::ActorId ActorId,
2016 cr::VehicleControl Control) -> R<void>
2017 {
2019 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2020 if (!CarlaActor)
2021 {
2022 return RespondError(
2023 "apply_control_to_vehicle",
2025 " Actor Id: " + FString::FromInt(ActorId));
2026 }
2027 ECarlaServerResponse Response =
2028 CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::Client);
2029 if (Response != ECarlaServerResponse::Success)
2030 {
2031 return RespondError(
2032 "apply_control_to_vehicle",
2033 Response,
2034 " Actor Id: " + FString::FromInt(ActorId));
2035 }
2036 return R<void>::Success();
2037 };
2038
2039 BIND_SYNC(apply_ackermann_control_to_vehicle) << [this](
2040 cr::ActorId ActorId,
2041 cr::VehicleAckermannControl Control) -> R<void>
2042 {
2044 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2045 if (!CarlaActor)
2046 {
2047 return RespondError(
2048 "apply_ackermann_control_to_vehicle",
2050 " Actor Id: " + FString::FromInt(ActorId));
2051 }
2052 ECarlaServerResponse Response =
2053 CarlaActor->ApplyAckermannControlToVehicle(Control, EVehicleInputPriority::Client);
2054 if (Response != ECarlaServerResponse::Success)
2055 {
2056 return RespondError(
2057 "apply_ackermann_control_to_vehicle",
2058 Response,
2059 " Actor Id: " + FString::FromInt(ActorId));
2060 }
2061 return R<void>::Success();
2062 };
2063
2064 BIND_SYNC(get_ackermann_controller_settings) << [this](
2065 cr::ActorId ActorId) -> R<cr::AckermannControllerSettings>
2066 {
2068 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2069 if (!CarlaActor)
2070 {
2071 return RespondError(
2072 "get_ackermann_controller_settings",
2074 " Actor Id: " + FString::FromInt(ActorId));
2075 }
2077 ECarlaServerResponse Response =
2078 CarlaActor->GetAckermannControllerSettings(Settings);
2079 if (Response != ECarlaServerResponse::Success)
2080 {
2081 return RespondError(
2082 "get_ackermann_controller_settings",
2083 Response,
2084 " Actor Id: " + FString::FromInt(ActorId));
2085 }
2086 return cr::AckermannControllerSettings(Settings);
2087 };
2088
2089 BIND_SYNC(apply_ackermann_controller_settings) << [this](
2090 cr::ActorId ActorId,
2091 cr::AckermannControllerSettings AckermannSettings) -> R<void>
2092 {
2094 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2095 if (!CarlaActor)
2096 {
2097 return RespondError(
2098 "apply_ackermann_controller_settings",
2100 " Actor Id: " + FString::FromInt(ActorId));
2101 }
2102 ECarlaServerResponse Response =
2103 CarlaActor->ApplyAckermannControllerSettings(FAckermannControllerSettings(AckermannSettings));
2104 if (Response != ECarlaServerResponse::Success)
2105 {
2106 return RespondError(
2107 "apply_ackermann_controller_settings",
2108 Response,
2109 " Actor Id: " + FString::FromInt(ActorId));
2110 }
2111 return R<void>::Success();
2112 };
2113
2114 BIND_SYNC(apply_control_to_walker) << [this](
2115 cr::ActorId ActorId,
2116 cr::WalkerControl Control) -> R<void>
2117 {
2119 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2120 if (!CarlaActor)
2121 {
2122 return RespondError(
2123 "apply_control_to_walker",
2125 " Actor Id: " + FString::FromInt(ActorId));
2126 }
2127 ECarlaServerResponse Response =
2128 CarlaActor->ApplyControlToWalker(Control);
2129 if (Response != ECarlaServerResponse::Success)
2130 {
2131 return RespondError(
2132 "apply_control_to_walker",
2133 Response,
2134 " Actor Id: " + FString::FromInt(ActorId));
2135 }
2136 return R<void>::Success();
2137 };
2138
2139 BIND_SYNC(get_bones_transform) << [this](
2140 cr::ActorId ActorId) -> R<cr::WalkerBoneControlOut>
2141 {
2143 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2144 if (!CarlaActor)
2145 {
2146 return RespondError(
2147 "get_bones_transform",
2149 " Actor Id: " + FString::FromInt(ActorId));
2150 }
2152 ECarlaServerResponse Response =
2153 CarlaActor->GetBonesTransform(Bones);
2154 if (Response != ECarlaServerResponse::Success)
2155 {
2156 return RespondError(
2157 "get_bones_transform",
2158 Response,
2159 " Actor Id: " + FString::FromInt(ActorId));
2160 }
2161
2162 std::vector<carla::rpc::BoneTransformDataOut> BoneData;
2163 for (auto Bone : Bones.BoneTransforms)
2164 {
2166 Data.bone_name = std::string(TCHAR_TO_UTF8(*Bone.Get<0>()));
2167 FWalkerBoneControlOutData Transforms = Bone.Get<1>();
2168 Data.world = Transforms.World;
2169 Data.component = Transforms.Component;
2170 Data.relative = Transforms.Relative;
2171 BoneData.push_back(Data);
2172 }
2173 return carla::rpc::WalkerBoneControlOut(BoneData);
2174 };
2175
2176 BIND_SYNC(set_bones_transform) << [this](
2177 cr::ActorId ActorId,
2179 {
2181 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2182 if (!CarlaActor)
2183 {
2184 return RespondError(
2185 "set_bones_transform",
2187 " Actor Id: " + FString::FromInt(ActorId));
2188 }
2189
2191 ECarlaServerResponse Response = CarlaActor->SetBonesTransform(Bones2);
2192 if (Response != ECarlaServerResponse::Success)
2193 {
2194 return RespondError(
2195 "set_bones_transform",
2196 Response,
2197 " Actor Id: " + FString::FromInt(ActorId));
2198 }
2199
2200 return R<void>::Success();
2201 };
2202
2203 BIND_SYNC(blend_pose) << [this](
2204 cr::ActorId ActorId,
2205 float Blend) -> R<void>
2206 {
2208 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2209 if (!CarlaActor)
2210 {
2211 return RespondError(
2212 "blend_pose",
2214 " Actor Id: " + FString::FromInt(ActorId));
2215 }
2216
2217 ECarlaServerResponse Response = CarlaActor->BlendPose(Blend);
2218 if (Response != ECarlaServerResponse::Success)
2219 {
2220 return RespondError(
2221 "blend_pose",
2222 Response,
2223 " Actor Id: " + FString::FromInt(ActorId));
2224 }
2225
2226 return R<void>::Success();
2227 };
2228
2229 BIND_SYNC(get_pose_from_animation) << [this](
2230 cr::ActorId ActorId) -> R<void>
2231 {
2233 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2234 if (!CarlaActor)
2235 {
2236 return RespondError(
2237 "get_pose_from_animation",
2239 " Actor Id: " + FString::FromInt(ActorId));
2240 }
2241
2242 ECarlaServerResponse Response = CarlaActor->GetPoseFromAnimation();
2243 if (Response != ECarlaServerResponse::Success)
2244 {
2245 return RespondError(
2246 "get_pose_from_animation",
2247 Response,
2248 " Actor Id: " + FString::FromInt(ActorId));
2249 }
2250
2251 return R<void>::Success();
2252 };
2253
2254 BIND_SYNC(set_actor_autopilot) << [this](
2255 cr::ActorId ActorId,
2256 bool bEnabled) -> R<void>
2257 {
2259 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2260 if (!CarlaActor)
2261 {
2262 return RespondError(
2263 "set_actor_autopilot",
2265 " Actor Id: " + FString::FromInt(ActorId));
2266 }
2267 ECarlaServerResponse Response =
2268 CarlaActor->SetActorAutopilot(bEnabled);
2269 if (Response != ECarlaServerResponse::Success)
2270 {
2271 return RespondError(
2272 "set_actor_autopilot",
2273 Response,
2274 " Actor Id: " + FString::FromInt(ActorId));
2275 }
2276 return R<void>::Success();
2277 };
2278
2279 BIND_SYNC(get_telemetry_data) << [this](
2280 cr::ActorId ActorId) -> R<cr::VehicleTelemetryData>
2281 {
2283 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2284 if (!CarlaActor)
2285 {
2286 return RespondError(
2287 "get_telemetry_data",
2289 " Actor Id: " + FString::FromInt(ActorId));
2290 }
2291 FVehicleTelemetryData TelemetryData;
2292 ECarlaServerResponse Response =
2293 CarlaActor->GetVehicleTelemetryData(TelemetryData);
2294 if (Response != ECarlaServerResponse::Success)
2295 {
2296 return RespondError(
2297 "get_telemetry_data",
2298 Response,
2299 " Actor Id: " + FString::FromInt(ActorId));
2300 }
2301 return cr::VehicleTelemetryData(TelemetryData);
2302 };
2303
2304 BIND_SYNC(show_vehicle_debug_telemetry) << [this](
2305 cr::ActorId ActorId,
2306 bool bEnabled) -> R<void>
2307 {
2309 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2310 if (!CarlaActor)
2311 {
2312 return RespondError(
2313 "show_vehicle_debug_telemetry",
2315 " Actor Id: " + FString::FromInt(ActorId));
2316 }
2317 ECarlaServerResponse Response =
2318 CarlaActor->ShowVehicleDebugTelemetry(bEnabled);
2319 if (Response != ECarlaServerResponse::Success)
2320 {
2321 return RespondError(
2322 "show_vehicle_debug_telemetry",
2323 Response,
2324 " Actor Id: " + FString::FromInt(ActorId));
2325 }
2326 return R<void>::Success();
2327 };
2328
2329 BIND_SYNC(enable_carsim) << [this](
2330 cr::ActorId ActorId,
2331 std::string SimfilePath) -> R<void>
2332 {
2334 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2335 if (!CarlaActor)
2336 {
2337 return RespondError(
2338 "enable_carsim",
2340 " Actor Id: " + FString::FromInt(ActorId));
2341 }
2342 ECarlaServerResponse Response =
2343 CarlaActor->EnableCarSim(carla::rpc::ToFString(SimfilePath));
2344 if (Response != ECarlaServerResponse::Success)
2345 {
2346 return RespondError(
2347 "enable_carsim",
2348 Response,
2349 " Actor Id: " + FString::FromInt(ActorId));
2350 }
2351 return R<void>::Success();
2352 };
2353
2354 BIND_SYNC(use_carsim_road) << [this](
2355 cr::ActorId ActorId,
2356 bool bEnabled) -> R<void>
2357 {
2359 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2360 if (!CarlaActor)
2361 {
2362 return RespondError(
2363 "use_carsim_road",
2365 " Actor Id: " + FString::FromInt(ActorId));
2366 }
2367 ECarlaServerResponse Response =
2368 CarlaActor->UseCarSimRoad(bEnabled);
2369 if (Response != ECarlaServerResponse::Success)
2370 {
2371 return RespondError(
2372 "use_carsim_road",
2373 Response,
2374 " Actor Id: " + FString::FromInt(ActorId));
2375 }
2376 return R<void>::Success();
2377 };
2378
2379 BIND_SYNC(enable_chrono_physics) << [this](
2380 cr::ActorId ActorId,
2381 uint64_t MaxSubsteps,
2382 float MaxSubstepDeltaTime,
2383 std::string VehicleJSON,
2384 std::string PowertrainJSON,
2385 std::string TireJSON,
2386 std::string BaseJSONPath) -> R<void>
2387 {
2389 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2390 if (!CarlaActor)
2391 {
2392 return RespondError(
2393 "enable_chrono_physics",
2395 " Actor Id: " + FString::FromInt(ActorId));
2396 }
2397 ECarlaServerResponse Response =
2398 CarlaActor->EnableChronoPhysics(
2399 MaxSubsteps, MaxSubstepDeltaTime,
2400 cr::ToFString(VehicleJSON),
2401 cr::ToFString(PowertrainJSON),
2402 cr::ToFString(TireJSON),
2403 cr::ToFString(BaseJSONPath));
2404 if (Response != ECarlaServerResponse::Success)
2405 {
2406 return RespondError(
2407 "enable_chrono_physics",
2408 Response,
2409 " Actor Id: " + FString::FromInt(ActorId));
2410 }
2411 return R<void>::Success();
2412 };
2413
2414 BIND_SYNC(restore_physx_physics) << [this](
2415 cr::ActorId ActorId) -> R<void>
2416 {
2418 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2419 if (!CarlaActor)
2420 {
2421 return RespondError(
2422 "restore_physx_physics",
2424 " Actor Id: " + FString::FromInt(ActorId));
2425 }
2426 ECarlaServerResponse Response =
2427 CarlaActor->RestorePhysXPhysics();
2428 if (Response != ECarlaServerResponse::Success)
2429 {
2430 return RespondError(
2431 "restore_physx_physics",
2432 Response,
2433 " Actor Id: " + FString::FromInt(ActorId));
2434 }
2435 return R<void>::Success();
2436 };
2437
2438 // ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2439
2440 BIND_SYNC(set_traffic_light_state) << [this](
2441 cr::ActorId ActorId,
2442 cr::TrafficLightState trafficLightState) -> R<void>
2443 {
2445 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2446 if (!CarlaActor)
2447 {
2448 return RespondError(
2449 "set_traffic_light_state",
2451 " Actor Id: " + FString::FromInt(ActorId));
2452 }
2453 ECarlaServerResponse Response =
2454 CarlaActor->SetTrafficLightState(
2455 static_cast<ETrafficLightState>(trafficLightState));
2456 if (Response != ECarlaServerResponse::Success)
2457 {
2458 return RespondError(
2459 "set_traffic_light_state",
2460 Response,
2461 " Actor Id: " + FString::FromInt(ActorId));
2462 }
2463 return R<void>::Success();
2464 };
2465
2466 BIND_SYNC(set_traffic_light_green_time) << [this](
2467 cr::ActorId ActorId,
2468 float GreenTime) -> R<void>
2469 {
2471 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2472 if (!CarlaActor)
2473 {
2474 return RespondError(
2475 "set_traffic_light_green_time",
2477 " Actor Id: " + FString::FromInt(ActorId));
2478 }
2479 ECarlaServerResponse Response =
2480 CarlaActor->SetLightGreenTime(GreenTime);
2481 if (Response != ECarlaServerResponse::Success)
2482 {
2483 return RespondError(
2484 "set_traffic_light_green_time",
2485 Response,
2486 " Actor Id: " + FString::FromInt(ActorId));
2487 }
2488 return R<void>::Success();
2489 };
2490
2491 BIND_SYNC(set_traffic_light_yellow_time) << [this](
2492 cr::ActorId ActorId,
2493 float YellowTime) -> R<void>
2494 {
2496 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2497 if (!CarlaActor)
2498 {
2499 return RespondError(
2500 "set_traffic_light_yellow_time",
2502 " Actor Id: " + FString::FromInt(ActorId));
2503 }
2504 ECarlaServerResponse Response =
2505 CarlaActor->SetLightYellowTime(YellowTime);
2506 if (Response != ECarlaServerResponse::Success)
2507 {
2508 return RespondError(
2509 "set_traffic_light_yellow_time",
2510 Response,
2511 " Actor Id: " + FString::FromInt(ActorId));
2512 }
2513 return R<void>::Success();
2514 };
2515
2516 BIND_SYNC(set_traffic_light_red_time) << [this](
2517 cr::ActorId ActorId,
2518 float RedTime) -> R<void>
2519 {
2521 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2522 if (!CarlaActor)
2523 {
2524 return RespondError(
2525 "set_traffic_light_red_time",
2527 " Actor Id: " + FString::FromInt(ActorId));
2528 }
2529 ECarlaServerResponse Response =
2530 CarlaActor->SetLightRedTime(RedTime);
2531 if (Response != ECarlaServerResponse::Success)
2532 {
2533 return RespondError(
2534 "set_traffic_light_red_time",
2535 Response,
2536 " Actor Id: " + FString::FromInt(ActorId));
2537 }
2538 return R<void>::Success();
2539 };
2540
2541 BIND_SYNC(freeze_traffic_light) << [this](
2542 cr::ActorId ActorId,
2543 bool Freeze) -> R<void>
2544 {
2546 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2547 if (!CarlaActor)
2548 {
2549 return RespondError(
2550 "freeze_traffic_light",
2552 " Actor Id: " + FString::FromInt(ActorId));
2553 }
2554 ECarlaServerResponse Response =
2555 CarlaActor->FreezeTrafficLight(Freeze);
2556 if (Response != ECarlaServerResponse::Success)
2557 {
2558 return RespondError(
2559 "freeze_traffic_light",
2560 Response,
2561 " Actor Id: " + FString::FromInt(ActorId));
2562 }
2563 return R<void>::Success();
2564 };
2565
2566 BIND_SYNC(reset_traffic_light_group) << [this](
2567 cr::ActorId ActorId) -> R<void>
2568 {
2570 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2571 if (!CarlaActor)
2572 {
2573 return RespondError(
2574 "reset_traffic_light_group",
2576 " Actor Id: " + FString::FromInt(ActorId));
2577 }
2578 ECarlaServerResponse Response =
2579 CarlaActor->ResetTrafficLightGroup();
2580 if (Response != ECarlaServerResponse::Success)
2581 {
2582 return RespondError(
2583 "reset_traffic_light_group",
2584 Response,
2585 " Actor Id: " + FString::FromInt(ActorId));
2586 }
2587 return R<void>::Success();
2588 };
2589
2590 BIND_SYNC(reset_all_traffic_lights) << [this]() -> R<void>
2591 {
2593 for (TActorIterator<ATrafficLightGroup> It(Episode->GetWorld()); It; ++It)
2594 {
2595 It->ResetGroup();
2596 }
2597 return R<void>::Success();
2598 };
2599
2600 BIND_SYNC(freeze_all_traffic_lights) << [this]
2601 (bool frozen) -> R<void>
2602 {
2604 auto* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
2605 if (!GameMode)
2606 {
2607 RESPOND_ERROR("unable to find CARLA game mode");
2608 }
2609 auto* TraffiLightManager = GameMode->GetTrafficLightManager();
2610 TraffiLightManager->SetFrozen(frozen);
2611 return R<void>::Success();
2612 };
2613
2614 BIND_SYNC(get_vehicle_light_states) << [this]() -> R<cr::VehicleLightStateList>
2615 {
2617 cr::VehicleLightStateList List;
2618
2619 auto It = Episode->GetActorRegistry().begin();
2620 for (; It != Episode->GetActorRegistry().end(); ++It)
2621 {
2622 const FCarlaActor& View = *(It.Value().Get());
2624 {
2625 if(View.IsDormant())
2626 {
2627 // todo: implement
2628 }
2629 else
2630 {
2631 auto Actor = View.GetActor();
2632 if (!Actor->IsPendingKill())
2633 {
2634 const ACarlaWheeledVehicle *Vehicle = Cast<ACarlaWheeledVehicle>(Actor);
2635 List.emplace_back(
2636 View.GetActorId(),
2637 cr::VehicleLightState(Vehicle->GetVehicleLightState()).GetLightStateAsValue());
2638 }
2639 }
2640 }
2641 }
2642 return List;
2643 };
2644
2645 BIND_SYNC(get_group_traffic_lights) << [this](
2646 const cr::ActorId ActorId) -> R<std::vector<cr::ActorId>>
2647 {
2649 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2650 if (!CarlaActor)
2651 {
2652 RESPOND_ERROR("unable to get group traffic lights: actor not found");
2653 }
2654 if (CarlaActor->IsDormant())
2655 {
2656 //todo implement
2657 return std::vector<cr::ActorId>();
2658 }
2659 else
2660 {
2661 auto TrafficLight = Cast<ATrafficLightBase>(CarlaActor->GetActor());
2662 if (TrafficLight == nullptr)
2663 {
2664 RESPOND_ERROR("unable to get group traffic lights: actor is not a traffic light");
2665 }
2666 std::vector<cr::ActorId> Result;
2667 for (auto* TLight : TrafficLight->GetGroupTrafficLights())
2668 {
2669 auto* View = Episode->FindCarlaActor(TLight);
2670 if (View)
2671 {
2672 Result.push_back(View->GetActorId());
2673 }
2674 }
2675 return Result;
2676 }
2677 };
2678
2679 BIND_SYNC(get_light_boxes) << [this](
2680 const cr::ActorId ActorId) -> R<std::vector<cg::BoundingBox>>
2681 {
2683 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2684 if (!CarlaActor)
2685 {
2686 return RespondError(
2687 "get_light_boxes",
2689 " Actor Id: " + FString::FromInt(ActorId));
2690 }
2691 if (CarlaActor->IsDormant())
2692 {
2693 return RespondError(
2694 "get_light_boxes",
2696 " Actor Id: " + FString::FromInt(ActorId));
2697 }
2698 else
2699 {
2700 ATrafficLightBase* TrafficLight = Cast<ATrafficLightBase>(CarlaActor->GetActor());
2701 if (!TrafficLight)
2702 {
2703 return RespondError(
2704 "get_light_boxes",
2706 " Actor Id: " + FString::FromInt(ActorId));
2707 }
2708 TArray<FBoundingBox> Result;
2709 TArray<uint8> OutTag;
2711 TrafficLight, Result, OutTag,
2712 static_cast<uint8>(carla::rpc::CityObjectLabel::TrafficLight));
2713 return MakeVectorFromTArray<cg::BoundingBox>(Result);
2714 }
2715 };
2716
2717 // ~~ GBuffer tokens ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2718 BIND_SYNC(get_gbuffer_token) << [this](const cr::ActorId ActorId, uint32_t GBufferId) -> R<std::vector<unsigned char>>
2719 {
2721 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2722 if(!CarlaActor)
2723 {
2724 return RespondError(
2725 "get_gbuffer_token",
2727 " Actor Id: " + FString::FromInt(ActorId));
2728 }
2729 if (CarlaActor->IsDormant())
2730 {
2731 return RespondError(
2732 "get_gbuffer_token",
2734 " Actor Id: " + FString::FromInt(ActorId));
2735 }
2736 ASceneCaptureSensor* Sensor = Cast<ASceneCaptureSensor>(CarlaActor->GetActor());
2737 if (!Sensor)
2738 {
2739 return RespondError(
2740 "get_gbuffer_token",
2742 " Actor Id: " + FString::FromInt(ActorId));
2743 }
2744
2745 switch (GBufferId)
2746 {
2747 case 0:
2748 {
2749 const auto &Token = Sensor->CameraGBuffers.SceneColor.GetToken();
2750 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2751 }
2752 case 1:
2753 {
2754 const auto &Token = Sensor->CameraGBuffers.SceneDepth.GetToken();
2755 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2756 }
2757 case 2:
2758 {
2759 const auto& Token = Sensor->CameraGBuffers.SceneStencil.GetToken();
2760 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2761 }
2762 case 3:
2763 {
2764 const auto &Token = Sensor->CameraGBuffers.GBufferA.GetToken();
2765 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2766 }
2767 case 4:
2768 {
2769 const auto &Token = Sensor->CameraGBuffers.GBufferB.GetToken();
2770 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2771 }
2772 case 5:
2773 {
2774 const auto &Token = Sensor->CameraGBuffers.GBufferC.GetToken();
2775 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2776 }
2777 case 6:
2778 {
2779 const auto &Token = Sensor->CameraGBuffers.GBufferD.GetToken();
2780 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2781 }
2782 case 7:
2783 {
2784 const auto &Token = Sensor->CameraGBuffers.GBufferE.GetToken();
2785 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2786 }
2787 case 8:
2788 {
2789 const auto &Token = Sensor->CameraGBuffers.GBufferF.GetToken();
2790 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2791 }
2792 case 9:
2793 {
2794 const auto &Token = Sensor->CameraGBuffers.Velocity.GetToken();
2795 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2796 }
2797 case 10:
2798 {
2799 const auto &Token = Sensor->CameraGBuffers.SSAO.GetToken();
2800 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2801 }
2802 case 11:
2803 {
2804 const auto& Token = Sensor->CameraGBuffers.CustomDepth.GetToken();
2805 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2806 }
2807 case 12:
2808 {
2809 const auto& Token = Sensor->CameraGBuffers.CustomStencil.GetToken();
2810 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2811 }
2812 default:
2813 UE_LOG(LogCarla, Error, TEXT("Requested invalid GBuffer ID %u"), GBufferId);
2814 return {};
2815 }
2816 };
2817
2818 // ~~ Logging and playback ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2819
2820 BIND_SYNC(start_recorder) << [this](std::string name, bool AdditionalData) -> R<std::string>
2821 {
2823 return R<std::string>(Episode->StartRecorder(name, AdditionalData));
2824 };
2825
2826 BIND_SYNC(stop_recorder) << [this]() -> R<void>
2827 {
2829 Episode->GetRecorder()->Stop();
2830 return R<void>::Success();
2831 };
2832
2833 BIND_SYNC(show_recorder_file_info) << [this](
2834 std::string name,
2835 bool show_all) -> R<std::string>
2836 {
2838 return R<std::string>(Episode->GetRecorder()->ShowFileInfo(
2839 name,
2840 show_all));
2841 };
2842
2843 BIND_SYNC(show_recorder_collisions) << [this](
2844 std::string name,
2845 char type1,
2846 char type2) -> R<std::string>
2847 {
2849 return R<std::string>(Episode->GetRecorder()->ShowFileCollisions(
2850 name,
2851 type1,
2852 type2));
2853 };
2854
2855 BIND_SYNC(show_recorder_actors_blocked) << [this](
2856 std::string name,
2857 double min_time,
2858 double min_distance) -> R<std::string>
2859 {
2861 return R<std::string>(Episode->GetRecorder()->ShowFileActorsBlocked(
2862 name,
2863 min_time,
2864 min_distance));
2865 };
2866
2867 BIND_SYNC(replay_file) << [this](
2868 std::string name,
2869 double start,
2870 double duration,
2871 uint32_t follow_id,
2872 bool replay_sensors) -> R<std::string>
2873 {
2875 return R<std::string>(Episode->GetRecorder()->ReplayFile(
2876 name,
2877 start,
2878 duration,
2879 follow_id,
2880 replay_sensors));
2881 };
2882
2883 BIND_SYNC(set_replayer_time_factor) << [this](double time_factor) -> R<void>
2884 {
2886 Episode->GetRecorder()->SetReplayerTimeFactor(time_factor);
2887 return R<void>::Success();
2888 };
2889
2890 BIND_SYNC(set_replayer_ignore_hero) << [this](bool ignore_hero) -> R<void>
2891 {
2893 Episode->GetRecorder()->SetReplayerIgnoreHero(ignore_hero);
2894 return R<void>::Success();
2895 };
2896
2897 BIND_SYNC(set_replayer_ignore_spectator) << [this](bool ignore_spectator) -> R<void>
2898 {
2900 Episode->GetRecorder()->SetReplayerIgnoreSpectator(ignore_spectator);
2901 return R<void>::Success();
2902 };
2903
2904 BIND_SYNC(stop_replayer) << [this](bool keep_actors) -> R<void>
2905 {
2907 Episode->GetRecorder()->StopReplayer(keep_actors);
2908 return R<void>::Success();
2909 };
2910
2911 // ~~ Draw debug shapes ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2912
2913 BIND_SYNC(draw_debug_shape) << [this](const cr::DebugShape &shape) -> R<void>
2914 {
2916 auto *World = Episode->GetWorld();
2917 check(World != nullptr);
2918 FDebugShapeDrawer Drawer(*World);
2919 Drawer.Draw(shape);
2920 return R<void>::Success();
2921 };
2922
2923 // ~~ Apply commands in batch ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2924
2925 using C = cr::Command;
2926 using CR = cr::CommandResponse;
2927 using ActorId = carla::ActorId;
2928
2929 auto parse_result = [](ActorId id, const auto &response) {
2930 return response.HasError() ? CR{response.GetError()} : CR{id};
2931 };
2932
2933#define MAKE_RESULT(operation) return parse_result(c.actor, operation);
2934
2935 auto command_visitor = carla::Functional::MakeRecursiveOverload(
2936 [=](auto self, const C::SpawnActor &c) -> CR {
2937 auto result = c.parent.has_value() ?
2938 spawn_actor_with_parent(
2939 c.description,
2940 c.transform,
2941 *c.parent,
2942 cr::AttachmentType::Rigid,
2943 c.socket_name) :
2944 spawn_actor(c.description, c.transform);
2945 if (!result.HasError())
2946 {
2947 ActorId id = result.Get().id;
2948 auto set_id = carla::Functional::MakeOverload(
2949 [](C::SpawnActor &) {},
2950 [](C::ConsoleCommand &) {},
2951 [id](auto &s) { s.actor = id; });
2952 for (auto command : c.do_after)
2953 {
2954 boost::variant2::visit(set_id, command.command);
2955 boost::variant2::visit(self, command.command);
2956 }
2957 return id;
2958 }
2959 return result.GetError();
2960 },
2961 [=](auto, const C::DestroyActor &c) { MAKE_RESULT(destroy_actor(c.actor)); },
2962 [=](auto, const C::ApplyVehicleControl &c) { MAKE_RESULT(apply_control_to_vehicle(c.actor, c.control)); },
2963 [=](auto, const C::ApplyVehicleAckermannControl &c) { MAKE_RESULT(apply_ackermann_control_to_vehicle(c.actor, c.control)); },
2964 [=](auto, const C::ApplyWalkerControl &c) { MAKE_RESULT(apply_control_to_walker(c.actor, c.control)); },
2965 [=](auto, const C::ApplyVehiclePhysicsControl &c) { MAKE_RESULT(apply_physics_control(c.actor, c.physics_control)); },
2966 [=](auto, const C::ApplyTransform &c) { MAKE_RESULT(set_actor_transform(c.actor, c.transform)); },
2967 [=](auto, const C::ApplyTargetVelocity &c) { MAKE_RESULT(set_actor_target_velocity(c.actor, c.velocity)); },
2968 [=](auto, const C::ApplyTargetAngularVelocity &c) { MAKE_RESULT(set_actor_target_angular_velocity(c.actor, c.angular_velocity)); },
2969 [=](auto, const C::ApplyImpulse &c) { MAKE_RESULT(add_actor_impulse(c.actor, c.impulse)); },
2970 [=](auto, const C::ApplyForce &c) { MAKE_RESULT(add_actor_force(c.actor, c.force)); },
2971 [=](auto, const C::ApplyAngularImpulse &c) { MAKE_RESULT(add_actor_angular_impulse(c.actor, c.impulse)); },
2972 [=](auto, const C::ApplyTorque &c) { MAKE_RESULT(add_actor_torque(c.actor, c.torque)); },
2973 [=](auto, const C::SetSimulatePhysics &c) { MAKE_RESULT(set_actor_simulate_physics(c.actor, c.enabled)); },
2974 [=](auto, const C::SetEnableGravity &c) { MAKE_RESULT(set_actor_enable_gravity(c.actor, c.enabled)); },
2975 // TODO: SetAutopilot should be removed. This is the old way to control the vehicles
2976 [=](auto, const C::SetAutopilot &c) { MAKE_RESULT(set_actor_autopilot(c.actor, c.enabled)); },
2977 [=](auto, const C::ShowDebugTelemetry &c) { MAKE_RESULT(show_vehicle_debug_telemetry(c.actor, c.enabled)); },
2978 [=](auto, const C::SetVehicleLightState &c) { MAKE_RESULT(set_vehicle_light_state(c.actor, c.light_state)); },
2979// [=](auto, const C::OpenVehicleDoor &c) { MAKE_RESULT(open_vehicle_door(c.actor, c.door_idx)); },
2980// [=](auto, const C::CloseVehicleDoor &c) { MAKE_RESULT(close_vehicle_door(c.actor, c.door_idx)); },
2981 [=](auto, const C::ApplyWalkerState &c) { MAKE_RESULT(set_walker_state(c.actor, c.transform, c.speed)); },
2982 [=](auto, const C::ConsoleCommand& c) -> CR { return console_command(c.cmd); },
2983 [=](auto, const C::SetTrafficLightState& c) { MAKE_RESULT(set_traffic_light_state(c.actor, c.traffic_light_state)); },
2984 [=](auto, const C::ApplyLocation& c) { MAKE_RESULT(set_actor_location(c.actor, c.location)); }
2985 );
2986
2987#undef MAKE_RESULT
2988
2989 BIND_SYNC(apply_batch) << [=](
2990 const std::vector<cr::Command> &commands,
2991 bool do_tick_cue)
2992 {
2993 std::vector<CR> result;
2994 result.reserve(commands.size());
2995 for (const auto &command : commands)
2996 {
2997 result.emplace_back(boost::variant2::visit(command_visitor, command.command));
2998 }
2999 if (do_tick_cue)
3000 {
3001 tick_cue();
3002 }
3003 return result;
3004 };
3005
3006 // ~~ Light Subsystem ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3007
3008 BIND_SYNC(query_lights_state) << [this](std::string client) -> R<std::vector<cr::LightState>>
3009 {
3011 std::vector<cr::LightState> result;
3012 auto *World = Episode->GetWorld();
3013 if(World) {
3014 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
3015 result = CarlaLightSubsystem->GetLights(FString(client.c_str()));
3016 }
3017 return result;
3018 };
3019
3020 BIND_SYNC(update_lights_state) << [this]
3021 (std::string client, const std::vector<cr::LightState>& lights, bool discard_client) -> R<void>
3022 {
3024 auto *World = Episode->GetWorld();
3025 if(World) {
3026 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
3027 CarlaLightSubsystem->SetLights(FString(client.c_str()), lights, discard_client);
3028 }
3029 return R<void>::Success();
3030 };
3031
3032 BIND_SYNC(update_day_night_cycle) << [this]
3033 (std::string client, const bool active) -> R<void>
3034 {
3036 auto *World = Episode->GetWorld();
3037 if(World) {
3038 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
3039 CarlaLightSubsystem->SetDayNightCycle(active);
3040 }
3041 return R<void>::Success();
3042 };
3043
3044
3045 // ~~ Ray Casting ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3046
3047 BIND_SYNC(project_point) << [this]
3048 (cr::Location Location, cr::Vector3D Direction, float SearchDistance)
3049 -> R<std::pair<bool,cr::LabelledPoint>>
3050 {
3052 auto *World = Episode->GetWorld();
3053 constexpr float meter_to_centimeter = 100.0f;
3054 FVector UELocation = Location;
3055 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
3056 ALargeMapManager* LargeMap = GameMode->GetLMManager();
3057 if (LargeMap)
3058 {
3059 UELocation = LargeMap->GlobalToLocalLocation(UELocation);
3060 }
3061 return URayTracer::ProjectPoint(UELocation, Direction.ToFVector(),
3062 meter_to_centimeter * SearchDistance, World);
3063 };
3064
3065 BIND_SYNC(cast_ray) << [this]
3066 (cr::Location StartLocation, cr::Location EndLocation)
3067 -> R<std::vector<cr::LabelledPoint>>
3068 {
3070 auto *World = Episode->GetWorld();
3071 FVector UEStartLocation = StartLocation;
3072 FVector UEEndLocation = EndLocation;
3073 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
3074 ALargeMapManager* LargeMap = GameMode->GetLMManager();
3075 if (LargeMap)
3076 {
3077 UEStartLocation = LargeMap->GlobalToLocalLocation(UEStartLocation);
3078 UEEndLocation = LargeMap->GlobalToLocalLocation(UEEndLocation);
3079 }
3080 return URayTracer::CastRay(StartLocation, EndLocation, World);
3081 };
3082
3083}
3084
3085// =============================================================================
3086// -- Undef helper macros ------------------------------------------------------
3087// =============================================================================
3088
3089#undef BIND_ASYNC
3090#undef BIND_SYNC
3091#undef REQUIRE_CARLA_EPISODE
3092#undef RESPOND_ERROR_FSTRING
3093#undef RESPOND_ERROR
3094#undef CARLA_ENSURE_GAME_THREAD
3095
3096// =============================================================================
3097// -- FCarlaServer -------------------------------------------------------
3098// =============================================================================
3099
3101
3105
3106FDataMultiStream FCarlaServer::Start(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
3107{
3108 Pimpl = MakeUnique<FPimpl>(RPCPort, StreamingPort, SecondaryPort);
3109 StreamingPort = Pimpl->StreamingServer.GetLocalEndpoint().port();
3110 SecondaryPort = Pimpl->SecondaryServer->GetLocalEndpoint().port();
3111
3112 UE_LOG(
3113 LogCarlaServer,
3114 Log,
3115 TEXT("Initialized CarlaServer: Ports(rpc=%d, streaming=%d, secondary=%d)"),
3116 RPCPort,
3117 StreamingPort,
3118 SecondaryPort);
3119 return Pimpl->BroadcastStream;
3120}
3121
3122void FCarlaServer::NotifyBeginEpisode(UCarlaEpisode &Episode)
3123{
3124 check(Pimpl != nullptr);
3125 UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName());
3126 Pimpl->Episode = &Episode;
3127}
3128
3130{
3131 check(Pimpl != nullptr);
3132 Pimpl->Episode = nullptr;
3133}
3134
3135void FCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads)
3136{
3137 check(Pimpl != nullptr);
3138 /// @todo Define better the number of threads each server gets.
3139 int ThreadsPerServer = std::max(2u, NumberOfWorkerThreads / 3u);
3140 int32_t RPCThreads;
3141 int32_t StreamingThreads;
3142 int32_t SecondaryThreads;
3143
3144 UE_LOG(LogCarla, Log, TEXT("FCommandLine %s"), FCommandLine::Get());
3145
3146 if(!FParse::Value(FCommandLine::Get(), TEXT("-RPCThreads="), RPCThreads))
3147 {
3148 RPCThreads = ThreadsPerServer;
3149 }
3150 if(!FParse::Value(FCommandLine::Get(), TEXT("-StreamingThreads="), StreamingThreads))
3151 {
3152 StreamingThreads = ThreadsPerServer;
3153 }
3154 if(!FParse::Value(FCommandLine::Get(), TEXT("-SecondaryThreads="), SecondaryThreads))
3155 {
3156 SecondaryThreads = ThreadsPerServer;
3157 }
3158
3159 UE_LOG(LogCarla, Log, TEXT("FCarlaServer AsyncRun %d, RPCThreads %d, StreamingThreads %d, SecondaryThreads %d"),
3160 NumberOfWorkerThreads, RPCThreads, StreamingThreads, SecondaryThreads);
3161
3162 Pimpl->Server.AsyncRun(RPCThreads);
3163 Pimpl->StreamingServer.AsyncRun(StreamingThreads);
3164 Pimpl->SecondaryServer->AsyncRun(SecondaryThreads);
3165}
3166
3167void FCarlaServer::RunSome(uint32 Milliseconds)
3168{
3169 TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
3170 Pimpl->Server.SyncRunFor(carla::time_duration::milliseconds(Milliseconds));
3171}
3172
3174{
3175 (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release);
3176}
3177
3179{
3180 auto k = Pimpl->TickCuesReceived.fetch_sub(1, std::memory_order_acquire);
3181 bool flag = (k > 0);
3182 if (!flag)
3183 (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release);
3184 return flag;
3185}
3186
3188{
3189 if (Pimpl)
3190 {
3191 Pimpl->Server.Stop();
3192 Pimpl->SecondaryServer->Stop();
3193 }
3194}
3195
3197{
3198 check(Pimpl != nullptr);
3199 return Pimpl->StreamingServer.MakeStream();
3200}
3201
3202std::shared_ptr<carla::multigpu::Router> FCarlaServer::GetSecondaryServer()
3203{
3204 return Pimpl->GetSecondaryServer();
3205}
3206
3208{
3209 return Pimpl->StreamingServer;
3210}
EAttachmentType
FVehicleLightState LightState
Definition ActorData.h:131
FVehiclePhysicsControl PhysicsControl
Definition ActorData.h:116
FVehicleControl Control
Definition ActorData.h:119
UE_LOG(LogCarla, Log, TEXT("UActorDispatcher::Destroying actor: '%s' %x"), *Id, Actor)
auto end() const noexcept
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld * World
TSharedPtr< const FActorInfo > carla::rpc::ActorState UWorld Actor
FString CarlaGetStringError(ECarlaServerResponse Response)
ECarlaServerResponse
#define REQUIRE_CARLA_EPISODE()
#define MAKE_RESULT(operation)
#define RESPOND_ERROR(str)
#define BIND_SYNC(name)
#define RESPOND_ERROR_FSTRING(fstr)
carla::rpc::ResponseError RespondError(const FString &FuncName, const FString &ErrorMessage, const FString &ExtraInfo="")
static std::vector< T > MakeVectorFromTArray(const TArray< Other > &Array)
#define BIND_ASYNC(name)
EVehicleWheelLocation
EVehicleDoor
Type of door to open/close
包含与Carla流处理相关的底层细节的头文件。
CARLA Game Mode 的基类。
void UnLoadMapLayer(int32 MapLayers)
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
TArray< FEnvironmentObject > GetEnvironmentObjects(uint8 QueriedTag=0xFF) const
AActor * FindActorByName(const FString &ActorName)
void LoadMapLayer(int32 MapLayers)
void ApplyTextureToActor(AActor *Actor, UTexture2D *Texture, const carla::rpc::MaterialParameter &TextureParam)
const FString GetFullMapPath() const
ALargeMapManager * GetLMManager() const
TArray< FString > GetNamesOfAllActors()
TArray< FBoundingBox > GetAllBBsOfLevel(uint8 TagQueried=0xFF) const
UTexture2D * CreateUETexture(const carla::rpc::TextureColor &Texture)
Base class for CARLA wheeled vehicles.
void Send(const FString message)
void ConsiderSpectatorAsEgo(bool _SpectatorAsEgo)
void OnActorSpawned(const FCarlaActor &CarlaActor)
FVector GlobalToLocalLocation(const FVector &InLocation) const
FTransform LocalToGlobalTransform(const FTransform &InTransform) const
FVector LocalToGlobalLocation(const FVector &InLocation) const
Base class for sensors using a USceneCaptureComponent2D for rendering the scene.
FCameraGBufferUint8 CustomDepth
FCameraGBufferUint8 GBufferD
struct ASceneCaptureSensor::@0 CameraGBuffers
FCameraGBufferUint8 GBufferE
FCameraGBufferUint8 GBufferF
FCameraGBufferUint8 GBufferA
FCameraGBufferUint8 SceneDepth
FCameraGBufferUint8 SceneStencil
FCameraGBufferUint8 SSAO
FCameraGBufferUint8 GBufferC
FCameraGBufferUint8 CustomStencil
FCameraGBufferUint8 Velocity
FCameraGBufferUint8 SceneColor
FCameraGBufferUint8 GBufferB
查看一个参与者和它的属性
Definition CarlaActor.h:23
ECarlaServerResponse AddActorImpulseAtLocation(const FVector &Impulse, const FVector &Location)
virtual ECarlaServerResponse GetPhysicsControl(FVehiclePhysicsControl &)
Definition CarlaActor.h:204
ECarlaServerResponse AddActorForceAtLocation(const FVector &Force, const FVector &Location)
virtual ECarlaServerResponse SetActorEnableGravity(bool bEnabled)
virtual ECarlaServerResponse GetBonesTransform(FWalkerBoneControlOut &)
Definition CarlaActor.h:369
virtual ECarlaServerResponse GetAckermannControllerSettings(FAckermannControllerSettings &)
Definition CarlaActor.h:271
virtual ECarlaServerResponse SetLightRedTime(float)
Definition CarlaActor.h:344
virtual ECarlaServerResponse ResetTrafficLightGroup()
Definition CarlaActor.h:399
IdType GetParent() const
Definition CarlaActor.h:99
ActorType GetActorType() const
Definition CarlaActor.h:71
virtual ECarlaServerResponse SetLightYellowTime(float)
Definition CarlaActor.h:339
virtual ECarlaServerResponse GetPoseFromAnimation()
Definition CarlaActor.h:384
virtual ECarlaServerResponse SetActorAutopilot(bool, bool bKeepState=false)
Definition CarlaActor.h:281
ECarlaServerResponse AddActorTorque(const FVector &Torque)
ECarlaServerResponse SetActorTargetAngularVelocity(const FVector &AngularVelocity)
bool IsDormant() const
Definition CarlaActor.h:59
ECarlaServerResponse AddActorImpulse(const FVector &Impulse)
AActor * GetActor()
Definition CarlaActor.h:75
virtual ECarlaServerResponse SetVehicleLightState(const FVehicleLightState &)
Definition CarlaActor.h:234
virtual ECarlaServerResponse SetActorDead()
Definition CarlaActor.h:389
virtual ECarlaServerResponse ApplyControlToVehicle(const FVehicleControl &, const EVehicleInputPriority &)
Definition CarlaActor.h:249
virtual ECarlaServerResponse GetWheelSteerAngle(const EVehicleWheelLocation &, float &)
Definition CarlaActor.h:244
virtual ECarlaServerResponse ApplyAckermannControllerSettings(const FAckermannControllerSettings &)
Definition CarlaActor.h:276
virtual ECarlaServerResponse SetActorCollisions(bool bEnabled)
virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData &)
Definition CarlaActor.h:286
virtual ECarlaServerResponse CloseVehicleDoor(const EVehicleDoor)
Definition CarlaActor.h:224
virtual ECarlaServerResponse RestorePhysXPhysics()
Definition CarlaActor.h:312
virtual ECarlaServerResponse ApplyAckermannControlToVehicle(const FVehicleAckermannControl &, const EVehicleInputPriority &)
Definition CarlaActor.h:255
void SetParent(IdType InParentId)
Definition CarlaActor.h:95
void SetAttachmentType(carla::rpc::AttachmentType InAttachmentType)
Definition CarlaActor.h:116
virtual ECarlaServerResponse SetWalkerState(const FTransform &Transform, carla::rpc::WalkerControl WalkerControl)
Definition CarlaActor.h:352
virtual ECarlaServerResponse DisableActorConstantVelocity()
Definition CarlaActor.h:199
virtual ECarlaServerResponse GetVehicleLightState(FVehicleLightState &)
Definition CarlaActor.h:214
virtual ECarlaServerResponse SetBonesTransform(const FWalkerBoneControlIn &)
Definition CarlaActor.h:374
virtual ECarlaServerResponse FreezeTrafficLight(bool)
Definition CarlaActor.h:394
void SetActorGlobalTransform(const FTransform &Transform, ETeleportType Teleport=ETeleportType::TeleportPhysics)
virtual ECarlaServerResponse ApplyControlToWalker(const FWalkerControl &)
Definition CarlaActor.h:359
void SetActorState(carla::rpc::ActorState InState)
Definition CarlaActor.h:91
void SetActorGlobalLocation(const FVector &Location, ETeleportType Teleport=ETeleportType::TeleportPhysics)
virtual ECarlaServerResponse UseCarSimRoad(bool)
Definition CarlaActor.h:301
virtual ECarlaServerResponse ApplyPhysicsControl(const FVehiclePhysicsControl &)
Definition CarlaActor.h:229
virtual ECarlaServerResponse SetLightGreenTime(float)
Definition CarlaActor.h:334
void AddChildren(IdType ChildId)
Definition CarlaActor.h:103
virtual ECarlaServerResponse OpenVehicleDoor(const EVehicleDoor)
Definition CarlaActor.h:219
const FActorInfo * GetActorInfo() const
Definition CarlaActor.h:83
IdType GetActorId() const
Definition CarlaActor.h:67
virtual ECarlaServerResponse EnableActorConstantVelocity(const FVector &)
Definition CarlaActor.h:194
virtual ECarlaServerResponse SetWheelSteerDirection(const EVehicleWheelLocation &, float)
Definition CarlaActor.h:239
virtual ECarlaServerResponse EnableCarSim(const FString &)
Definition CarlaActor.h:296
ECarlaServerResponse SetActorTargetVelocity(const FVector &Velocity)
ECarlaServerResponse AddActorForce(const FVector &Force)
virtual ECarlaServerResponse BlendPose(float Blend)
Definition CarlaActor.h:379
virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool)
Definition CarlaActor.h:291
virtual ECarlaServerResponse SetActorSimulatePhysics(bool bEnabled)
virtual ECarlaServerResponse EnableChronoPhysics(uint64_t, float, const FString &, const FString &, const FString &, const FString &)
Definition CarlaActor.h:306
ECarlaServerResponse AddActorAngularImpulse(const FVector &AngularInpulse)
virtual ECarlaServerResponse SetTrafficLightState(const ETrafficLightState &)
Definition CarlaActor.h:319
void PutActorToSleep(UCarlaEpisode *CarlaEpisode)
static uint64_t GetFrameCounter()
Definition CarlaEngine.h:68
carla::streaming::Stream BroadcastStream
carla::streaming::Server StreamingServer
std::shared_ptr< carla::multigpu::Router > SecondaryServer
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
UCarlaEpisode * Episode
carla::rpc::Server Server
std::atomic_size_t TickCuesReceived
FPimpl(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
std::map< uint16_t, std::string > TrafficManagerInfo
仿真中所有活动的交通管理器对 < port, ip > 的映射
bool TickCueReceived()
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
void RunSome(uint32 Milliseconds)
TUniquePtr< FPimpl > Pimpl
Definition CarlaServer.h:74
carla::streaming::Server & GetStreamingServer()
FDataStream OpenStream() const
void NotifyEndEpisode()
void NotifyBeginEpisode(UCarlaEpisode &Episode)
FDataMultiStream Start(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
void AsyncRun(uint32 NumberOfWorkerThreads)
void Draw(const carla::rpc::DebugShape &Shape)
static TArray< uint8 > Load(FString MapName)
Return the Navigation Mesh Binary associated to MapName, or empty if the such file wasn't serialized.
constexpr ServerBinder(const char *name, carla::rpc::Server &srv, bool sync)
auto operator<<(FuncT func)
const char * _name
carla::rpc::Server & _server
static void GetTrafficLightBoundingBox(const ATrafficLightBase *TrafficLight, TArray< FBoundingBox > &OutBB, TArray< uint8 > &OutTag, uint8 InTagQueried=0xFF)
void SetMapLayer(int32 MapLayer)
std::vector< carla::rpc::LightState > GetLights(FString Client)
void SetLights(FString Client, std::vector< carla::rpc::LightState > LightsToSet, bool DiscardClient=false)
void SetDayNightCycle(const bool active)
static UCarlaGameInstance * GetGameInstance(const UObject *WorldContextObject)
static ALargeMapManager * GetLargeMapManager(const UObject *WorldContextObject)
static TArray< FString > GetAllMapNames()
static ACarlaGameModeBase * GetGameMode(const UObject *WorldContextObject)
static FString GetXODR(const UWorld *World)
MapNameOpenDrive XMLҲļ򷵻ؿա
static std::pair< bool, carla::rpc::LabelledPoint > ProjectPoint(FVector StartLocation, FVector Direction, float MaxDistance, UWorld *World)
Definition RayTracer.cpp:49
static std::vector< carla::rpc::LabelledPoint > CastRay(FVector StartLocation, FVector EndLocation, UWorld *World)
Definition RayTracer.cpp:18
static auto MakeOverload(FuncTs &&... fs)
创建一个重载调用对象
Definition Functional.h:42
static auto MakeRecursiveOverload(FuncTs &&... fs)
创建递归重载调用对象
Definition Functional.h:57
Vector3D GetForwardVector() const
static std::shared_ptr< ROS2 > GetInstance()
Definition ROS2.h:51
一个RPC服务器,可以将功能绑定为同步或异步运行。
Definition rpc/Server.h:34
void BindSync(const std::string &name, FunctorT &&functor)
Definition rpc/Server.h:160
void BindAsync(const std::string &name, FunctorT &&functor)
Definition rpc/Server.h:169
A streaming server.
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)
void SetSynchronousMode(bool is_synchro)
Token token() const
与此流关联的 Token。客户端可使用该 Token 订阅此流。
constexpr size_t milliseconds() const noexcept
Definition Time.h:60
Carlaе·عܵռ
uint32_t stream_id_type
流ID的类型定义。
Definition Types.h:33
rpc::ActorId ActorId
Definition ActorId.h:26
包含CARLA客户端相关类和函数的命名空间。
TMap< FString, FActorAttribute > Variations
用户选择了参与者的变化版本。请注意,此时是 由不可修改的属性表示
FActorDescription Description
Definition ActorInfo.h:31
static FString StatusToString(EActorSpawnResultStatus Status)
auto GetToken() const
Return the token that allows subscribing to this sensor's stream.