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// -- Static local functions ---------------------------------------------------
89// =============================================================================
90
91template <typename T, typename Other>
92static std::vector<T> MakeVectorFromTArray(const TArray<Other> &Array)
93{
94 return {Array.GetData(), Array.GetData() + Array.Num()};
95}
96
97// =============================================================================
98// -- FCarlaServer::FPimpl -----------------------------------------------
99// =============================================================================
100
102{
103public:
104
105 FPimpl(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
106 : Server(RPCPort),
107 StreamingServer(StreamingPort),
108 BroadcastStream(StreamingServer.MakeStream())
109 {
110 // we need to create shared_ptr from the router for some handlers to live
111 SecondaryServer = std::make_shared<carla::multigpu::Router>(SecondaryPort);
112 SecondaryServer->SetCallbacks();
113 BindActions();
114 }
115
116 std::shared_ptr<carla::multigpu::Router> GetSecondaryServer() {
117 return SecondaryServer;
118 }
119
120 /// Map of pairs < port , ip > with all the Traffic Managers active in the simulation
121 std::map<uint16_t, std::string> TrafficManagerInfo;
122
124
126
128
129 std::shared_ptr<carla::multigpu::Router> SecondaryServer;
130
132
133 std::atomic_size_t TickCuesReceived { 0u };
134
135private:
136
137 void BindActions();
138};
139
140// =============================================================================
141// -- Define helper macros -----------------------------------------------------
142// =============================================================================
143
144#if WITH_EDITOR
145# define CARLA_ENSURE_GAME_THREAD() check(IsInGameThread());
146#else
147# define CARLA_ENSURE_GAME_THREAD()
148#endif // WITH_EDITOR
149
150#define RESPOND_ERROR(str) { \
151 UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), TEXT(str)); \
152 return carla::rpc::ResponseError(str); }
153
154#define RESPOND_ERROR_FSTRING(fstr) { \
155 UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), *fstr); \
156 return carla::rpc::ResponseError(carla::rpc::FromFString(fstr)); }
157
158#define REQUIRE_CARLA_EPISODE() \
159 CARLA_ENSURE_GAME_THREAD(); \
160 if (Episode == nullptr) { RESPOND_ERROR("episode not ready"); }
161
163 const FString& FuncName,
164 const FString& ErrorMessage,
165 const FString& ExtraInfo = "")
166{
167 FString TotalMessage = "Responding error from function " + FuncName + ": " +
168 ErrorMessage + ". " + ExtraInfo;
169 UE_LOG(LogCarlaServer, Log, TEXT("%s"), *TotalMessage);
170 return carla::rpc::ResponseError(carla::rpc::FromFString(TotalMessage));
171}
172
174 const FString& FuncName,
175 const ECarlaServerResponse& Error,
176 const FString& ExtraInfo = "")
177{
178 return RespondError(FuncName, CarlaGetStringError(Error), ExtraInfo);
179}
180
182{
183public:
184
185 constexpr ServerBinder(const char *name, carla::rpc::Server &srv, bool sync)
186 : _name(name),
187 _server(srv),
188 _sync(sync) {}
189
190 template <typename FuncT>
191 auto operator<<(FuncT func)
192 {
193 if (_sync)
194 {
195 _server.BindSync(_name, func);
196 }
197 else
198 {
199 _server.BindAsync(_name, func);
200 }
201 return func;
202 }
203
204private:
205
206 const char *_name;
207
209
210 bool _sync;
211};
212
213#define BIND_SYNC(name) auto name = ServerBinder(# name, Server, true)
214#define BIND_ASYNC(name) auto name = ServerBinder(# name, Server, false)
215
216// =============================================================================
217// -- Bind Actions -------------------------------------------------------------
218// =============================================================================
219
221{
222 namespace cr = carla::rpc;
223 namespace cg = carla::geom;
224
225 /// Looks for a Traffic Manager running on port
226 BIND_SYNC(is_traffic_manager_running) << [this] (uint16_t port) ->R<bool>
227 {
228 return (TrafficManagerInfo.find(port) != TrafficManagerInfo.end());
229 };
230
231 /// Gets a pair filled with the <IP, port> of the Trafic Manager running on port.
232 /// If there is no Traffic Manager running the pair will be ("", 0)
233 BIND_SYNC(get_traffic_manager_running) << [this] (uint16_t port) ->R<std::pair<std::string, uint16_t>>
234 {
235 auto it = TrafficManagerInfo.find(port);
236 if(it != TrafficManagerInfo.end()) {
237 return std::pair<std::string, uint16_t>(it->second, it->first);
238 }
239 return std::pair<std::string, uint16_t>("",0);
240 };
241
242 /// Add a new Traffic Manager running on <IP, port>
243 BIND_SYNC(add_traffic_manager_running) << [this] (std::pair<std::string, uint16_t> trafficManagerInfo) ->R<bool>
244 {
245 uint16_t port = trafficManagerInfo.second;
246 auto it = TrafficManagerInfo.find(port);
247 if(it == TrafficManagerInfo.end()) {
248 TrafficManagerInfo.insert(
249 std::pair<uint16_t, std::string>(port, trafficManagerInfo.first));
250 return true;
251 }
252 return false;
253
254 };
255
256 BIND_SYNC(destroy_traffic_manager) << [this] (uint16_t port) ->R<bool>
257 {
258 auto it = TrafficManagerInfo.find(port);
259 if(it != TrafficManagerInfo.end()) {
260 TrafficManagerInfo.erase(it);
261 return true;
262 }
263 return false;
264 };
265
266 BIND_ASYNC(version) << [] () -> R<std::string>
267 {
268 return carla::version();
269 };
270
271 // ~~ Tick ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
272
273 BIND_SYNC(tick_cue) << [this]() -> R<uint64_t>
274 {
275 TRACE_CPUPROFILER_EVENT_SCOPE(TickCueReceived);
276 auto Current = FCarlaEngine::GetFrameCounter();
277 (void)TickCuesReceived.fetch_add(1, std::memory_order_release);
278 return Current + 1;
279 };
280
281 // ~~ Load new episode ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
282
283 BIND_ASYNC(get_available_maps) << [this]() -> R<std::vector<std::string>>
284 {
285 const auto MapNames = UCarlaStatics::GetAllMapNames();
286 std::vector<std::string> result;
287 result.reserve(MapNames.Num());
288 for (const auto &MapName : MapNames)
289 {
290 if (MapName.Contains("/Sublevels/"))
291 continue;
292 if (MapName.Contains("/BaseMap/"))
293 continue;
294 if (MapName.Contains("/BaseLargeMap/"))
295 continue;
296 if (MapName.Contains("_Tile_"))
297 continue;
298
299 result.emplace_back(cr::FromFString(MapName));
300 }
301 return result;
302 };
303
304 BIND_SYNC(load_new_episode) << [this](const std::string &map_name, const bool reset_settings, cr::MapLayer MapLayers) -> R<void>
305 {
307
308 UCarlaGameInstance* GameInstance = UCarlaStatics::GetGameInstance(Episode->GetWorld());
309 if (!GameInstance)
310 {
311 RESPOND_ERROR("unable to find CARLA game instance");
312 }
313 GameInstance->SetMapLayer(static_cast<int32>(MapLayers));
314
315 if(!Episode->LoadNewEpisode(cr::ToFString(map_name), reset_settings))
316 {
317 FString Str(TEXT("Map '"));
318 Str += cr::ToFString(map_name);
319 Str += TEXT("' not found");
321 }
322
323 return R<void>::Success();
324 };
325
326 BIND_SYNC(load_map_layer) << [this](cr::MapLayer MapLayers) -> R<void>
327 {
329
331 if (!GameMode)
332 {
333 RESPOND_ERROR("unable to find CARLA game mode");
334 }
335 GameMode->LoadMapLayer(static_cast<int32>(MapLayers));
336
337 return R<void>::Success();
338 };
339
340 BIND_SYNC(unload_map_layer) << [this](cr::MapLayer MapLayers) -> R<void>
341 {
343
345 if (!GameMode)
346 {
347 RESPOND_ERROR("unable to find CARLA game mode");
348 }
349 GameMode->UnLoadMapLayer(static_cast<int32>(MapLayers));
350
351 return R<void>::Success();
352 };
353
354 BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, cr::OpendriveGenerationParameters Params) -> R<void>
355 {
357 if (!Episode->LoadNewOpendriveEpisode(cr::ToLongFString(opendrive), Params))
358 {
359 RESPOND_ERROR("opendrive could not be correctly parsed");
360 }
361 return R<void>::Success();
362 };
363
364 BIND_SYNC(apply_color_texture_to_objects) << [this](
365 const std::vector<std::string> &actors_name,
366 const cr::MaterialParameter& parameter,
367 const cr::TextureColor& Texture) -> R<void>
368 {
371 if (!GameMode)
372 {
373 RESPOND_ERROR("unable to find CARLA game mode");
374 }
375 TArray<AActor*> ActorsToPaint;
376 for(const std::string& actor_name : actors_name)
377 {
378 AActor* ActorToPaint = GameMode->FindActorByName(cr::ToFString(actor_name));
379 if (ActorToPaint)
380 {
381 ActorsToPaint.Add(ActorToPaint);
382 }
383 }
384
385 if(!ActorsToPaint.Num())
386 {
387 RESPOND_ERROR("unable to find Actor to apply the texture");
388 }
389
390 UTexture2D* UETexture = GameMode->CreateUETexture(Texture);
391
392 for(AActor* ActorToPaint : ActorsToPaint)
393 {
394 GameMode->ApplyTextureToActor(
395 ActorToPaint,
396 UETexture,
397 parameter);
398 }
399 return R<void>::Success();
400 };
401
402 BIND_SYNC(apply_float_color_texture_to_objects) << [this](
403 const std::vector<std::string> &actors_name,
404 const cr::MaterialParameter& parameter,
405 const cr::TextureFloatColor& Texture) -> R<void>
406 {
409 if (!GameMode)
410 {
411 RESPOND_ERROR("unable to find CARLA game mode");
412 }
413 TArray<AActor*> ActorsToPaint;
414 for(const std::string& actor_name : actors_name)
415 {
416 AActor* ActorToPaint = GameMode->FindActorByName(cr::ToFString(actor_name));
417 if (ActorToPaint)
418 {
419 ActorsToPaint.Add(ActorToPaint);
420 }
421 }
422
423 if(!ActorsToPaint.Num())
424 {
425 RESPOND_ERROR("unable to find Actor to apply the texture");
426 }
427
428 UTexture2D* UETexture = GameMode->CreateUETexture(Texture);
429
430 for(AActor* ActorToPaint : ActorsToPaint)
431 {
432 GameMode->ApplyTextureToActor(
433 ActorToPaint,
434 UETexture,
435 parameter);
436 }
437 return R<void>::Success();
438 };
439
440 BIND_SYNC(get_names_of_all_objects) << [this]() -> R<std::vector<std::string>>
441 {
444 if (!GameMode)
445 {
446 RESPOND_ERROR("unable to find CARLA game mode");
447 }
448 TArray<FString> NamesFString = GameMode->GetNamesOfAllActors();
449 std::vector<std::string> NamesStd;
450 for (const FString &Name : NamesFString)
451 {
452 NamesStd.emplace_back(cr::FromFString(Name));
453 }
454 return NamesStd;
455 };
456
457 // ~~ Episode settings and info ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
458
459 BIND_SYNC(get_episode_info) << [this]() -> R<cr::EpisodeInfo>
460 {
462 return cr::EpisodeInfo{Episode->GetId(), BroadcastStream.token()};
463 };
464
465 BIND_SYNC(get_map_info) << [this]() -> R<cr::MapInfo>
466 {
469 const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
470 FString FullMapPath = GameMode->GetFullMapPath();
471 FString MapDir = FullMapPath.RightChop(FullMapPath.Find("Content/", ESearchCase::CaseSensitive) + 8);
472 MapDir += "/" + Episode->GetMapName();
473 return cr::MapInfo{
474 cr::FromFString(MapDir),
475 MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
476 };
477
478 BIND_SYNC(get_map_data) << [this]() -> R<std::string>
479 {
481 return cr::FromLongFString(UOpenDrive::GetXODR(Episode->GetWorld()));
482 };
483
484 BIND_SYNC(get_navigation_mesh) << [this]() -> R<std::vector<uint8_t>>
485 {
487 auto FileContents = FNavigationMesh::Load(Episode->GetMapName());
488 // make a mem copy (from TArray to std::vector)
489 std::vector<uint8_t> Result(FileContents.Num());
490 memcpy(&Result[0], FileContents.GetData(), FileContents.Num());
491 return Result;
492 };
493
494 BIND_SYNC(get_required_files) << [this](std::string folder = "") -> R<std::vector<std::string>>
495 {
497
498 // Check that the path ends in a slash, add it otherwise
499 if (folder[folder.size() - 1] != '/' && folder[folder.size() - 1] != '\\') {
500 folder += "/";
501 }
502
503 // Get the map's folder absolute path and check if it's in its own folder
505 const auto mapDir = GameMode->GetFullMapPath();
506 const auto folderDir = mapDir + "/" + folder.c_str();
507 const auto fileName = mapDir.EndsWith(Episode->GetMapName()) ? "*" : Episode->GetMapName();
508
509 // Find all the xodr and bin files from the map
510 TArray<FString> Files;
511 IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName + ".xodr"), true, false, false);
512 IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName + ".bin"), true, false, false);
513
514 // Remove the start of the path until the content folder and put each file in the result
515 std::vector<std::string> result;
516 for (auto File : Files) {
517 File.RemoveFromStart(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
518 result.emplace_back(TCHAR_TO_UTF8(*File));
519 }
520
521 return result;
522 };
523 BIND_SYNC(request_file) << [this](std::string name) -> R<std::vector<uint8_t>>
524 {
526
527 // Get the absolute path of the file
528 FString path(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
529 path.Append(name.c_str());
530
531 // Copy the binary data of the file into the result and return it
532 TArray<uint8_t> Content;
533 FFileHelper::LoadFileToArray(Content, *path, 0);
534 std::vector<uint8_t> Result(Content.Num());
535 memcpy(&Result[0], Content.GetData(), Content.Num());
536
537 return Result;
538 };
539
540 BIND_SYNC(get_episode_settings) << [this]() -> R<cr::EpisodeSettings>
541 {
543 return cr::EpisodeSettings{Episode->GetSettings()};
544 };
545
546 BIND_SYNC(set_episode_settings) << [this](
547 const cr::EpisodeSettings &settings) -> R<uint64_t>
548 {
550 Episode->ApplySettings(settings);
551 StreamingServer.SetSynchronousMode(settings.synchronous_mode);
552
554 if (!GameMode)
555 {
556 RESPOND_ERROR("unable to find CARLA game mode");
557 }
558 ALargeMapManager* LargeMap = GameMode->GetLMManager();
559 if (LargeMap)
560 {
561 LargeMap->ConsiderSpectatorAsEgo(settings.spectator_as_ego);
562 }
563
565 };
566
567 BIND_SYNC(get_actor_definitions) << [this]() -> R<std::vector<cr::ActorDefinition>>
568 {
570 return MakeVectorFromTArray<cr::ActorDefinition>(Episode->GetActorDefinitions());
571 };
572
573 BIND_SYNC(get_spectator) << [this]() -> R<cr::Actor>
574 {
577 if (!CarlaActor)
578 {
579 RESPOND_ERROR("internal error: unable to find spectator");
580 }
581 return Episode->SerializeActor(CarlaActor);
582 };
583
584 BIND_SYNC(get_all_level_BBs) << [this](uint8 QueriedTag) -> R<std::vector<cg::BoundingBox>>
585 {
587 TArray<FBoundingBox> Result;
589 if (!GameMode)
590 {
591 RESPOND_ERROR("unable to find CARLA game mode");
592 }
593 Result = GameMode->GetAllBBsOfLevel(QueriedTag);
594 ALargeMapManager* LargeMap = GameMode->GetLMManager();
595 if (LargeMap)
596 {
597 for(auto& Box : Result)
598 {
599 Box.Origin = LargeMap->LocalToGlobalLocation(Box.Origin);
600 }
601 }
602 return MakeVectorFromTArray<cg::BoundingBox>(Result);
603 };
604
605 BIND_SYNC(get_environment_objects) << [this](uint8 QueriedTag) -> R<std::vector<cr::EnvironmentObject>>
606 {
609 if (!GameMode)
610 {
611 RESPOND_ERROR("unable to find CARLA game mode");
612 }
613 TArray<FEnvironmentObject> Result = GameMode->GetEnvironmentObjects(QueriedTag);
614 ALargeMapManager* LargeMap = GameMode->GetLMManager();
615 if (LargeMap)
616 {
617 for(auto& Object : Result)
618 {
619 Object.Transform = LargeMap->LocalToGlobalTransform(Object.Transform);
620 }
621 }
622 return MakeVectorFromTArray<cr::EnvironmentObject>(Result);
623 };
624
625 BIND_SYNC(enable_environment_objects) << [this](std::vector<uint64_t> EnvObjectIds, bool Enable) -> R<void>
626 {
629 if (!GameMode)
630 {
631 RESPOND_ERROR("unable to find CARLA game mode");
632 }
633
634 TSet<uint64> EnvObjectIdsSet;
635 for(uint64 Id : EnvObjectIds)
636 {
637 EnvObjectIdsSet.Emplace(Id);
638 }
639
640 GameMode->EnableEnvironmentObjects(EnvObjectIdsSet, Enable);
641 return R<void>::Success();
642 };
643
644 // ~~ Weather ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
645
646 BIND_SYNC(get_weather_parameters) << [this]() -> R<cr::WeatherParameters>
647 {
649 auto *Weather = Episode->GetWeather();
650 if (Weather == nullptr)
651 {
652 RESPOND_ERROR("internal error: unable to find weather");
653 }
654 return Weather->GetCurrentWeather();
655 };
656
657 BIND_SYNC(set_weather_parameters) << [this](
658 const cr::WeatherParameters &weather) -> R<void>
659 {
661 auto *Weather = Episode->GetWeather();
662 if (Weather == nullptr)
663 {
664 RESPOND_ERROR("internal error: unable to find weather");
665 }
666 Weather->ApplyWeather(weather);
667 return R<void>::Success();
668 };
669
670 // -- IMUI Gravity ---------------------------------------------------------
671
672 BIND_SYNC(get_imui_gravity) << [this]() -> R<float>
673 {
676 if (GameMode == nullptr)
677 {
678 RESPOND_ERROR("get_imui_gravity error: unable to get carla gamemode");
679 }
680 return GameMode->IMUISensorGravity;
681 };
682
683 BIND_SYNC(set_imui_gravity) << [this](float newimuigravity) -> R<void>
684 {
687 if (GameMode == nullptr)
688 {
689 RESPOND_ERROR("get_imui_gravity error: unable to get carla gamemode");
690 }
691 GameMode->IMUISensorGravity = newimuigravity;
692 return R<void>::Success();
693 };
694
695 // ~~ Actor operations ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
696
697 BIND_SYNC(get_actors_by_id) << [this](
698 const std::vector<FCarlaActor::IdType> &ids) -> R<std::vector<cr::Actor>>
699 {
701 std::vector<cr::Actor> Result;
702 Result.reserve(ids.size());
703 for (auto &&Id : ids)
704 {
706 if (View)
707 {
708 Result.emplace_back(Episode->SerializeActor(View));
709 }
710 }
711 return Result;
712 };
713
714 BIND_SYNC(spawn_actor) << [this](
715 cr::ActorDescription Description,
716 const cr::Transform &Transform) -> R<cr::Actor>
717 {
719
720 auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
721
722 if (Result.Key != EActorSpawnResultStatus::Success)
723 {
724 UE_LOG(LogCarla, Error, TEXT("Actor not Spawned"));
726 }
727
729 if(LargeMap)
730 {
731 LargeMap->OnActorSpawned(*Result.Value);
732 }
733
734 return Episode->SerializeActor(Result.Value);
735 };
736
737 BIND_SYNC(spawn_actor_with_parent) << [this](
738 cr::ActorDescription Description,
739 const cr::Transform &Transform,
740 cr::ActorId ParentId,
741 cr::AttachmentType InAttachmentType,
742 const std::string& socket_name) -> R<cr::Actor>
743 {
745
746 auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
747 if (Result.Key != EActorSpawnResultStatus::Success)
748 {
750 }
751
752 FCarlaActor* CarlaActor = Episode->FindCarlaActor(Result.Value->GetActorId());
753 if (!CarlaActor)
754 {
755 RESPOND_ERROR("internal error: actor could not be spawned");
756 }
757
758 FCarlaActor* ParentCarlaActor = Episode->FindCarlaActor(ParentId);
759
760 if (!ParentCarlaActor)
761 {
762 RESPOND_ERROR("unable to attach actor: parent actor not found");
763 }
764
765 CarlaActor->SetParent(ParentId);
766 CarlaActor->SetAttachmentType(InAttachmentType);
767 ParentCarlaActor->AddChildren(CarlaActor->GetActorId());
768
769 #if defined(WITH_ROS2)
770 auto ROS2 = carla::ros2::ROS2::GetInstance();
771 if (ROS2->IsEnabled())
772 {
773 FCarlaActor* CurrentActor = ParentCarlaActor;
774 while(CurrentActor)
775 {
776 for (const auto &Attr : CurrentActor->GetActorInfo()->Description.Variations)
777 {
778 if (Attr.Key == "ros_name")
779 {
780 const std::string value = std::string(TCHAR_TO_UTF8(*Attr.Value.Value));
781 ROS2->AddActorParentRosName(static_cast<void*>(CarlaActor->GetActor()), static_cast<void*>(CurrentActor->GetActor()));
782 }
783 }
784 CurrentActor = Episode->FindCarlaActor(CurrentActor->GetParent());
785 }
786 }
787 #endif
788
789 // Only is possible to attach if the actor has been really spawned and
790 // is not in dormant state
791 if(!ParentCarlaActor->IsDormant())
792 {
794 CarlaActor->GetActor(),
795 ParentCarlaActor->GetActor(),
796 static_cast<EAttachmentType>(InAttachmentType),
797 FString(socket_name.c_str()));
798 }
799 else
800 {
801 Episode->PutActorToSleep(CarlaActor->GetActorId());
802 }
803
804 return Episode->SerializeActor(CarlaActor);
805 };
806
807 BIND_SYNC(destroy_actor) << [this](cr::ActorId ActorId) -> R<bool>
808 {
810 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
811 if ( !CarlaActor )
812 {
813 RESPOND_ERROR("unable to destroy actor: not found");
814 }
815 UE_LOG(LogCarla, Log, TEXT("CarlaServer destroy_actor %d"), ActorId);
816 // We need to force the actor state change, since dormant actors
817 // will ignore the FCarlaActor destruction
818 CarlaActor->SetActorState(cr::ActorState::PendingKill);
819 if (!Episode->DestroyActor(ActorId))
820 {
821 RESPOND_ERROR("internal error: unable to destroy actor");
822 }
823 return true;
824 };
825
826 BIND_SYNC(console_command) << [this](std::string cmd) -> R<bool>
827 {
829 APlayerController* PController= UGameplayStatics::GetPlayerController(Episode->GetWorld(), 0);
830 if( PController )
831 {
832 auto result = PController->ConsoleCommand(UTF8_TO_TCHAR(cmd.c_str()), true);
833 return !(
834 result.Contains(FString(TEXT("Command not recognized"))) ||
835 result.Contains(FString(TEXT("Error")))
836 );
837 }
838 return GEngine->Exec(Episode->GetWorld(), UTF8_TO_TCHAR(cmd.c_str()));
839 };
840
841 BIND_SYNC(get_sensor_token) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
843 {
845 bool ForceInPrimary = false;
846
847 // check for the world observer (always in primary server)
848 if (sensor_id == 1)
849 {
850 ForceInPrimary = true;
851 }
852
853 // collision sensor always in primary server in multi-gpu
854 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
855 if (Desc == "" || Desc == "sensor.other.collision")
856 {
857 ForceInPrimary = true;
858 }
859
860 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
861 {
862 // multi-gpu
863 UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in secondary server"), sensor_id, *Desc);
864 return SecondaryServer->GetCommander().GetToken(sensor_id);
865 }
866 else
867 {
868 // single-gpu
869 UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in primary server"), sensor_id, *Desc);
870 return StreamingServer.GetToken(sensor_id);
871 }
872 };
873
874 BIND_SYNC(enable_sensor_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
875 R<void>
876 {
878 bool ForceInPrimary = false;
879
880 // check for the world observer (always in primary server)
881 if (sensor_id == 1)
882 {
883 ForceInPrimary = true;
884 }
885
886 // collision sensor always in primary server in multi-gpu
887 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
888 if (Desc == "" || Desc == "sensor.other.collision")
889 {
890 ForceInPrimary = true;
891 }
892
893 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
894 {
895 // multi-gpu
896 SecondaryServer->GetCommander().EnableForROS(sensor_id);
897 }
898 else
899 {
900 // single-gpu
901 StreamingServer.EnableForROS(sensor_id);
902 }
903 return R<void>::Success();
904 };
905
906 BIND_SYNC(disable_sensor_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
907 R<void>
908 {
910 bool ForceInPrimary = false;
911
912 // check for the world observer (always in primary server)
913 if (sensor_id == 1)
914 {
915 ForceInPrimary = true;
916 }
917
918 // collision sensor always in primary server in multi-gpu
919 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
920 if (Desc == "" || Desc == "sensor.other.collision")
921 {
922 ForceInPrimary = true;
923 }
924
925 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
926 {
927 // multi-gpu
928 SecondaryServer->GetCommander().DisableForROS(sensor_id);
929 }
930 else
931 {
932 // single-gpu
934 }
935 return R<void>::Success();
936 };
937
938BIND_SYNC(is_sensor_enabled_for_ros) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
939 R<bool>
940 {
942 bool ForceInPrimary = false;
943
944 // check for the world observer (always in primary server)
945 if (sensor_id == 1)
946 {
947 ForceInPrimary = true;
948 }
949
950 // collision sensor always in primary server in multi-gpu
951 FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
952 if (Desc == "" || Desc == "sensor.other.collision")
953 {
954 ForceInPrimary = true;
955 }
956
957 if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
958 {
959 // multi-gpu
960 return SecondaryServer->GetCommander().IsEnabledForROS(sensor_id);
961 }
962 else
963 {
964 // single-gpu
965 return StreamingServer.IsEnabledForROS(sensor_id);
966 }
967 };
968
969
970 BIND_SYNC(send) << [this](
971 cr::ActorId ActorId,
972 std::string message) -> R<void>
973 {
975 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
976 if (!CarlaActor)
977 {
978 return RespondError(
979 "send",
981 " Actor Id: " + FString::FromInt(ActorId));
982 }
983
984 if (CarlaActor->IsDormant())
985 {
986 return RespondError(
987 "send",
989 " Actor Id: " + FString::FromInt(ActorId));
990 }
991 ACustomV2XSensor* Sensor = Cast<ACustomV2XSensor>(CarlaActor->GetActor());
992 if (!Sensor)
993 {
994 return RespondError(
995 "send",
997 " Actor Id: " + FString::FromInt(ActorId));
998 }
999
1000 Sensor->Send(cr::ToFString(message));
1001 return R<void>::Success();
1002 };
1003
1004 // ~~ Actor physics ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1005
1006 BIND_SYNC(set_actor_location) << [this](
1007 cr::ActorId ActorId,
1008 cr::Location Location) -> R<void>
1009 {
1011 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1012 if (!CarlaActor)
1013 {
1014 return RespondError(
1015 "set_actor_location",
1017 " Actor Id: " + FString::FromInt(ActorId));
1018 }
1019
1020 CarlaActor->SetActorGlobalLocation(
1021 Location, ETeleportType::TeleportPhysics);
1022 return R<void>::Success();
1023 };
1024
1025 BIND_SYNC(set_actor_transform) << [this](
1026 cr::ActorId ActorId,
1027 cr::Transform Transform) -> R<void>
1028 {
1030 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1031 if (!CarlaActor)
1032 {
1033 return RespondError(
1034 "set_actor_transform",
1036 " Actor Id: " + FString::FromInt(ActorId));
1037 }
1038
1039 CarlaActor->SetActorGlobalTransform(
1040 Transform, ETeleportType::TeleportPhysics);
1041 return R<void>::Success();
1042 };
1043
1044 BIND_SYNC(set_walker_state) << [this] (
1045 cr::ActorId ActorId,
1046 cr::Transform Transform,
1047 float Speed) -> R<void>
1048 {
1050 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1051 if (!CarlaActor)
1052 {
1053 return RespondError(
1054 "set_walker_state",
1056 " Actor Id: " + FString::FromInt(ActorId));
1057 }
1058
1059 // apply walker transform
1060 ECarlaServerResponse Response =
1061 CarlaActor->SetWalkerState(
1062 Transform,
1063 cr::WalkerControl(
1064 Transform.GetForwardVector(), Speed, false));
1065 if (Response != ECarlaServerResponse::Success)
1066 {
1067 return RespondError(
1068 "set_walker_state",
1069 Response,
1070 " Actor Id: " + FString::FromInt(ActorId));
1071 }
1072 return R<void>::Success();
1073 };
1074
1075 BIND_SYNC(set_actor_target_velocity) << [this](
1076 cr::ActorId ActorId,
1077 cr::Vector3D vector) -> R<void>
1078 {
1080 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1081 if (!CarlaActor)
1082 {
1083 return RespondError(
1084 "set_actor_target_velocity",
1086 " Actor Id: " + FString::FromInt(ActorId));
1087 }
1088 ECarlaServerResponse Response =
1089 CarlaActor->SetActorTargetVelocity(vector.ToCentimeters().ToFVector());
1090 if (Response != ECarlaServerResponse::Success)
1091 {
1092 return RespondError(
1093 "set_actor_target_velocity",
1094 Response,
1095 " Actor Id: " + FString::FromInt(ActorId));
1096 }
1097 return R<void>::Success();
1098 };
1099
1100 BIND_SYNC(set_actor_target_angular_velocity) << [this](
1101 cr::ActorId ActorId,
1102 cr::Vector3D vector) -> R<void>
1103 {
1105 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1106 if (!CarlaActor)
1107 {
1108 return RespondError(
1109 "set_actor_target_angular_velocity",
1111 " Actor Id: " + FString::FromInt(ActorId));
1112 }
1113 ECarlaServerResponse Response =
1114 CarlaActor->SetActorTargetAngularVelocity(vector.ToFVector());
1115 if (Response != ECarlaServerResponse::Success)
1116 {
1117 return RespondError(
1118 "set_actor_target_angular_velocity",
1119 Response,
1120 " Actor Id: " + FString::FromInt(ActorId));
1121 }
1122 return R<void>::Success();
1123 };
1124
1125 BIND_SYNC(enable_actor_constant_velocity) << [this](
1126 cr::ActorId ActorId,
1127 cr::Vector3D vector) -> R<void>
1128 {
1130 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1131 if (!CarlaActor)
1132 {
1133 return RespondError(
1134 "enable_actor_constant_velocity",
1136 " Actor Id: " + FString::FromInt(ActorId));
1137 }
1138
1139 ECarlaServerResponse Response =
1140 CarlaActor->EnableActorConstantVelocity(vector.ToCentimeters().ToFVector());
1141 if (Response != ECarlaServerResponse::Success)
1142 {
1143 return RespondError(
1144 "enable_actor_constant_velocity",
1145 Response,
1146 " Actor Id: " + FString::FromInt(ActorId));
1147 }
1148
1149 return R<void>::Success();
1150 };
1151
1152 BIND_SYNC(disable_actor_constant_velocity) << [this](
1153 cr::ActorId ActorId) -> R<void>
1154 {
1156 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1157 if (!CarlaActor)
1158 {
1159 return RespondError(
1160 "disable_actor_constant_velocity",
1162 " Actor Id: " + FString::FromInt(ActorId));
1163 }
1164
1165 ECarlaServerResponse Response =
1166 CarlaActor->DisableActorConstantVelocity();
1167 if (Response != ECarlaServerResponse::Success)
1168 {
1169 return RespondError(
1170 "disable_actor_constant_velocity",
1171 Response,
1172 " Actor Id: " + FString::FromInt(ActorId));
1173 }
1174
1175 return R<void>::Success();
1176 };
1177
1178 BIND_SYNC(add_actor_impulse) << [this](
1179 cr::ActorId ActorId,
1180 cr::Vector3D vector) -> R<void>
1181 {
1183 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1184 if (!CarlaActor)
1185 {
1186 return RespondError(
1187 "add_actor_impulse",
1189 " Actor Id: " + FString::FromInt(ActorId));
1190 }
1191
1192 ECarlaServerResponse Response =
1193 CarlaActor->AddActorImpulse(vector.ToCentimeters().ToFVector());
1194 if (Response != ECarlaServerResponse::Success)
1195 {
1196 return RespondError(
1197 "add_actor_impulse",
1198 Response,
1199 " Actor Id: " + FString::FromInt(ActorId));
1200 }
1201 return R<void>::Success();
1202 };
1203
1204 BIND_SYNC(add_actor_impulse_at_location) << [this](
1205 cr::ActorId ActorId,
1206 cr::Vector3D impulse,
1207 cr::Vector3D location) -> R<void>
1208 {
1210 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1211 if (!CarlaActor)
1212 {
1213 return RespondError(
1214 "add_actor_impulse_at_location",
1216 " Actor Id: " + FString::FromInt(ActorId));
1217 }
1218 FVector UELocation = location.ToCentimeters().ToFVector();
1219 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1220 ALargeMapManager* LargeMap = GameMode->GetLMManager();
1221 if (LargeMap)
1222 {
1223 UELocation = LargeMap->GlobalToLocalLocation(UELocation);
1224 }
1225 ECarlaServerResponse Response =
1226 CarlaActor->AddActorImpulseAtLocation(impulse.ToCentimeters().ToFVector(), UELocation);
1227 if (Response != ECarlaServerResponse::Success)
1228 {
1229 return RespondError(
1230 "add_actor_impulse_at_location",
1231 Response,
1232 " Actor Id: " + FString::FromInt(ActorId));
1233 }
1234
1235 return R<void>::Success();
1236 };
1237
1238 BIND_SYNC(add_actor_force) << [this](
1239 cr::ActorId ActorId,
1240 cr::Vector3D vector) -> R<void>
1241 {
1243 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1244 if (!CarlaActor)
1245 {
1246 return RespondError(
1247 "add_actor_force",
1249 " Actor Id: " + FString::FromInt(ActorId));
1250 }
1251 ECarlaServerResponse Response =
1252 CarlaActor->AddActorForce(vector.ToCentimeters().ToFVector());
1253 if (Response != ECarlaServerResponse::Success)
1254 {
1255 return RespondError(
1256 "add_actor_force",
1257 Response,
1258 " Actor Id: " + FString::FromInt(ActorId));
1259 }
1260 return R<void>::Success();
1261 };
1262
1263 BIND_SYNC(add_actor_force_at_location) << [this](
1264 cr::ActorId ActorId,
1265 cr::Vector3D force,
1266 cr::Vector3D location) -> R<void>
1267 {
1269 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1270 if (!CarlaActor)
1271 {
1272 return RespondError(
1273 "add_actor_force_at_location",
1275 " Actor Id: " + FString::FromInt(ActorId));
1276 }
1277 FVector UELocation = location.ToCentimeters().ToFVector();
1278 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1279 ALargeMapManager* LargeMap = GameMode->GetLMManager();
1280 if (LargeMap)
1281 {
1282 UELocation = LargeMap->GlobalToLocalLocation(UELocation);
1283 }
1284 ECarlaServerResponse Response =
1285 CarlaActor->AddActorForceAtLocation(UELocation, force.ToCentimeters().ToFVector());
1286 if (Response != ECarlaServerResponse::Success)
1287 {
1288 return RespondError(
1289 "add_actor_force_at_location",
1290 Response,
1291 " Actor Id: " + FString::FromInt(ActorId));
1292 }
1293 return R<void>::Success();
1294 };
1295
1296 BIND_SYNC(add_actor_angular_impulse) << [this](
1297 cr::ActorId ActorId,
1298 cr::Vector3D vector) -> R<void>
1299 {
1301 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1302 if (!CarlaActor)
1303 {
1304 return RespondError(
1305 "add_actor_angular_impulse",
1307 " Actor Id: " + FString::FromInt(ActorId));
1308 }
1309 ECarlaServerResponse Response =
1310 CarlaActor->AddActorAngularImpulse(vector.ToFVector());
1311 if (Response != ECarlaServerResponse::Success)
1312 {
1313 return RespondError(
1314 "add_actor_angular_impulse",
1315 Response,
1316 " Actor Id: " + FString::FromInt(ActorId));
1317 }
1318 return R<void>::Success();
1319 };
1320
1321 BIND_SYNC(add_actor_torque) << [this](
1322 cr::ActorId ActorId,
1323 cr::Vector3D vector) -> R<void>
1324 {
1326 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1327 if (!CarlaActor)
1328 {
1329 return RespondError(
1330 "add_actor_torque",
1332 " Actor Id: " + FString::FromInt(ActorId));
1333 }
1334 ECarlaServerResponse Response =
1335 CarlaActor->AddActorTorque(vector.ToFVector());
1336 if (Response != ECarlaServerResponse::Success)
1337 {
1338 return RespondError(
1339 "add_actor_torque",
1340 Response,
1341 " Actor Id: " + FString::FromInt(ActorId));
1342 }
1343 return R<void>::Success();
1344 };
1345
1346 BIND_SYNC(get_actor_component_world_transform) << [this](
1347 cr::ActorId ActorId,
1348 const std::string componentName) -> R<cr::Transform>
1349 {
1351 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1352 if (!CarlaActor)
1353 {
1354 return RespondError(
1355 "get_actor_component_world_transform",
1357 " Actor Id: " + FString::FromInt(ActorId));
1358 }
1359 else
1360 {
1361 TArray<UActorComponent*> Components;
1362 CarlaActor->GetActor()->GetComponents(Components);
1363
1364 USceneComponent* Component = nullptr;
1365 for(auto Cmp : Components)
1366 {
1367 if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
1368 {
1369 if(SCMP->GetName() == componentName.c_str())
1370 {
1371 Component = SCMP;
1372 break;
1373 }
1374 }
1375 }
1376
1377 if(!Component)
1378 {
1379 return RespondError(
1380 "get_actor_component_world_transform",
1382 " Component Name: " + FString(componentName.c_str()));
1383 }
1384
1385 FTransform ComponentWorldTransform = Component->GetComponentTransform();
1386 return cr::Transform(ComponentWorldTransform);
1387 }
1388 };
1389
1390 BIND_SYNC(get_actor_component_relative_transform) << [this](
1391 cr::ActorId ActorId,
1392 const std::string componentName) -> R<cr::Transform>
1393 {
1395 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1396 if (!CarlaActor)
1397 {
1398 return RespondError(
1399 "get_actor_component_relative_transform",
1401 " Actor Id: " + FString::FromInt(ActorId));
1402 }
1403 else
1404 {
1405 TArray<UActorComponent*> Components;
1406 CarlaActor->GetActor()->GetComponents(Components);
1407
1408 USceneComponent* Component = nullptr;
1409 for(auto Cmp : Components)
1410 {
1411 if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
1412 {
1413 if(SCMP->GetName() == componentName.c_str())
1414 {
1415 Component = SCMP;
1416 break;
1417 }
1418 }
1419 }
1420
1421 if(!Component)
1422 {
1423 return RespondError(
1424 "get_actor_component_world_transform",
1426 " Component Name: " + FString(componentName.c_str()));
1427 }
1428
1429 FTransform ComponentRelativeTransform = Component->GetRelativeTransform();
1430 return cr::Transform(ComponentRelativeTransform);
1431 }
1432 };
1433
1434 BIND_SYNC(get_actor_bone_world_transforms) << [this](
1435 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1436 {
1438 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1439 if (!CarlaActor)
1440 {
1441 return RespondError(
1442 "get_actor_bone_world_transforms",
1444 " Actor Id: " + FString::FromInt(ActorId));
1445 }
1446 else
1447 {
1448 TArray<FTransform> BoneWorldTransforms;
1449 TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
1450 CarlaActor->GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
1451 if(!SkinnedMeshComponents[0])
1452 {
1453 return RespondError(
1454 "get_actor_bone_world_transforms",
1456 " Component Name: SkinnedMeshComponent ");
1457 }
1458 else
1459 {
1460 for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
1461 {
1462 const int32 NumBones = SkinnedMeshComponent->GetNumBones();
1463 for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
1464 {
1465 FTransform WorldTransform = SkinnedMeshComponent->GetComponentTransform();
1466 FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, WorldTransform);
1467 BoneWorldTransforms.Add(BoneTransform);
1468 }
1469 }
1470 return MakeVectorFromTArray<cr::Transform>(BoneWorldTransforms);
1471 }
1472 }
1473 };
1474
1475 BIND_SYNC(get_actor_bone_relative_transforms) << [this](
1476 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1477 {
1479 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1480 if (!CarlaActor)
1481 {
1482 return RespondError(
1483 "get_actor_bone_relative_transforms",
1485 " Actor Id: " + FString::FromInt(ActorId));
1486 }
1487 else
1488 {
1489 TArray<FTransform> BoneRelativeTransforms;
1490 TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
1491 CarlaActor->GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
1492 if(!SkinnedMeshComponents[0])
1493 {
1494 return RespondError(
1495 "get_actor_bone_relative_transforms",
1497 " Component Name: SkinnedMeshComponent ");
1498 }
1499 else
1500 {
1501 for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
1502 {
1503 const int32 NumBones = SkinnedMeshComponent->GetNumBones();
1504 for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
1505 {
1506 FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, FTransform::Identity);
1507 BoneRelativeTransforms.Add(BoneTransform);
1508 }
1509 }
1510 return MakeVectorFromTArray<cr::Transform>(BoneRelativeTransforms);
1511 }
1512 }
1513 };
1514
1515 BIND_SYNC(get_actor_component_names) << [this](
1516 cr::ActorId ActorId) -> R<std::vector<std::string>>
1517 {
1519 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1520 if (!CarlaActor)
1521 {
1522 return RespondError(
1523 "get_actor_component_names",
1525 " Actor Id: " + FString::FromInt(ActorId));
1526 }
1527 else
1528 {
1529 TArray<UActorComponent*> Components;
1530 CarlaActor->GetActor()->GetComponents(Components);
1531 std::vector<std::string> ComponentNames;
1532 for(auto Cmp : Components)
1533 {
1534 FString ComponentName = Cmp->GetName();
1535 ComponentNames.push_back(TCHAR_TO_UTF8(*ComponentName));
1536 }
1537 return ComponentNames;
1538 }
1539 };
1540
1541 BIND_SYNC(get_actor_bone_names) << [this](
1542 cr::ActorId ActorId) -> R<std::vector<std::string>>
1543 {
1545 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1546 if (!CarlaActor)
1547 {
1548 return RespondError(
1549 "get_actor_bone_names",
1551 " Actor Id: " + FString::FromInt(ActorId));
1552 }
1553 else
1554 {
1555 USkinnedMeshComponent* SkinnedMeshComponent = CarlaActor->GetActor()->FindComponentByClass<USkinnedMeshComponent>();
1556 if(!SkinnedMeshComponent)
1557 {
1558 return RespondError(
1559 "get_actor_bone_names",
1561 " Component Name: SkinnedMeshComponent ");
1562 }
1563 else
1564 {
1565 TArray<FName> BoneNames;
1566 SkinnedMeshComponent->GetBoneNames(BoneNames);
1567 TArray<std::string> StringBoneNames;
1568 for (const FName& Name : BoneNames)
1569 {
1570 FString FBoneName = Name.ToString();
1571 std::string StringBoneName = TCHAR_TO_UTF8(*FBoneName);
1572 StringBoneNames.Add(StringBoneName);
1573 }
1574 return MakeVectorFromTArray<std::string>(StringBoneNames);
1575 }
1576 }
1577 };
1578
1579 BIND_SYNC(get_actor_socket_world_transforms) << [this](
1580 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1581 {
1583 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1584 if (!CarlaActor)
1585 {
1586 return RespondError(
1587 "get_actor_socket_world_transforms",
1589 " Actor Id: " + FString::FromInt(ActorId));
1590 }
1591 else
1592 {
1593 TArray<FTransform> SocketWorldTransforms;
1594 TArray<UActorComponent*> Components;
1595 CarlaActor->GetActor()->GetComponents(Components);
1596 for(UActorComponent* ActorComponent : Components)
1597 {
1598 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1599 {
1600 const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
1601 for (const FName& SocketName : SocketNames)
1602 {
1603 FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName);
1604 SocketWorldTransforms.Add(SocketTransform);
1605 }
1606 }
1607 }
1608 return MakeVectorFromTArray<cr::Transform>(SocketWorldTransforms);
1609 }
1610 };
1611
1612 BIND_SYNC(get_actor_socket_relative_transforms) << [this](
1613 cr::ActorId ActorId) -> R<std::vector<cr::Transform>>
1614 {
1616 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1617 if (!CarlaActor)
1618 {
1619 return RespondError(
1620 "get_actor_socket_relative_transforms",
1622 " Actor Id: " + FString::FromInt(ActorId));
1623 }
1624 else
1625 {
1626 TArray<FTransform> SocketRelativeTransforms;
1627 TArray<UActorComponent*> Components;
1628 CarlaActor->GetActor()->GetComponents(Components);
1629 for(UActorComponent* ActorComponent : Components)
1630 {
1631 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1632 {
1633 const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
1634 for (const FName& SocketName : SocketNames)
1635 {
1636 FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName, ERelativeTransformSpace::RTS_Actor);
1637 SocketRelativeTransforms.Add(SocketTransform);
1638 }
1639 }
1640 }
1641 return MakeVectorFromTArray<cr::Transform>(SocketRelativeTransforms);
1642 }
1643 };
1644
1645 BIND_SYNC(get_actor_socket_names) << [this](
1646 cr::ActorId ActorId) -> R<std::vector<std::string>>
1647 {
1649 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1650 if (!CarlaActor)
1651 {
1652 return RespondError(
1653 "get_actor_socket_names",
1655 " Actor Id: " + FString::FromInt(ActorId));
1656 }
1657 else
1658 {
1659 TArray<FName> SocketNames;
1660 std::vector<std::string> StringSocketNames;
1661 TArray<UActorComponent*> Components;
1662 CarlaActor->GetActor()->GetComponents(Components);
1663 for(UActorComponent* ActorComponent : Components)
1664 {
1665 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1666 {
1667 SocketNames = SceneComponent->GetAllSocketNames();
1668 for (const FName& Name : SocketNames)
1669 {
1670 FString FSocketName = Name.ToString();
1671 std::string StringSocketName = TCHAR_TO_UTF8(*FSocketName);
1672 StringSocketNames.push_back(StringSocketName);
1673 }
1674 }
1675 }
1676 return StringSocketNames;
1677 }
1678 };
1679
1680 BIND_SYNC(get_physics_control) << [this](
1681 cr::ActorId ActorId) -> R<cr::VehiclePhysicsControl>
1682 {
1684 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1685 if (!CarlaActor)
1686 {
1687 return RespondError(
1688 "get_physics_control",
1690 " Actor Id: " + FString::FromInt(ActorId));
1691 }
1693 ECarlaServerResponse Response =
1694 CarlaActor->GetPhysicsControl(PhysicsControl);
1695 if (Response != ECarlaServerResponse::Success)
1696 {
1697 return RespondError(
1698 "get_physics_control",
1699 Response,
1700 " Actor Id: " + FString::FromInt(ActorId));
1701 }
1702 return cr::VehiclePhysicsControl(PhysicsControl);
1703 };
1704
1705 BIND_SYNC(get_vehicle_light_state) << [this](
1706 cr::ActorId ActorId) -> R<cr::VehicleLightState>
1707 {
1709 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1710 if (!CarlaActor)
1711 {
1712 return RespondError(
1713 "get_vehicle_light_state",
1715 " Actor Id: " + FString::FromInt(ActorId));
1716 }
1717 FVehicleLightState LightState;
1718 ECarlaServerResponse Response =
1719 CarlaActor->GetVehicleLightState(LightState);
1720 if (Response != ECarlaServerResponse::Success)
1721 {
1722 return RespondError(
1723 "get_vehicle_light_state",
1724 Response,
1725 " Actor Id: " + FString::FromInt(ActorId));
1726 }
1727 return cr::VehicleLightState(LightState);
1728 };
1729
1730 BIND_SYNC(apply_physics_control) << [this](
1731 cr::ActorId ActorId,
1732 cr::VehiclePhysicsControl PhysicsControl) -> R<void>
1733 {
1735 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1736 if (!CarlaActor)
1737 {
1738 return RespondError(
1739 "apply_physics_control",
1741 " Actor Id: " + FString::FromInt(ActorId));
1742 }
1743 ECarlaServerResponse Response =
1745 if (Response != ECarlaServerResponse::Success)
1746 {
1747 return RespondError(
1748 "apply_physics_control",
1749 Response,
1750 " Actor Id: " + FString::FromInt(ActorId));
1751 }
1752 return R<void>::Success();
1753 };
1754
1755 BIND_SYNC(set_vehicle_light_state) << [this](
1756 cr::ActorId ActorId,
1757 cr::VehicleLightState LightState) -> R<void>
1758 {
1760 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1761 if (!CarlaActor)
1762 {
1763 return RespondError(
1764 "set_vehicle_light_state",
1766 " Actor Id: " + FString::FromInt(ActorId));
1767 }
1768 ECarlaServerResponse Response =
1769 CarlaActor->SetVehicleLightState(FVehicleLightState(LightState));
1770 if (Response != ECarlaServerResponse::Success)
1771 {
1772 return RespondError(
1773 "set_vehicle_light_state",
1774 Response,
1775 " Actor Id: " + FString::FromInt(ActorId));
1776 }
1777 return R<void>::Success();
1778 };
1779
1780
1781 BIND_SYNC(open_vehicle_door) << [this](
1782 cr::ActorId ActorId,
1783 cr::VehicleDoor DoorIdx) -> R<void>
1784 {
1786 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1787 if (!CarlaActor)
1788 {
1789 return RespondError(
1790 "open_vehicle_door",
1792 " Actor Id: " + FString::FromInt(ActorId));
1793 }
1794 ECarlaServerResponse Response =
1795 CarlaActor->OpenVehicleDoor(static_cast<EVehicleDoor>(DoorIdx));
1796 if (Response != ECarlaServerResponse::Success)
1797 {
1798 return RespondError(
1799 "open_vehicle_door",
1800 Response,
1801 " Actor Id: " + FString::FromInt(ActorId));
1802 }
1803 return R<void>::Success();
1804 };
1805
1806 BIND_SYNC(close_vehicle_door) << [this](
1807 cr::ActorId ActorId,
1808 cr::VehicleDoor DoorIdx) -> R<void>
1809 {
1811 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1812 if (!CarlaActor)
1813 {
1814 return RespondError(
1815 "close_vehicle_door",
1817 " Actor Id: " + FString::FromInt(ActorId));
1818 }
1819 ECarlaServerResponse Response =
1820 CarlaActor->CloseVehicleDoor(static_cast<EVehicleDoor>(DoorIdx));
1821 if (Response != ECarlaServerResponse::Success)
1822 {
1823 return RespondError(
1824 "close_vehicle_door",
1825 Response,
1826 " Actor Id: " + FString::FromInt(ActorId));
1827 }
1828 return R<void>::Success();
1829 };
1830
1831 BIND_SYNC(set_wheel_steer_direction) << [this](
1832 cr::ActorId ActorId,
1833 cr::VehicleWheelLocation WheelLocation,
1834 float AngleInDeg) -> R<void>
1835 {
1837 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1838 if(!CarlaActor){
1839 return RespondError(
1840 "set_wheel_steer_direction",
1842 " Actor Id: " + FString::FromInt(ActorId));
1843 }
1844 ECarlaServerResponse Response =
1845 CarlaActor->SetWheelSteerDirection(
1846 static_cast<EVehicleWheelLocation>(WheelLocation), AngleInDeg);
1847 if (Response != ECarlaServerResponse::Success)
1848 {
1849 return RespondError(
1850 "set_wheel_steer_direction",
1851 Response,
1852 " Actor Id: " + FString::FromInt(ActorId));
1853 }
1854 return R<void>::Success();
1855 };
1856
1857 BIND_SYNC(get_wheel_steer_angle) << [this](
1858 const cr::ActorId ActorId,
1859 cr::VehicleWheelLocation WheelLocation) -> R<float>
1860 {
1862 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1863 if(!CarlaActor){
1864 return RespondError(
1865 "get_wheel_steer_angle",
1867 " Actor Id: " + FString::FromInt(ActorId));
1868 }
1869 float Angle;
1870 ECarlaServerResponse Response =
1871 CarlaActor->GetWheelSteerAngle(
1872 static_cast<EVehicleWheelLocation>(WheelLocation), Angle);
1873 if (Response != ECarlaServerResponse::Success)
1874 {
1875 return RespondError(
1876 "get_wheel_steer_angle",
1877 Response,
1878 " Actor Id: " + FString::FromInt(ActorId));
1879 }
1880 return Angle;
1881 };
1882
1883 BIND_SYNC(set_actor_simulate_physics) << [this](
1884 cr::ActorId ActorId,
1885 bool bEnabled) -> R<void>
1886 {
1888 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1889 if (!CarlaActor)
1890 {
1891 return RespondError(
1892 "set_actor_simulate_physics",
1894 " Actor Id: " + FString::FromInt(ActorId));
1895 }
1896 ECarlaServerResponse Response =
1897 CarlaActor->SetActorSimulatePhysics(bEnabled);
1898 if (Response != ECarlaServerResponse::Success)
1899 {
1900 return RespondError(
1901 "set_actor_simulate_physics",
1902 Response,
1903 " Actor Id: " + FString::FromInt(ActorId));
1904 }
1905 return R<void>::Success();
1906 };
1907
1908 BIND_SYNC(set_actor_collisions) << [this](
1909 cr::ActorId ActorId,
1910 bool bEnabled) -> R<void>
1911 {
1913 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1914 if (!CarlaActor)
1915 {
1916 return RespondError(
1917 "set_actor_collisions",
1919 " Actor Id: " + FString::FromInt(ActorId));
1920 }
1921 ECarlaServerResponse Response =
1922 CarlaActor->SetActorCollisions(bEnabled);
1923 if (Response != ECarlaServerResponse::Success)
1924 {
1925 return RespondError(
1926 "set_actor_collisions",
1927 Response,
1928 " Actor Id: " + FString::FromInt(ActorId));
1929 }
1930 return R<void>::Success();
1931 };
1932
1933 BIND_SYNC(set_actor_dead) << [this](
1934 cr::ActorId ActorId) -> R<void>
1935 {
1937 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1938 if (!CarlaActor)
1939 {
1940 return RespondError(
1941 "set_actor_dead",
1943 " Actor Id: " + FString::FromInt(ActorId));
1944 }
1945 ECarlaServerResponse Response =
1946 CarlaActor->SetActorDead();
1947 if (Response != ECarlaServerResponse::Success)
1948 {
1949 return RespondError(
1950 "set_actor_dead",
1951 Response,
1952 " Actor Id: " + FString::FromInt(ActorId));
1953 }
1954 return R<void>::Success();
1955 };
1956
1957 BIND_SYNC(set_actor_enable_gravity) << [this](
1958 cr::ActorId ActorId,
1959 bool bEnabled) -> R<void>
1960 {
1962 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1963 if (!CarlaActor)
1964 {
1965 return RespondError(
1966 "set_actor_enable_gravity",
1968 " Actor Id: " + FString::FromInt(ActorId));
1969 }
1970 ECarlaServerResponse Response =
1971 CarlaActor->SetActorEnableGravity(bEnabled);
1972 if (Response != ECarlaServerResponse::Success)
1973 {
1974 return RespondError(
1975 "set_actor_enable_gravity",
1976 Response,
1977 " Actor Id: " + FString::FromInt(ActorId));
1978 }
1979 return R<void>::Success();
1980 };
1981
1982 // ~~ Apply control ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1983
1984 BIND_SYNC(apply_control_to_vehicle) << [this](
1985 cr::ActorId ActorId,
1986 cr::VehicleControl Control) -> R<void>
1987 {
1989 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1990 if (!CarlaActor)
1991 {
1992 return RespondError(
1993 "apply_control_to_vehicle",
1995 " Actor Id: " + FString::FromInt(ActorId));
1996 }
1997 ECarlaServerResponse Response =
1998 CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::Client);
1999 if (Response != ECarlaServerResponse::Success)
2000 {
2001 return RespondError(
2002 "apply_control_to_vehicle",
2003 Response,
2004 " Actor Id: " + FString::FromInt(ActorId));
2005 }
2006 return R<void>::Success();
2007 };
2008
2009 BIND_SYNC(apply_ackermann_control_to_vehicle) << [this](
2010 cr::ActorId ActorId,
2011 cr::VehicleAckermannControl Control) -> R<void>
2012 {
2014 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2015 if (!CarlaActor)
2016 {
2017 return RespondError(
2018 "apply_ackermann_control_to_vehicle",
2020 " Actor Id: " + FString::FromInt(ActorId));
2021 }
2022 ECarlaServerResponse Response =
2023 CarlaActor->ApplyAckermannControlToVehicle(Control, EVehicleInputPriority::Client);
2024 if (Response != ECarlaServerResponse::Success)
2025 {
2026 return RespondError(
2027 "apply_ackermann_control_to_vehicle",
2028 Response,
2029 " Actor Id: " + FString::FromInt(ActorId));
2030 }
2031 return R<void>::Success();
2032 };
2033
2034 BIND_SYNC(get_ackermann_controller_settings) << [this](
2035 cr::ActorId ActorId) -> R<cr::AckermannControllerSettings>
2036 {
2038 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2039 if (!CarlaActor)
2040 {
2041 return RespondError(
2042 "get_ackermann_controller_settings",
2044 " Actor Id: " + FString::FromInt(ActorId));
2045 }
2047 ECarlaServerResponse Response =
2048 CarlaActor->GetAckermannControllerSettings(Settings);
2049 if (Response != ECarlaServerResponse::Success)
2050 {
2051 return RespondError(
2052 "get_ackermann_controller_settings",
2053 Response,
2054 " Actor Id: " + FString::FromInt(ActorId));
2055 }
2056 return cr::AckermannControllerSettings(Settings);
2057 };
2058
2059 BIND_SYNC(apply_ackermann_controller_settings) << [this](
2060 cr::ActorId ActorId,
2061 cr::AckermannControllerSettings AckermannSettings) -> R<void>
2062 {
2064 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2065 if (!CarlaActor)
2066 {
2067 return RespondError(
2068 "apply_ackermann_controller_settings",
2070 " Actor Id: " + FString::FromInt(ActorId));
2071 }
2072 ECarlaServerResponse Response =
2073 CarlaActor->ApplyAckermannControllerSettings(FAckermannControllerSettings(AckermannSettings));
2074 if (Response != ECarlaServerResponse::Success)
2075 {
2076 return RespondError(
2077 "apply_ackermann_controller_settings",
2078 Response,
2079 " Actor Id: " + FString::FromInt(ActorId));
2080 }
2081 return R<void>::Success();
2082 };
2083
2084 BIND_SYNC(apply_control_to_walker) << [this](
2085 cr::ActorId ActorId,
2086 cr::WalkerControl Control) -> R<void>
2087 {
2089 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2090 if (!CarlaActor)
2091 {
2092 return RespondError(
2093 "apply_control_to_walker",
2095 " Actor Id: " + FString::FromInt(ActorId));
2096 }
2097 ECarlaServerResponse Response =
2098 CarlaActor->ApplyControlToWalker(Control);
2099 if (Response != ECarlaServerResponse::Success)
2100 {
2101 return RespondError(
2102 "apply_control_to_walker",
2103 Response,
2104 " Actor Id: " + FString::FromInt(ActorId));
2105 }
2106 return R<void>::Success();
2107 };
2108
2109 BIND_SYNC(get_bones_transform) << [this](
2110 cr::ActorId ActorId) -> R<cr::WalkerBoneControlOut>
2111 {
2113 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2114 if (!CarlaActor)
2115 {
2116 return RespondError(
2117 "get_bones_transform",
2119 " Actor Id: " + FString::FromInt(ActorId));
2120 }
2122 ECarlaServerResponse Response =
2123 CarlaActor->GetBonesTransform(Bones);
2124 if (Response != ECarlaServerResponse::Success)
2125 {
2126 return RespondError(
2127 "get_bones_transform",
2128 Response,
2129 " Actor Id: " + FString::FromInt(ActorId));
2130 }
2131
2132 std::vector<carla::rpc::BoneTransformDataOut> BoneData;
2133 for (auto Bone : Bones.BoneTransforms)
2134 {
2136 Data.bone_name = std::string(TCHAR_TO_UTF8(*Bone.Get<0>()));
2137 FWalkerBoneControlOutData Transforms = Bone.Get<1>();
2138 Data.world = Transforms.World;
2139 Data.component = Transforms.Component;
2140 Data.relative = Transforms.Relative;
2141 BoneData.push_back(Data);
2142 }
2143 return carla::rpc::WalkerBoneControlOut(BoneData);
2144 };
2145
2146 BIND_SYNC(set_bones_transform) << [this](
2147 cr::ActorId ActorId,
2149 {
2151 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2152 if (!CarlaActor)
2153 {
2154 return RespondError(
2155 "set_bones_transform",
2157 " Actor Id: " + FString::FromInt(ActorId));
2158 }
2159
2161 ECarlaServerResponse Response = CarlaActor->SetBonesTransform(Bones2);
2162 if (Response != ECarlaServerResponse::Success)
2163 {
2164 return RespondError(
2165 "set_bones_transform",
2166 Response,
2167 " Actor Id: " + FString::FromInt(ActorId));
2168 }
2169
2170 return R<void>::Success();
2171 };
2172
2173 BIND_SYNC(blend_pose) << [this](
2174 cr::ActorId ActorId,
2175 float Blend) -> R<void>
2176 {
2178 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2179 if (!CarlaActor)
2180 {
2181 return RespondError(
2182 "blend_pose",
2184 " Actor Id: " + FString::FromInt(ActorId));
2185 }
2186
2187 ECarlaServerResponse Response = CarlaActor->BlendPose(Blend);
2188 if (Response != ECarlaServerResponse::Success)
2189 {
2190 return RespondError(
2191 "blend_pose",
2192 Response,
2193 " Actor Id: " + FString::FromInt(ActorId));
2194 }
2195
2196 return R<void>::Success();
2197 };
2198
2199 BIND_SYNC(get_pose_from_animation) << [this](
2200 cr::ActorId ActorId) -> R<void>
2201 {
2203 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2204 if (!CarlaActor)
2205 {
2206 return RespondError(
2207 "get_pose_from_animation",
2209 " Actor Id: " + FString::FromInt(ActorId));
2210 }
2211
2212 ECarlaServerResponse Response = CarlaActor->GetPoseFromAnimation();
2213 if (Response != ECarlaServerResponse::Success)
2214 {
2215 return RespondError(
2216 "get_pose_from_animation",
2217 Response,
2218 " Actor Id: " + FString::FromInt(ActorId));
2219 }
2220
2221 return R<void>::Success();
2222 };
2223
2224 BIND_SYNC(set_actor_autopilot) << [this](
2225 cr::ActorId ActorId,
2226 bool bEnabled) -> R<void>
2227 {
2229 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2230 if (!CarlaActor)
2231 {
2232 return RespondError(
2233 "set_actor_autopilot",
2235 " Actor Id: " + FString::FromInt(ActorId));
2236 }
2237 ECarlaServerResponse Response =
2238 CarlaActor->SetActorAutopilot(bEnabled);
2239 if (Response != ECarlaServerResponse::Success)
2240 {
2241 return RespondError(
2242 "set_actor_autopilot",
2243 Response,
2244 " Actor Id: " + FString::FromInt(ActorId));
2245 }
2246 return R<void>::Success();
2247 };
2248
2249 BIND_SYNC(get_telemetry_data) << [this](
2250 cr::ActorId ActorId) -> R<cr::VehicleTelemetryData>
2251 {
2253 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2254 if (!CarlaActor)
2255 {
2256 return RespondError(
2257 "get_telemetry_data",
2259 " Actor Id: " + FString::FromInt(ActorId));
2260 }
2261 FVehicleTelemetryData TelemetryData;
2262 ECarlaServerResponse Response =
2263 CarlaActor->GetVehicleTelemetryData(TelemetryData);
2264 if (Response != ECarlaServerResponse::Success)
2265 {
2266 return RespondError(
2267 "get_telemetry_data",
2268 Response,
2269 " Actor Id: " + FString::FromInt(ActorId));
2270 }
2271 return cr::VehicleTelemetryData(TelemetryData);
2272 };
2273
2274 BIND_SYNC(show_vehicle_debug_telemetry) << [this](
2275 cr::ActorId ActorId,
2276 bool bEnabled) -> R<void>
2277 {
2279 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2280 if (!CarlaActor)
2281 {
2282 return RespondError(
2283 "show_vehicle_debug_telemetry",
2285 " Actor Id: " + FString::FromInt(ActorId));
2286 }
2287 ECarlaServerResponse Response =
2288 CarlaActor->ShowVehicleDebugTelemetry(bEnabled);
2289 if (Response != ECarlaServerResponse::Success)
2290 {
2291 return RespondError(
2292 "show_vehicle_debug_telemetry",
2293 Response,
2294 " Actor Id: " + FString::FromInt(ActorId));
2295 }
2296 return R<void>::Success();
2297 };
2298
2299 BIND_SYNC(enable_carsim) << [this](
2300 cr::ActorId ActorId,
2301 std::string SimfilePath) -> R<void>
2302 {
2304 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2305 if (!CarlaActor)
2306 {
2307 return RespondError(
2308 "enable_carsim",
2310 " Actor Id: " + FString::FromInt(ActorId));
2311 }
2312 ECarlaServerResponse Response =
2313 CarlaActor->EnableCarSim(carla::rpc::ToFString(SimfilePath));
2314 if (Response != ECarlaServerResponse::Success)
2315 {
2316 return RespondError(
2317 "enable_carsim",
2318 Response,
2319 " Actor Id: " + FString::FromInt(ActorId));
2320 }
2321 return R<void>::Success();
2322 };
2323
2324 BIND_SYNC(use_carsim_road) << [this](
2325 cr::ActorId ActorId,
2326 bool bEnabled) -> R<void>
2327 {
2329 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2330 if (!CarlaActor)
2331 {
2332 return RespondError(
2333 "use_carsim_road",
2335 " Actor Id: " + FString::FromInt(ActorId));
2336 }
2337 ECarlaServerResponse Response =
2338 CarlaActor->UseCarSimRoad(bEnabled);
2339 if (Response != ECarlaServerResponse::Success)
2340 {
2341 return RespondError(
2342 "use_carsim_road",
2343 Response,
2344 " Actor Id: " + FString::FromInt(ActorId));
2345 }
2346 return R<void>::Success();
2347 };
2348
2349 BIND_SYNC(enable_chrono_physics) << [this](
2350 cr::ActorId ActorId,
2351 uint64_t MaxSubsteps,
2352 float MaxSubstepDeltaTime,
2353 std::string VehicleJSON,
2354 std::string PowertrainJSON,
2355 std::string TireJSON,
2356 std::string BaseJSONPath) -> R<void>
2357 {
2359 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2360 if (!CarlaActor)
2361 {
2362 return RespondError(
2363 "enable_chrono_physics",
2365 " Actor Id: " + FString::FromInt(ActorId));
2366 }
2367 ECarlaServerResponse Response =
2368 CarlaActor->EnableChronoPhysics(
2369 MaxSubsteps, MaxSubstepDeltaTime,
2370 cr::ToFString(VehicleJSON),
2371 cr::ToFString(PowertrainJSON),
2372 cr::ToFString(TireJSON),
2373 cr::ToFString(BaseJSONPath));
2374 if (Response != ECarlaServerResponse::Success)
2375 {
2376 return RespondError(
2377 "enable_chrono_physics",
2378 Response,
2379 " Actor Id: " + FString::FromInt(ActorId));
2380 }
2381 return R<void>::Success();
2382 };
2383
2384 BIND_SYNC(restore_physx_physics) << [this](
2385 cr::ActorId ActorId) -> R<void>
2386 {
2388 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2389 if (!CarlaActor)
2390 {
2391 return RespondError(
2392 "restore_physx_physics",
2394 " Actor Id: " + FString::FromInt(ActorId));
2395 }
2396 ECarlaServerResponse Response =
2397 CarlaActor->RestorePhysXPhysics();
2398 if (Response != ECarlaServerResponse::Success)
2399 {
2400 return RespondError(
2401 "restore_physx_physics",
2402 Response,
2403 " Actor Id: " + FString::FromInt(ActorId));
2404 }
2405 return R<void>::Success();
2406 };
2407
2408 // ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2409
2410 BIND_SYNC(set_traffic_light_state) << [this](
2411 cr::ActorId ActorId,
2412 cr::TrafficLightState trafficLightState) -> R<void>
2413 {
2415 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2416 if (!CarlaActor)
2417 {
2418 return RespondError(
2419 "set_traffic_light_state",
2421 " Actor Id: " + FString::FromInt(ActorId));
2422 }
2423 ECarlaServerResponse Response =
2424 CarlaActor->SetTrafficLightState(
2425 static_cast<ETrafficLightState>(trafficLightState));
2426 if (Response != ECarlaServerResponse::Success)
2427 {
2428 return RespondError(
2429 "set_traffic_light_state",
2430 Response,
2431 " Actor Id: " + FString::FromInt(ActorId));
2432 }
2433 return R<void>::Success();
2434 };
2435
2436 BIND_SYNC(set_traffic_light_green_time) << [this](
2437 cr::ActorId ActorId,
2438 float GreenTime) -> R<void>
2439 {
2441 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2442 if (!CarlaActor)
2443 {
2444 return RespondError(
2445 "set_traffic_light_green_time",
2447 " Actor Id: " + FString::FromInt(ActorId));
2448 }
2449 ECarlaServerResponse Response =
2450 CarlaActor->SetLightGreenTime(GreenTime);
2451 if (Response != ECarlaServerResponse::Success)
2452 {
2453 return RespondError(
2454 "set_traffic_light_green_time",
2455 Response,
2456 " Actor Id: " + FString::FromInt(ActorId));
2457 }
2458 return R<void>::Success();
2459 };
2460
2461 BIND_SYNC(set_traffic_light_yellow_time) << [this](
2462 cr::ActorId ActorId,
2463 float YellowTime) -> R<void>
2464 {
2466 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2467 if (!CarlaActor)
2468 {
2469 return RespondError(
2470 "set_traffic_light_yellow_time",
2472 " Actor Id: " + FString::FromInt(ActorId));
2473 }
2474 ECarlaServerResponse Response =
2475 CarlaActor->SetLightYellowTime(YellowTime);
2476 if (Response != ECarlaServerResponse::Success)
2477 {
2478 return RespondError(
2479 "set_traffic_light_yellow_time",
2480 Response,
2481 " Actor Id: " + FString::FromInt(ActorId));
2482 }
2483 return R<void>::Success();
2484 };
2485
2486 BIND_SYNC(set_traffic_light_red_time) << [this](
2487 cr::ActorId ActorId,
2488 float RedTime) -> R<void>
2489 {
2491 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2492 if (!CarlaActor)
2493 {
2494 return RespondError(
2495 "set_traffic_light_red_time",
2497 " Actor Id: " + FString::FromInt(ActorId));
2498 }
2499 ECarlaServerResponse Response =
2500 CarlaActor->SetLightRedTime(RedTime);
2501 if (Response != ECarlaServerResponse::Success)
2502 {
2503 return RespondError(
2504 "set_traffic_light_red_time",
2505 Response,
2506 " Actor Id: " + FString::FromInt(ActorId));
2507 }
2508 return R<void>::Success();
2509 };
2510
2511 BIND_SYNC(freeze_traffic_light) << [this](
2512 cr::ActorId ActorId,
2513 bool Freeze) -> R<void>
2514 {
2516 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2517 if (!CarlaActor)
2518 {
2519 return RespondError(
2520 "freeze_traffic_light",
2522 " Actor Id: " + FString::FromInt(ActorId));
2523 }
2524 ECarlaServerResponse Response =
2525 CarlaActor->FreezeTrafficLight(Freeze);
2526 if (Response != ECarlaServerResponse::Success)
2527 {
2528 return RespondError(
2529 "freeze_traffic_light",
2530 Response,
2531 " Actor Id: " + FString::FromInt(ActorId));
2532 }
2533 return R<void>::Success();
2534 };
2535
2536 BIND_SYNC(reset_traffic_light_group) << [this](
2537 cr::ActorId ActorId) -> R<void>
2538 {
2540 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2541 if (!CarlaActor)
2542 {
2543 return RespondError(
2544 "reset_traffic_light_group",
2546 " Actor Id: " + FString::FromInt(ActorId));
2547 }
2548 ECarlaServerResponse Response =
2549 CarlaActor->ResetTrafficLightGroup();
2550 if (Response != ECarlaServerResponse::Success)
2551 {
2552 return RespondError(
2553 "reset_traffic_light_group",
2554 Response,
2555 " Actor Id: " + FString::FromInt(ActorId));
2556 }
2557 return R<void>::Success();
2558 };
2559
2560 BIND_SYNC(reset_all_traffic_lights) << [this]() -> R<void>
2561 {
2563 for (TActorIterator<ATrafficLightGroup> It(Episode->GetWorld()); It; ++It)
2564 {
2565 It->ResetGroup();
2566 }
2567 return R<void>::Success();
2568 };
2569
2570 BIND_SYNC(freeze_all_traffic_lights) << [this]
2571 (bool frozen) -> R<void>
2572 {
2574 auto* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
2575 if (!GameMode)
2576 {
2577 RESPOND_ERROR("unable to find CARLA game mode");
2578 }
2579 auto* TraffiLightManager = GameMode->GetTrafficLightManager();
2580 TraffiLightManager->SetFrozen(frozen);
2581 return R<void>::Success();
2582 };
2583
2584 BIND_SYNC(get_vehicle_light_states) << [this]() -> R<cr::VehicleLightStateList>
2585 {
2587 cr::VehicleLightStateList List;
2588
2589 auto It = Episode->GetActorRegistry().begin();
2590 for (; It != Episode->GetActorRegistry().end(); ++It)
2591 {
2592 const FCarlaActor& View = *(It.Value().Get());
2594 {
2595 if(View.IsDormant())
2596 {
2597 // todo: implement
2598 }
2599 else
2600 {
2601 auto Actor = View.GetActor();
2602 if (!Actor->IsPendingKill())
2603 {
2604 const ACarlaWheeledVehicle *Vehicle = Cast<ACarlaWheeledVehicle>(Actor);
2605 List.emplace_back(
2606 View.GetActorId(),
2607 cr::VehicleLightState(Vehicle->GetVehicleLightState()).GetLightStateAsValue());
2608 }
2609 }
2610 }
2611 }
2612 return List;
2613 };
2614
2615 BIND_SYNC(get_group_traffic_lights) << [this](
2616 const cr::ActorId ActorId) -> R<std::vector<cr::ActorId>>
2617 {
2619 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2620 if (!CarlaActor)
2621 {
2622 RESPOND_ERROR("unable to get group traffic lights: actor not found");
2623 }
2624 if (CarlaActor->IsDormant())
2625 {
2626 //todo implement
2627 return std::vector<cr::ActorId>();
2628 }
2629 else
2630 {
2631 auto TrafficLight = Cast<ATrafficLightBase>(CarlaActor->GetActor());
2632 if (TrafficLight == nullptr)
2633 {
2634 RESPOND_ERROR("unable to get group traffic lights: actor is not a traffic light");
2635 }
2636 std::vector<cr::ActorId> Result;
2637 for (auto* TLight : TrafficLight->GetGroupTrafficLights())
2638 {
2639 auto* View = Episode->FindCarlaActor(TLight);
2640 if (View)
2641 {
2642 Result.push_back(View->GetActorId());
2643 }
2644 }
2645 return Result;
2646 }
2647 };
2648
2649 BIND_SYNC(get_light_boxes) << [this](
2650 const cr::ActorId ActorId) -> R<std::vector<cg::BoundingBox>>
2651 {
2653 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2654 if (!CarlaActor)
2655 {
2656 return RespondError(
2657 "get_light_boxes",
2659 " Actor Id: " + FString::FromInt(ActorId));
2660 }
2661 if (CarlaActor->IsDormant())
2662 {
2663 return RespondError(
2664 "get_light_boxes",
2666 " Actor Id: " + FString::FromInt(ActorId));
2667 }
2668 else
2669 {
2670 ATrafficLightBase* TrafficLight = Cast<ATrafficLightBase>(CarlaActor->GetActor());
2671 if (!TrafficLight)
2672 {
2673 return RespondError(
2674 "get_light_boxes",
2676 " Actor Id: " + FString::FromInt(ActorId));
2677 }
2678 TArray<FBoundingBox> Result;
2679 TArray<uint8> OutTag;
2681 TrafficLight, Result, OutTag,
2682 static_cast<uint8>(carla::rpc::CityObjectLabel::TrafficLight));
2683 return MakeVectorFromTArray<cg::BoundingBox>(Result);
2684 }
2685 };
2686
2687 // ~~ GBuffer tokens ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2688 BIND_SYNC(get_gbuffer_token) << [this](const cr::ActorId ActorId, uint32_t GBufferId) -> R<std::vector<unsigned char>>
2689 {
2691 FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2692 if(!CarlaActor)
2693 {
2694 return RespondError(
2695 "get_gbuffer_token",
2697 " Actor Id: " + FString::FromInt(ActorId));
2698 }
2699 if (CarlaActor->IsDormant())
2700 {
2701 return RespondError(
2702 "get_gbuffer_token",
2704 " Actor Id: " + FString::FromInt(ActorId));
2705 }
2706 ASceneCaptureSensor* Sensor = Cast<ASceneCaptureSensor>(CarlaActor->GetActor());
2707 if (!Sensor)
2708 {
2709 return RespondError(
2710 "get_gbuffer_token",
2712 " Actor Id: " + FString::FromInt(ActorId));
2713 }
2714
2715 switch (GBufferId)
2716 {
2717 case 0:
2718 {
2719 const auto &Token = Sensor->CameraGBuffers.SceneColor.GetToken();
2720 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2721 }
2722 case 1:
2723 {
2724 const auto &Token = Sensor->CameraGBuffers.SceneDepth.GetToken();
2725 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2726 }
2727 case 2:
2728 {
2729 const auto& Token = Sensor->CameraGBuffers.SceneStencil.GetToken();
2730 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2731 }
2732 case 3:
2733 {
2734 const auto &Token = Sensor->CameraGBuffers.GBufferA.GetToken();
2735 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2736 }
2737 case 4:
2738 {
2739 const auto &Token = Sensor->CameraGBuffers.GBufferB.GetToken();
2740 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2741 }
2742 case 5:
2743 {
2744 const auto &Token = Sensor->CameraGBuffers.GBufferC.GetToken();
2745 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2746 }
2747 case 6:
2748 {
2749 const auto &Token = Sensor->CameraGBuffers.GBufferD.GetToken();
2750 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2751 }
2752 case 7:
2753 {
2754 const auto &Token = Sensor->CameraGBuffers.GBufferE.GetToken();
2755 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2756 }
2757 case 8:
2758 {
2759 const auto &Token = Sensor->CameraGBuffers.GBufferF.GetToken();
2760 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2761 }
2762 case 9:
2763 {
2764 const auto &Token = Sensor->CameraGBuffers.Velocity.GetToken();
2765 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2766 }
2767 case 10:
2768 {
2769 const auto &Token = Sensor->CameraGBuffers.SSAO.GetToken();
2770 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2771 }
2772 case 11:
2773 {
2774 const auto& Token = Sensor->CameraGBuffers.CustomDepth.GetToken();
2775 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2776 }
2777 case 12:
2778 {
2779 const auto& Token = Sensor->CameraGBuffers.CustomStencil.GetToken();
2780 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2781 }
2782 default:
2783 UE_LOG(LogCarla, Error, TEXT("Requested invalid GBuffer ID %u"), GBufferId);
2784 return {};
2785 }
2786 };
2787
2788 // ~~ Logging and playback ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2789
2790 BIND_SYNC(start_recorder) << [this](std::string name, bool AdditionalData) -> R<std::string>
2791 {
2793 return R<std::string>(Episode->StartRecorder(name, AdditionalData));
2794 };
2795
2796 BIND_SYNC(stop_recorder) << [this]() -> R<void>
2797 {
2799 Episode->GetRecorder()->Stop();
2800 return R<void>::Success();
2801 };
2802
2803 BIND_SYNC(show_recorder_file_info) << [this](
2804 std::string name,
2805 bool show_all) -> R<std::string>
2806 {
2809 name,
2810 show_all));
2811 };
2812
2813 BIND_SYNC(show_recorder_collisions) << [this](
2814 std::string name,
2815 char type1,
2816 char type2) -> R<std::string>
2817 {
2820 name,
2821 type1,
2822 type2));
2823 };
2824
2825 BIND_SYNC(show_recorder_actors_blocked) << [this](
2826 std::string name,
2827 double min_time,
2828 double min_distance) -> R<std::string>
2829 {
2832 name,
2833 min_time,
2834 min_distance));
2835 };
2836
2837 BIND_SYNC(replay_file) << [this](
2838 std::string name,
2839 double start,
2840 double duration,
2841 uint32_t follow_id,
2842 bool replay_sensors) -> R<std::string>
2843 {
2846 name,
2847 start,
2848 duration,
2849 follow_id,
2850 replay_sensors));
2851 };
2852
2853 BIND_SYNC(set_replayer_time_factor) << [this](double time_factor) -> R<void>
2854 {
2856 Episode->GetRecorder()->SetReplayerTimeFactor(time_factor);
2857 return R<void>::Success();
2858 };
2859
2860 BIND_SYNC(set_replayer_ignore_hero) << [this](bool ignore_hero) -> R<void>
2861 {
2863 Episode->GetRecorder()->SetReplayerIgnoreHero(ignore_hero);
2864 return R<void>::Success();
2865 };
2866
2867 BIND_SYNC(set_replayer_ignore_spectator) << [this](bool ignore_spectator) -> R<void>
2868 {
2870 Episode->GetRecorder()->SetReplayerIgnoreSpectator(ignore_spectator);
2871 return R<void>::Success();
2872 };
2873
2874 BIND_SYNC(stop_replayer) << [this](bool keep_actors) -> R<void>
2875 {
2877 Episode->GetRecorder()->StopReplayer(keep_actors);
2878 return R<void>::Success();
2879 };
2880
2881 // ~~ Draw debug shapes ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2882
2883 BIND_SYNC(draw_debug_shape) << [this](const cr::DebugShape &shape) -> R<void>
2884 {
2886 auto *World = Episode->GetWorld();
2887 check(World != nullptr);
2888 FDebugShapeDrawer Drawer(*World);
2889 Drawer.Draw(shape);
2890 return R<void>::Success();
2891 };
2892
2893 // ~~ Apply commands in batch ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2894
2895 using C = cr::Command;
2896 using CR = cr::CommandResponse;
2897 using ActorId = carla::ActorId;
2898
2899 auto parse_result = [](ActorId id, const auto &response) {
2900 return response.HasError() ? CR{response.GetError()} : CR{id};
2901 };
2902
2903#define MAKE_RESULT(operation) return parse_result(c.actor, operation);
2904
2905 auto command_visitor = carla::Functional::MakeRecursiveOverload(
2906 [=](auto self, const C::SpawnActor &c) -> CR {
2907 auto result = c.parent.has_value() ?
2908 spawn_actor_with_parent(
2909 c.description,
2910 c.transform,
2911 *c.parent,
2912 cr::AttachmentType::Rigid,
2913 c.socket_name) :
2914 spawn_actor(c.description, c.transform);
2915 if (!result.HasError())
2916 {
2917 ActorId id = result.Get().id;
2918 auto set_id = carla::Functional::MakeOverload(
2919 [](C::SpawnActor &) {},
2920 [](C::ConsoleCommand &) {},
2921 [id](auto &s) { s.actor = id; });
2922 for (auto command : c.do_after)
2923 {
2924 boost::variant2::visit(set_id, command.command);
2925 boost::variant2::visit(self, command.command);
2926 }
2927 return id;
2928 }
2929 return result.GetError();
2930 },
2931 [=](auto, const C::DestroyActor &c) { MAKE_RESULT(destroy_actor(c.actor)); },
2932 [=](auto, const C::ApplyVehicleControl &c) { MAKE_RESULT(apply_control_to_vehicle(c.actor, c.control)); },
2933 [=](auto, const C::ApplyVehicleAckermannControl &c) { MAKE_RESULT(apply_ackermann_control_to_vehicle(c.actor, c.control)); },
2934 [=](auto, const C::ApplyWalkerControl &c) { MAKE_RESULT(apply_control_to_walker(c.actor, c.control)); },
2935 [=](auto, const C::ApplyVehiclePhysicsControl &c) { MAKE_RESULT(apply_physics_control(c.actor, c.physics_control)); },
2936 [=](auto, const C::ApplyTransform &c) { MAKE_RESULT(set_actor_transform(c.actor, c.transform)); },
2937 [=](auto, const C::ApplyTargetVelocity &c) { MAKE_RESULT(set_actor_target_velocity(c.actor, c.velocity)); },
2938 [=](auto, const C::ApplyTargetAngularVelocity &c) { MAKE_RESULT(set_actor_target_angular_velocity(c.actor, c.angular_velocity)); },
2939 [=](auto, const C::ApplyImpulse &c) { MAKE_RESULT(add_actor_impulse(c.actor, c.impulse)); },
2940 [=](auto, const C::ApplyForce &c) { MAKE_RESULT(add_actor_force(c.actor, c.force)); },
2941 [=](auto, const C::ApplyAngularImpulse &c) { MAKE_RESULT(add_actor_angular_impulse(c.actor, c.impulse)); },
2942 [=](auto, const C::ApplyTorque &c) { MAKE_RESULT(add_actor_torque(c.actor, c.torque)); },
2943 [=](auto, const C::SetSimulatePhysics &c) { MAKE_RESULT(set_actor_simulate_physics(c.actor, c.enabled)); },
2944 [=](auto, const C::SetEnableGravity &c) { MAKE_RESULT(set_actor_enable_gravity(c.actor, c.enabled)); },
2945 // TODO: SetAutopilot should be removed. This is the old way to control the vehicles
2946 [=](auto, const C::SetAutopilot &c) { MAKE_RESULT(set_actor_autopilot(c.actor, c.enabled)); },
2947 [=](auto, const C::ShowDebugTelemetry &c) { MAKE_RESULT(show_vehicle_debug_telemetry(c.actor, c.enabled)); },
2948 [=](auto, const C::SetVehicleLightState &c) { MAKE_RESULT(set_vehicle_light_state(c.actor, c.light_state)); },
2949// [=](auto, const C::OpenVehicleDoor &c) { MAKE_RESULT(open_vehicle_door(c.actor, c.door_idx)); },
2950// [=](auto, const C::CloseVehicleDoor &c) { MAKE_RESULT(close_vehicle_door(c.actor, c.door_idx)); },
2951 [=](auto, const C::ApplyWalkerState &c) { MAKE_RESULT(set_walker_state(c.actor, c.transform, c.speed)); },
2952 [=](auto, const C::ConsoleCommand& c) -> CR { return console_command(c.cmd); },
2953 [=](auto, const C::SetTrafficLightState& c) { MAKE_RESULT(set_traffic_light_state(c.actor, c.traffic_light_state)); },
2954 [=](auto, const C::ApplyLocation& c) { MAKE_RESULT(set_actor_location(c.actor, c.location)); }
2955 );
2956
2957#undef MAKE_RESULT
2958
2959 BIND_SYNC(apply_batch) << [=](
2960 const std::vector<cr::Command> &commands,
2961 bool do_tick_cue)
2962 {
2963 std::vector<CR> result;
2964 result.reserve(commands.size());
2965 for (const auto &command : commands)
2966 {
2967 result.emplace_back(boost::variant2::visit(command_visitor, command.command));
2968 }
2969 if (do_tick_cue)
2970 {
2971 tick_cue();
2972 }
2973 return result;
2974 };
2975
2976 // ~~ Light Subsystem ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2977
2978 BIND_SYNC(query_lights_state) << [this](std::string client) -> R<std::vector<cr::LightState>>
2979 {
2981 std::vector<cr::LightState> result;
2982 auto *World = Episode->GetWorld();
2983 if(World) {
2984 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
2985 result = CarlaLightSubsystem->GetLights(FString(client.c_str()));
2986 }
2987 return result;
2988 };
2989
2990 BIND_SYNC(update_lights_state) << [this]
2991 (std::string client, const std::vector<cr::LightState>& lights, bool discard_client) -> R<void>
2992 {
2994 auto *World = Episode->GetWorld();
2995 if(World) {
2996 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
2997 CarlaLightSubsystem->SetLights(FString(client.c_str()), lights, discard_client);
2998 }
2999 return R<void>::Success();
3000 };
3001
3002 BIND_SYNC(update_day_night_cycle) << [this]
3003 (std::string client, const bool active) -> R<void>
3004 {
3006 auto *World = Episode->GetWorld();
3007 if(World) {
3008 UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
3009 CarlaLightSubsystem->SetDayNightCycle(active);
3010 }
3011 return R<void>::Success();
3012 };
3013
3014
3015 // ~~ Ray Casting ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3016
3017 BIND_SYNC(project_point) << [this]
3018 (cr::Location Location, cr::Vector3D Direction, float SearchDistance)
3019 -> R<std::pair<bool,cr::LabelledPoint>>
3020 {
3022 auto *World = Episode->GetWorld();
3023 constexpr float meter_to_centimeter = 100.0f;
3024 FVector UELocation = Location;
3025 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
3026 ALargeMapManager* LargeMap = GameMode->GetLMManager();
3027 if (LargeMap)
3028 {
3029 UELocation = LargeMap->GlobalToLocalLocation(UELocation);
3030 }
3031 return URayTracer::ProjectPoint(UELocation, Direction.ToFVector(),
3032 meter_to_centimeter * SearchDistance, World);
3033 };
3034
3035 BIND_SYNC(cast_ray) << [this]
3036 (cr::Location StartLocation, cr::Location EndLocation)
3037 -> R<std::vector<cr::LabelledPoint>>
3038 {
3040 auto *World = Episode->GetWorld();
3041 FVector UEStartLocation = StartLocation;
3042 FVector UEEndLocation = EndLocation;
3043 ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
3044 ALargeMapManager* LargeMap = GameMode->GetLMManager();
3045 if (LargeMap)
3046 {
3047 UEStartLocation = LargeMap->GlobalToLocalLocation(UEStartLocation);
3048 UEEndLocation = LargeMap->GlobalToLocalLocation(UEEndLocation);
3049 }
3050 return URayTracer::CastRay(StartLocation, EndLocation, World);
3051 };
3052
3053}
3054
3055// =============================================================================
3056// -- Undef helper macros ------------------------------------------------------
3057// =============================================================================
3058
3059#undef BIND_ASYNC
3060#undef BIND_SYNC
3061#undef REQUIRE_CARLA_EPISODE
3062#undef RESPOND_ERROR_FSTRING
3063#undef RESPOND_ERROR
3064#undef CARLA_ENSURE_GAME_THREAD
3065
3066// =============================================================================
3067// -- FCarlaServer -------------------------------------------------------
3068// =============================================================================
3069
3071
3075
3076FDataMultiStream FCarlaServer::Start(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
3077{
3078 Pimpl = MakeUnique<FPimpl>(RPCPort, StreamingPort, SecondaryPort);
3079 StreamingPort = Pimpl->StreamingServer.GetLocalEndpoint().port();
3080 SecondaryPort = Pimpl->SecondaryServer->GetLocalEndpoint().port();
3081
3082 UE_LOG(
3083 LogCarlaServer,
3084 Log,
3085 TEXT("Initialized CarlaServer: Ports(rpc=%d, streaming=%d, secondary=%d)"),
3086 RPCPort,
3087 StreamingPort,
3088 SecondaryPort);
3089 return Pimpl->BroadcastStream;
3090}
3091
3093{
3094 check(Pimpl != nullptr);
3095 UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName());
3096 Pimpl->Episode = &Episode;
3097}
3098
3100{
3101 check(Pimpl != nullptr);
3102 Pimpl->Episode = nullptr;
3103}
3104
3105void FCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads)
3106{
3107 check(Pimpl != nullptr);
3108 /// @todo Define better the number of threads each server gets.
3109 int ThreadsPerServer = std::max(2u, NumberOfWorkerThreads / 3u);
3110 int32_t RPCThreads;
3111 int32_t StreamingThreads;
3112 int32_t SecondaryThreads;
3113
3114 UE_LOG(LogCarla, Log, TEXT("FCommandLine %s"), FCommandLine::Get());
3115
3116 if(!FParse::Value(FCommandLine::Get(), TEXT("-RPCThreads="), RPCThreads))
3117 {
3118 RPCThreads = ThreadsPerServer;
3119 }
3120 if(!FParse::Value(FCommandLine::Get(), TEXT("-StreamingThreads="), StreamingThreads))
3121 {
3122 StreamingThreads = ThreadsPerServer;
3123 }
3124 if(!FParse::Value(FCommandLine::Get(), TEXT("-SecondaryThreads="), SecondaryThreads))
3125 {
3126 SecondaryThreads = ThreadsPerServer;
3127 }
3128
3129 UE_LOG(LogCarla, Log, TEXT("FCarlaServer AsyncRun %d, RPCThreads %d, StreamingThreads %d, SecondaryThreads %d"),
3130 NumberOfWorkerThreads, RPCThreads, StreamingThreads, SecondaryThreads);
3131
3132 Pimpl->Server.AsyncRun(RPCThreads);
3133 Pimpl->StreamingServer.AsyncRun(StreamingThreads);
3134 Pimpl->SecondaryServer->AsyncRun(SecondaryThreads);
3135}
3136
3137void FCarlaServer::RunSome(uint32 Milliseconds)
3138{
3139 TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
3140 Pimpl->Server.SyncRunFor(carla::time_duration::milliseconds(Milliseconds));
3141}
3142
3144{
3145 (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release);
3146}
3147
3149{
3150 auto k = Pimpl->TickCuesReceived.fetch_sub(1, std::memory_order_acquire);
3151 bool flag = (k > 0);
3152 if (!flag)
3153 (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release);
3154 return flag;
3155}
3156
3158{
3159 if (Pimpl)
3160 {
3161 Pimpl->Server.Stop();
3162 Pimpl->SecondaryServer->Stop();
3163 }
3164}
3165
3167{
3168 check(Pimpl != nullptr);
3169 return Pimpl->StreamingServer.MakeStream();
3170}
3171
3172std::shared_ptr<carla::multigpu::Router> FCarlaServer::GetSecondaryServer()
3173{
3174 return Pimpl->GetSecondaryServer();
3175}
3176
3178{
3179 return Pimpl->StreamingServer;
3180}
EAttachmentType
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
Base class for the 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)
std::string ShowFileCollisions(std::string Name, char Type1, char Type2)
void StopReplayer(bool KeepActors=false)
std::string ShowFileInfo(std::string Name, bool bShowAll=false)
std::string ReplayFile(std::string Name, double TimeStart, double Duration, uint32_t FollowId, bool ReplaySensors)
std::string ShowFileActorsBlocked(std::string Name, double MinTime=30, double MinDistance=10)
void SetReplayerIgnoreSpectator(bool IgnoreSpectator)
void SetReplayerIgnoreHero(bool IgnoreHero)
void SetReplayerTimeFactor(double TimeFactor)
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
auto begin() const noexcept
A view over an actor and its properties.
Definition CarlaActor.h:25
ECarlaServerResponse AddActorImpulseAtLocation(const FVector &Impulse, const FVector &Location)
virtual ECarlaServerResponse GetPhysicsControl(FVehiclePhysicsControl &)
Definition CarlaActor.h:244
ECarlaServerResponse AddActorForceAtLocation(const FVector &Force, const FVector &Location)
virtual ECarlaServerResponse SetActorEnableGravity(bool bEnabled)
virtual ECarlaServerResponse GetBonesTransform(FWalkerBoneControlOut &)
Definition CarlaActor.h:409
virtual ECarlaServerResponse GetAckermannControllerSettings(FAckermannControllerSettings &)
Definition CarlaActor.h:311
virtual ECarlaServerResponse SetLightRedTime(float)
Definition CarlaActor.h:384
virtual ECarlaServerResponse ResetTrafficLightGroup()
Definition CarlaActor.h:439
IdType GetParent() const
Definition CarlaActor.h:121
ActorType GetActorType() const
Definition CarlaActor.h:86
virtual ECarlaServerResponse SetLightYellowTime(float)
Definition CarlaActor.h:379
virtual ECarlaServerResponse GetPoseFromAnimation()
Definition CarlaActor.h:424
virtual ECarlaServerResponse SetActorAutopilot(bool, bool bKeepState=false)
Definition CarlaActor.h:321
ECarlaServerResponse AddActorTorque(const FVector &Torque)
ECarlaServerResponse SetActorTargetAngularVelocity(const FVector &AngularVelocity)
bool IsDormant() const
Definition CarlaActor.h:71
ECarlaServerResponse AddActorImpulse(const FVector &Impulse)
AActor * GetActor()
Definition CarlaActor.h:91
virtual ECarlaServerResponse SetVehicleLightState(const FVehicleLightState &)
Definition CarlaActor.h:274
virtual ECarlaServerResponse SetActorDead()
Definition CarlaActor.h:429
virtual ECarlaServerResponse ApplyControlToVehicle(const FVehicleControl &, const EVehicleInputPriority &)
Definition CarlaActor.h:289
virtual ECarlaServerResponse GetWheelSteerAngle(const EVehicleWheelLocation &, float &)
Definition CarlaActor.h:284
virtual ECarlaServerResponse ApplyAckermannControllerSettings(const FAckermannControllerSettings &)
Definition CarlaActor.h:316
virtual ECarlaServerResponse SetActorCollisions(bool bEnabled)
virtual ECarlaServerResponse GetVehicleTelemetryData(FVehicleTelemetryData &)
Definition CarlaActor.h:326
virtual ECarlaServerResponse CloseVehicleDoor(const EVehicleDoor)
Definition CarlaActor.h:264
virtual ECarlaServerResponse RestorePhysXPhysics()
Definition CarlaActor.h:352
virtual ECarlaServerResponse ApplyAckermannControlToVehicle(const FVehicleAckermannControl &, const EVehicleInputPriority &)
Definition CarlaActor.h:295
void SetParent(IdType InParentId)
Definition CarlaActor.h:116
void SetAttachmentType(carla::rpc::AttachmentType InAttachmentType)
Definition CarlaActor.h:141
virtual ECarlaServerResponse SetWalkerState(const FTransform &Transform, carla::rpc::WalkerControl WalkerControl)
Definition CarlaActor.h:392
virtual ECarlaServerResponse DisableActorConstantVelocity()
Definition CarlaActor.h:239
virtual ECarlaServerResponse GetVehicleLightState(FVehicleLightState &)
Definition CarlaActor.h:254
virtual ECarlaServerResponse SetBonesTransform(const FWalkerBoneControlIn &)
Definition CarlaActor.h:414
virtual ECarlaServerResponse FreezeTrafficLight(bool)
Definition CarlaActor.h:434
void SetActorGlobalTransform(const FTransform &Transform, ETeleportType Teleport=ETeleportType::TeleportPhysics)
virtual ECarlaServerResponse ApplyControlToWalker(const FWalkerControl &)
Definition CarlaActor.h:399
void SetActorState(carla::rpc::ActorState InState)
Definition CarlaActor.h:111
void SetActorGlobalLocation(const FVector &Location, ETeleportType Teleport=ETeleportType::TeleportPhysics)
virtual ECarlaServerResponse UseCarSimRoad(bool)
Definition CarlaActor.h:341
virtual ECarlaServerResponse ApplyPhysicsControl(const FVehiclePhysicsControl &)
Definition CarlaActor.h:269
virtual ECarlaServerResponse SetLightGreenTime(float)
Definition CarlaActor.h:374
void AddChildren(IdType ChildId)
Definition CarlaActor.h:126
virtual ECarlaServerResponse OpenVehicleDoor(const EVehicleDoor)
Definition CarlaActor.h:259
const FActorInfo * GetActorInfo() const
Definition CarlaActor.h:101
IdType GetActorId() const
Definition CarlaActor.h:81
virtual ECarlaServerResponse EnableActorConstantVelocity(const FVector &)
Definition CarlaActor.h:234
virtual ECarlaServerResponse SetWheelSteerDirection(const EVehicleWheelLocation &, float)
Definition CarlaActor.h:279
virtual ECarlaServerResponse EnableCarSim(const FString &)
Definition CarlaActor.h:336
ECarlaServerResponse SetActorTargetVelocity(const FVector &Velocity)
ECarlaServerResponse AddActorForce(const FVector &Force)
virtual ECarlaServerResponse BlendPose(float Blend)
Definition CarlaActor.h:419
virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool)
Definition CarlaActor.h:331
virtual ECarlaServerResponse SetActorSimulatePhysics(bool bEnabled)
virtual ECarlaServerResponse EnableChronoPhysics(uint64_t, float, const FString &, const FString &, const FString &, const FString &)
Definition CarlaActor.h:346
ECarlaServerResponse AddActorAngularImpulse(const FVector &AngularInpulse)
virtual ECarlaServerResponse SetTrafficLightState(const ETrafficLightState &)
Definition CarlaActor.h:359
static uint64_t GetFrameCounter()
Definition CarlaEngine.h:65
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
Map of pairs < port , ip > with all the Traffic Managers active in the simulation
bool TickCueReceived()
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
void RunSome(uint32 Milliseconds)
TUniquePtr< FPimpl > Pimpl
Definition CarlaServer.h:54
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)
A simulation episode.
auto GetId() const
Return the unique id of this episode.
std::string StartRecorder(std::string name, bool AdditionalData)
carla::rpc::Actor SerializeActor(FCarlaActor *CarlaActor) const
Create a serializable object describing the actor.
void PutActorToSleep(carla::rpc::ActorId ActorId)
bool LoadNewOpendriveEpisode(const FString &OpenDriveString, const carla::rpc::OpendriveGenerationParameters &Params)
Load a new map generating the mesh from OpenDRIVE data and start a new episode.
const TArray< FActorDefinition > & GetActorDefinitions() const
Return the list of actor definitions that are available to be spawned this episode.
FCarlaActor * FindCarlaActor(FCarlaActor::IdType ActorId)
Find a Carla actor by id.
const FString & GetMapName() const
Return the name of the map loaded in this episode.
AWeather * GetWeather() const
void ApplySettings(const FEpisodeSettings &Settings)
FString GetActorDescriptionFromStream(carla::streaming::detail::stream_id_type StreamId)
Get the description of the Carla actor (sensor) using specific stream id.
TPair< EActorSpawnResultStatus, FCarlaActor * > SpawnActorWithInfo(const FTransform &Transform, FActorDescription thisActorDescription, FCarlaActor::IdType DesiredId=0)
Spawns an actor based on ActorDescription at Transform.
const FEpisodeSettings & GetSettings() const
APawn * GetSpectatorPawn() const
const FActorRegistry & GetActorRegistry() const
ACarlaRecorder * GetRecorder() const
bool LoadNewEpisode(const FString &MapString, bool ResetSettings=true)
Load a new map and start a new episode.
TArray< FTransform > GetRecommendedSpawnPoints() const
Return the list of recommended spawn points for vehicles.
void AttachActors(AActor *Child, AActor *Parent, EAttachmentType InAttachmentType=EAttachmentType::Rigid, const FString &SocketName="")
Attach Child to Parent.
bool DestroyActor(AActor *Actor)
The game instance contains elements that must be kept alive in between levels.
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)
Return the OpenDrive XML associated to MapName, or empty if the file is not found.
static std::pair< bool, carla::rpc::LabelledPoint > ProjectPoint(FVector StartLocation, FVector Direction, float MaxDistance, UWorld *World)
Definition RayTracer.cpp:46
static std::vector< carla::rpc::LabelledPoint > CastRay(FVector StartLocation, FVector EndLocation, UWorld *World)
Definition RayTracer.cpp:15
static auto MakeOverload(FuncTs &&... fs)
Creates an "overloaded callable object" out of one or more callable objects, each callable object wil...
Definition Functional.h:27
static auto MakeRecursiveOverload(FuncTs &&... fs)
Definition Functional.h:33
Vector3D GetForwardVector() const
static std::shared_ptr< ROS2 > GetInstance()
Definition ROS2.h:51
An RPC server in which functions can be bind to run synchronously or asynchronously.
Definition rpc/Server.h:37
void BindSync(const std::string &name, FunctorT &&functor)
Definition rpc/Server.h:152
void BindAsync(const std::string &name, FunctorT &&functor)
Definition rpc/Server.h:160
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 associated with this stream.
constexpr size_t milliseconds() const noexcept
Definition Time.h:58
uint32_t stream_id_type
Definition Types.h:18
rpc::ActorId ActorId
Definition ActorId.h:18
TMap< FString, FActorAttribute > Variations
User selected variations of the actor.
FActorDescription Description
Definition ActorInfo.h:26
static FString StatusToString(EActorSpawnResultStatus Status)
auto GetToken() const
Return the token that allows subscribing to this sensor's stream.