CARLA
CarlaServer.cpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
2 // de Barcelona (UAB).
3 //
4 // This work is licensed under the terms of the MIT license.
5 // For a copy, see <https://opensource.org/licenses/MIT>.
6 
7 #include "Carla.h"
10 #include "EngineUtils.h"
11 
15 #include "Carla/Util/RayTracer.h"
19 #include "GameFramework/CharacterMovementComponent.h"
20 #include "Carla/Game/Tagger.h"
24 #include "Carla/Actor/ActorData.h"
25 #include "CarlaServerResponse.h"
27 #include "Misc/FileHelper.h"
28 
30 #include <carla/Functional.h>
31 #include <carla/multigpu/router.h>
32 #include <carla/Version.h>
34 #include <carla/rpc/Actor.h>
38 #include <carla/rpc/Command.h>
40 #include <carla/rpc/DebugShape.h>
42 #include <carla/rpc/EpisodeInfo.h>
45 #include <carla/rpc/LightState.h>
46 #include <carla/rpc/MapInfo.h>
47 #include <carla/rpc/MapLayer.h>
48 #include <carla/rpc/Response.h>
49 #include <carla/rpc/Server.h>
50 #include <carla/rpc/String.h>
51 #include <carla/rpc/Transform.h>
52 #include <carla/rpc/Vector2D.h>
53 #include <carla/rpc/Vector3D.h>
54 #include <carla/rpc/VehicleDoor.h>
66 #include <carla/rpc/Texture.h>
69 
70 #include <vector>
71 #include <atomic>
72 #include <map>
73 #include <tuple>
74 
75 template <typename T>
77 
78 // =============================================================================
79 // -- Static local functions ---------------------------------------------------
80 // =============================================================================
81 
82 template <typename T, typename Other>
83 static std::vector<T> MakeVectorFromTArray(const TArray<Other> &Array)
84 {
85  return {Array.GetData(), Array.GetData() + Array.Num()};
86 }
87 
88 // =============================================================================
89 // -- FCarlaServer::FPimpl -----------------------------------------------
90 // =============================================================================
91 
93 {
94 public:
95 
96  FPimpl(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
97  : Server(RPCPort),
98  StreamingServer(StreamingPort),
99  BroadcastStream(StreamingServer.MakeStream())
100  {
101  // we need to create shared_ptr from the router for some handlers to live
102  SecondaryServer = std::make_shared<carla::multigpu::Router>(SecondaryPort);
103  SecondaryServer->SetCallbacks();
104  BindActions();
105  }
106 
107  std::shared_ptr<carla::multigpu::Router> GetSecondaryServer() {
108  return SecondaryServer;
109  }
110 
111  /// Map of pairs < port , ip > with all the Traffic Managers active in the simulation
112  std::map<uint16_t, std::string> TrafficManagerInfo;
113 
115 
117 
119 
120  std::shared_ptr<carla::multigpu::Router> SecondaryServer;
121 
122  UCarlaEpisode *Episode = nullptr;
123 
124  std::atomic_size_t TickCuesReceived { 0u };
125 
126 private:
127 
128  void BindActions();
129 };
130 
131 // =============================================================================
132 // -- Define helper macros -----------------------------------------------------
133 // =============================================================================
134 
135 #if WITH_EDITOR
136 # define CARLA_ENSURE_GAME_THREAD() check(IsInGameThread());
137 #else
138 # define CARLA_ENSURE_GAME_THREAD()
139 #endif // WITH_EDITOR
140 
141 #define RESPOND_ERROR(str) { \
142  UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), TEXT(str)); \
143  return carla::rpc::ResponseError(str); }
144 
145 #define RESPOND_ERROR_FSTRING(fstr) { \
146  UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), *fstr); \
147  return carla::rpc::ResponseError(carla::rpc::FromFString(fstr)); }
148 
149 #define REQUIRE_CARLA_EPISODE() \
150  CARLA_ENSURE_GAME_THREAD(); \
151  if (Episode == nullptr) { RESPOND_ERROR("episode not ready"); }
152 
154  const FString& FuncName,
155  const FString& ErrorMessage,
156  const FString& ExtraInfo = "")
157 {
158  FString TotalMessage = "Responding error from function " + FuncName + ": " +
159  ErrorMessage + ". " + ExtraInfo;
160  UE_LOG(LogCarlaServer, Log, TEXT("%s"), *TotalMessage);
161  return carla::rpc::ResponseError(carla::rpc::FromFString(TotalMessage));
162 }
163 
165  const FString& FuncName,
166  const ECarlaServerResponse& Error,
167  const FString& ExtraInfo = "")
168 {
169  return RespondError(FuncName, GetStringError(Error), ExtraInfo);
170 }
171 
173 {
174 public:
175 
176  constexpr ServerBinder(const char *name, carla::rpc::Server &srv, bool sync)
177  : _name(name),
178  _server(srv),
179  _sync(sync) {}
180 
181  template <typename FuncT>
182  auto operator<<(FuncT func)
183  {
184  if (_sync)
185  {
186  _server.BindSync(_name, func);
187  }
188  else
189  {
190  _server.BindAsync(_name, func);
191  }
192  return func;
193  }
194 
195 private:
196 
197  const char *_name;
198 
200 
201  bool _sync;
202 };
203 
204 #define BIND_SYNC(name) auto name = ServerBinder(# name, Server, true)
205 #define BIND_ASYNC(name) auto name = ServerBinder(# name, Server, false)
206 
207 // =============================================================================
208 // -- Bind Actions -------------------------------------------------------------
209 // =============================================================================
210 
212 {
213  namespace cr = carla::rpc;
214  namespace cg = carla::geom;
215 
216  /// Looks for a Traffic Manager running on port
217  BIND_SYNC(is_traffic_manager_running) << [this] (uint16_t port) ->R<bool>
218  {
219  return (TrafficManagerInfo.find(port) != TrafficManagerInfo.end());
220  };
221 
222  /// Gets a pair filled with the <IP, port> of the Trafic Manager running on port.
223  /// If there is no Traffic Manager running the pair will be ("", 0)
224  BIND_SYNC(get_traffic_manager_running) << [this] (uint16_t port) ->R<std::pair<std::string, uint16_t>>
225  {
226  auto it = TrafficManagerInfo.find(port);
227  if(it != TrafficManagerInfo.end()) {
228  return std::pair<std::string, uint16_t>(it->second, it->first);
229  }
230  return std::pair<std::string, uint16_t>("",0);
231  };
232 
233  /// Add a new Traffic Manager running on <IP, port>
234  BIND_SYNC(add_traffic_manager_running) << [this] (std::pair<std::string, uint16_t> trafficManagerInfo) ->R<bool>
235  {
236  uint16_t port = trafficManagerInfo.second;
237  auto it = TrafficManagerInfo.find(port);
238  if(it == TrafficManagerInfo.end()) {
239  TrafficManagerInfo.insert(
240  std::pair<uint16_t, std::string>(port, trafficManagerInfo.first));
241  return true;
242  }
243  return false;
244 
245  };
246 
247  BIND_SYNC(destroy_traffic_manager) << [this] (uint16_t port) ->R<bool>
248  {
249  auto it = TrafficManagerInfo.find(port);
250  if(it != TrafficManagerInfo.end()) {
251  TrafficManagerInfo.erase(it);
252  return true;
253  }
254  return false;
255  };
256 
257  BIND_ASYNC(version) << [] () -> R<std::string>
258  {
259  return carla::version();
260  };
261 
262  // ~~ Tick ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
263 
264  BIND_SYNC(tick_cue) << [this]() -> R<uint64_t>
265  {
266  TRACE_CPUPROFILER_EVENT_SCOPE(TickCueReceived);
267  auto Current = FCarlaEngine::GetFrameCounter();
268  (void)TickCuesReceived.fetch_add(1, std::memory_order_release);
269  return Current + 1;
270  };
271 
272  // ~~ Load new episode ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
273 
274  BIND_ASYNC(get_available_maps) << [this]() -> R<std::vector<std::string>>
275  {
276  const auto MapNames = UCarlaStatics::GetAllMapNames();
277  std::vector<std::string> result;
278  result.reserve(MapNames.Num());
279  for (const auto &MapName : MapNames)
280  {
281  if (MapName.Contains("/Sublevels/"))
282  continue;
283  if (MapName.Contains("/BaseMap/"))
284  continue;
285  if (MapName.Contains("/BaseLargeMap/"))
286  continue;
287  if (MapName.Contains("_Tile_"))
288  continue;
289 
290  result.emplace_back(cr::FromFString(MapName));
291  }
292  return result;
293  };
294 
295  BIND_SYNC(load_new_episode) << [this](const std::string &map_name, const bool reset_settings, cr::MapLayer MapLayers) -> R<void>
296  {
298 
299  UCarlaGameInstance* GameInstance = UCarlaStatics::GetGameInstance(Episode->GetWorld());
300  if (!GameInstance)
301  {
302  RESPOND_ERROR("unable to find CARLA game instance");
303  }
304  GameInstance->SetMapLayer(static_cast<int32>(MapLayers));
305 
306  if(!Episode->LoadNewEpisode(cr::ToFString(map_name), reset_settings))
307  {
308  RESPOND_ERROR("map not found");
309  }
310 
311  return R<void>::Success();
312  };
313 
314  BIND_SYNC(load_map_layer) << [this](cr::MapLayer MapLayers) -> R<void>
315  {
317 
318  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
319  if (!GameMode)
320  {
321  RESPOND_ERROR("unable to find CARLA game mode");
322  }
323  GameMode->LoadMapLayer(static_cast<int32>(MapLayers));
324 
325  return R<void>::Success();
326  };
327 
328  BIND_SYNC(unload_map_layer) << [this](cr::MapLayer MapLayers) -> R<void>
329  {
331 
332  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
333  if (!GameMode)
334  {
335  RESPOND_ERROR("unable to find CARLA game mode");
336  }
337  GameMode->UnLoadMapLayer(static_cast<int32>(MapLayers));
338 
339  return R<void>::Success();
340  };
341 
342  BIND_SYNC(copy_opendrive_to_file) << [this](const std::string &opendrive, cr::OpendriveGenerationParameters Params) -> R<void>
343  {
345  if (!Episode->LoadNewOpendriveEpisode(cr::ToLongFString(opendrive), Params))
346  {
347  RESPOND_ERROR("opendrive could not be correctly parsed");
348  }
349  return R<void>::Success();
350  };
351 
352  BIND_SYNC(apply_color_texture_to_objects) << [this](
353  const std::vector<std::string> &actors_name,
354  const cr::MaterialParameter& parameter,
355  const cr::TextureColor& Texture) -> R<void>
356  {
358  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
359  if (!GameMode)
360  {
361  RESPOND_ERROR("unable to find CARLA game mode");
362  }
363  TArray<AActor*> ActorsToPaint;
364  for(const std::string& actor_name : actors_name)
365  {
366  AActor* ActorToPaint = GameMode->FindActorByName(cr::ToFString(actor_name));
367  if (ActorToPaint)
368  {
369  ActorsToPaint.Add(ActorToPaint);
370  }
371  }
372 
373  if(!ActorsToPaint.Num())
374  {
375  RESPOND_ERROR("unable to find Actor to apply the texture");
376  }
377 
378  UTexture2D* UETexture = GameMode->CreateUETexture(Texture);
379 
380  for(AActor* ActorToPaint : ActorsToPaint)
381  {
382  GameMode->ApplyTextureToActor(
383  ActorToPaint,
384  UETexture,
385  parameter);
386  }
387  return R<void>::Success();
388  };
389 
390  BIND_SYNC(apply_float_color_texture_to_objects) << [this](
391  const std::vector<std::string> &actors_name,
392  const cr::MaterialParameter& parameter,
393  const cr::TextureFloatColor& Texture) -> R<void>
394  {
396  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
397  if (!GameMode)
398  {
399  RESPOND_ERROR("unable to find CARLA game mode");
400  }
401  TArray<AActor*> ActorsToPaint;
402  for(const std::string& actor_name : actors_name)
403  {
404  AActor* ActorToPaint = GameMode->FindActorByName(cr::ToFString(actor_name));
405  if (ActorToPaint)
406  {
407  ActorsToPaint.Add(ActorToPaint);
408  }
409  }
410 
411  if(!ActorsToPaint.Num())
412  {
413  RESPOND_ERROR("unable to find Actor to apply the texture");
414  }
415 
416  UTexture2D* UETexture = GameMode->CreateUETexture(Texture);
417 
418  for(AActor* ActorToPaint : ActorsToPaint)
419  {
420  GameMode->ApplyTextureToActor(
421  ActorToPaint,
422  UETexture,
423  parameter);
424  }
425  return R<void>::Success();
426  };
427 
428  BIND_SYNC(get_names_of_all_objects) << [this]() -> R<std::vector<std::string>>
429  {
431  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
432  if (!GameMode)
433  {
434  RESPOND_ERROR("unable to find CARLA game mode");
435  }
436  TArray<FString> NamesFString = GameMode->GetNamesOfAllActors();
437  std::vector<std::string> NamesStd;
438  for (const FString &Name : NamesFString)
439  {
440  NamesStd.emplace_back(cr::FromFString(Name));
441  }
442  return NamesStd;
443  };
444 
445  // ~~ Episode settings and info ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
446 
447  BIND_SYNC(get_episode_info) << [this]() -> R<cr::EpisodeInfo>
448  {
450  return cr::EpisodeInfo{Episode->GetId(), BroadcastStream.token()};
451  };
452 
453  BIND_SYNC(get_map_info) << [this]() -> R<cr::MapInfo>
454  {
456  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
457  const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
458  FString FullMapPath = GameMode->GetFullMapPath();
459  FString MapDir = FullMapPath.RightChop(FullMapPath.Find("Content/", ESearchCase::CaseSensitive) + 8);
460  MapDir += "/" + Episode->GetMapName();
461  return cr::MapInfo{
462  cr::FromFString(MapDir),
463  MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
464  };
465 
466  BIND_SYNC(get_map_data) << [this]() -> R<std::string>
467  {
469  return cr::FromLongFString(UOpenDrive::GetXODR(Episode->GetWorld()));
470  };
471 
472  BIND_SYNC(get_navigation_mesh) << [this]() -> R<std::vector<uint8_t>>
473  {
475  auto FileContents = FNavigationMesh::Load(Episode->GetMapName());
476  // make a mem copy (from TArray to std::vector)
477  std::vector<uint8_t> Result(FileContents.Num());
478  memcpy(&Result[0], FileContents.GetData(), FileContents.Num());
479  return Result;
480  };
481 
482  BIND_SYNC(get_required_files) << [this](std::string folder = "") -> R<std::vector<std::string>>
483  {
485 
486  // Check that the path ends in a slash, add it otherwise
487  if (folder[folder.size() - 1] != '/' && folder[folder.size() - 1] != '\\') {
488  folder += "/";
489  }
490 
491  // Get the map's folder absolute path and check if it's in its own folder
492  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
493  const auto mapDir = GameMode->GetFullMapPath();
494  const auto folderDir = mapDir + "/" + folder.c_str();
495  const auto fileName = mapDir.EndsWith(Episode->GetMapName()) ? "*" : Episode->GetMapName();
496 
497  // Find all the xodr and bin files from the map
498  TArray<FString> Files;
499  IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName + ".xodr"), true, false, false);
500  IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName + ".bin"), true, false, false);
501 
502  // Remove the start of the path until the content folder and put each file in the result
503  std::vector<std::string> result;
504  for (auto File : Files) {
505  File.RemoveFromStart(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
506  result.emplace_back(TCHAR_TO_UTF8(*File));
507  }
508 
509  return result;
510  };
511  BIND_SYNC(request_file) << [this](std::string name) -> R<std::vector<uint8_t>>
512  {
514 
515  // Get the absolute path of the file
516  FString path(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
517  path.Append(name.c_str());
518 
519  // Copy the binary data of the file into the result and return it
520  TArray<uint8_t> Content;
521  FFileHelper::LoadFileToArray(Content, *path, 0);
522  std::vector<uint8_t> Result(Content.Num());
523  memcpy(&Result[0], Content.GetData(), Content.Num());
524 
525  return Result;
526  };
527 
528  BIND_SYNC(get_episode_settings) << [this]() -> R<cr::EpisodeSettings>
529  {
531  return cr::EpisodeSettings{Episode->GetSettings()};
532  };
533 
534  BIND_SYNC(set_episode_settings) << [this](
535  const cr::EpisodeSettings &settings) -> R<uint64_t>
536  {
538  Episode->ApplySettings(settings);
539  StreamingServer.SetSynchronousMode(settings.synchronous_mode);
541  };
542 
543  BIND_SYNC(get_actor_definitions) << [this]() -> R<std::vector<cr::ActorDefinition>>
544  {
546  return MakeVectorFromTArray<cr::ActorDefinition>(Episode->GetActorDefinitions());
547  };
548 
549  BIND_SYNC(get_spectator) << [this]() -> R<cr::Actor>
550  {
553  if (!CarlaActor)
554  {
555  RESPOND_ERROR("internal error: unable to find spectator");
556  }
557  return Episode->SerializeActor(CarlaActor);
558  };
559 
560  BIND_SYNC(get_all_level_BBs) << [this](uint8 QueriedTag) -> R<std::vector<cg::BoundingBox>>
561  {
563  TArray<FBoundingBox> Result;
564  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
565  if (!GameMode)
566  {
567  RESPOND_ERROR("unable to find CARLA game mode");
568  }
569  Result = GameMode->GetAllBBsOfLevel(QueriedTag);
570  ALargeMapManager* LargeMap = GameMode->GetLMManager();
571  if (LargeMap)
572  {
573  for(auto& Box : Result)
574  {
575  Box.Origin = LargeMap->LocalToGlobalLocation(Box.Origin);
576  }
577  }
578  return MakeVectorFromTArray<cg::BoundingBox>(Result);
579  };
580 
581  BIND_SYNC(get_environment_objects) << [this](uint8 QueriedTag) -> R<std::vector<cr::EnvironmentObject>>
582  {
584  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
585  if (!GameMode)
586  {
587  RESPOND_ERROR("unable to find CARLA game mode");
588  }
589  TArray<FEnvironmentObject> Result = GameMode->GetEnvironmentObjects(QueriedTag);
590  ALargeMapManager* LargeMap = GameMode->GetLMManager();
591  if (LargeMap)
592  {
593  for(auto& Object : Result)
594  {
595  Object.Transform = LargeMap->LocalToGlobalTransform(Object.Transform);
596  }
597  }
598  return MakeVectorFromTArray<cr::EnvironmentObject>(Result);
599  };
600 
601  BIND_SYNC(enable_environment_objects) << [this](std::vector<uint64_t> EnvObjectIds, bool Enable) -> R<void>
602  {
604  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
605  if (!GameMode)
606  {
607  RESPOND_ERROR("unable to find CARLA game mode");
608  }
609 
610  TSet<uint64> EnvObjectIdsSet;
611  for(uint64 Id : EnvObjectIds)
612  {
613  EnvObjectIdsSet.Emplace(Id);
614  }
615 
616  GameMode->EnableEnvironmentObjects(EnvObjectIdsSet, Enable);
617  return R<void>::Success();
618  };
619 
620  // ~~ Weather ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
621 
622  BIND_SYNC(get_weather_parameters) << [this]() -> R<cr::WeatherParameters>
623  {
625  auto *Weather = Episode->GetWeather();
626  if (Weather == nullptr)
627  {
628  RESPOND_ERROR("internal error: unable to find weather");
629  }
630  return Weather->GetCurrentWeather();
631  };
632 
633  BIND_SYNC(set_weather_parameters) << [this](
634  const cr::WeatherParameters &weather) -> R<void>
635  {
637  auto *Weather = Episode->GetWeather();
638  if (Weather == nullptr)
639  {
640  RESPOND_ERROR("internal error: unable to find weather");
641  }
642  Weather->ApplyWeather(weather);
643  return R<void>::Success();
644  };
645 
646  // ~~ Actor operations ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
647 
648  BIND_SYNC(get_actors_by_id) << [this](
649  const std::vector<FCarlaActor::IdType> &ids) -> R<std::vector<cr::Actor>>
650  {
652  std::vector<cr::Actor> Result;
653  Result.reserve(ids.size());
654  for (auto &&Id : ids)
655  {
656  FCarlaActor* View = Episode->FindCarlaActor(Id);
657  if (View)
658  {
659  Result.emplace_back(Episode->SerializeActor(View));
660  }
661  }
662  return Result;
663  };
664 
665  BIND_SYNC(spawn_actor) << [this](
666  cr::ActorDescription Description,
668  {
670 
671  auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
672 
673  if (Result.Key != EActorSpawnResultStatus::Success)
674  {
675  UE_LOG(LogCarla, Error, TEXT("Actor not Spawned"));
677  }
678 
680  if(LargeMap)
681  {
682  LargeMap->OnActorSpawned(*Result.Value);
683  }
684 
685  return Episode->SerializeActor(Result.Value);
686  };
687 
688  BIND_SYNC(spawn_actor_with_parent) << [this](
689  cr::ActorDescription Description,
690  const cr::Transform &Transform,
691  cr::ActorId ParentId,
692  cr::AttachmentType InAttachmentType) -> R<cr::Actor>
693  {
695 
696  auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
697  if (Result.Key != EActorSpawnResultStatus::Success)
698  {
700  }
701 
702  FCarlaActor* CarlaActor = Episode->FindCarlaActor(Result.Value->GetActorId());
703  if (!CarlaActor)
704  {
705  RESPOND_ERROR("internal error: actor could not be spawned");
706  }
707 
708  FCarlaActor* ParentCarlaActor = Episode->FindCarlaActor(ParentId);
709 
710  if (!ParentCarlaActor)
711  {
712  RESPOND_ERROR("unable to attach actor: parent actor not found");
713  }
714 
715  CarlaActor->SetParent(ParentId);
716  CarlaActor->SetAttachmentType(InAttachmentType);
717  ParentCarlaActor->AddChildren(CarlaActor->GetActorId());
718 
719  // Only is possible to attach if the actor has been really spawned and
720  // is not in dormant state
721  if(!ParentCarlaActor->IsDormant())
722  {
724  CarlaActor->GetActor(),
725  ParentCarlaActor->GetActor(),
726  static_cast<EAttachmentType>(InAttachmentType));
727  }
728  else
729  {
730  Episode->PutActorToSleep(CarlaActor->GetActorId());
731  }
732 
733  return Episode->SerializeActor(CarlaActor);
734  };
735 
736  BIND_SYNC(destroy_actor) << [this](cr::ActorId ActorId) -> R<bool>
737  {
739  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
740  if ( !CarlaActor )
741  {
742  RESPOND_ERROR("unable to destroy actor: not found");
743  }
744  UE_LOG(LogCarla, Log, TEXT("CarlaServer destroy_actor %d"), ActorId);
745  // We need to force the actor state change, since dormant actors
746  // will ignore the FCarlaActor destruction
747  CarlaActor->SetActorState(cr::ActorState::PendingKill);
749  {
750  RESPOND_ERROR("internal error: unable to destroy actor");
751  }
752  return true;
753  };
754 
755  BIND_SYNC(console_command) << [this](std::string cmd) -> R<bool>
756  {
758  APlayerController* PController= UGameplayStatics::GetPlayerController(Episode->GetWorld(), 0);
759  if( PController )
760  {
761  auto result = PController->ConsoleCommand(UTF8_TO_TCHAR(cmd.c_str()), true);
762  return !(
763  result.Contains(FString(TEXT("Command not recognized"))) ||
764  result.Contains(FString(TEXT("Error")))
765  );
766  }
767  return GEngine->Exec(Episode->GetWorld(), UTF8_TO_TCHAR(cmd.c_str()));
768  };
769 
770  BIND_SYNC(get_sensor_token) << [this](carla::streaming::detail::stream_id_type sensor_id) ->
772  {
774  bool ForceInPrimary = false;
775 
776  // check for the world observer (always in primary server)
777  if (sensor_id == 1)
778  {
779  ForceInPrimary = true;
780  }
781 
782  // collision sensor always in primary server in multi-gpu
783  FString Desc = Episode->GetActorDescriptionFromStream(sensor_id);
784  if (Desc == "" || Desc == "sensor.other.collision")
785  {
786  ForceInPrimary = true;
787  }
788 
789  if (SecondaryServer->HasClientsConnected() && !ForceInPrimary)
790  {
791  // multi-gpu
792  UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in secondary server"), sensor_id, *Desc);
793  return SecondaryServer->GetCommander().SendGetToken(sensor_id);
794  }
795  else
796  {
797  // single-gpu
798  UE_LOG(LogCarla, Log, TEXT("Sensor %d '%s' created in primary server"), sensor_id, *Desc);
799  return StreamingServer.GetToken(sensor_id);
800  }
801  };
802 
803  // ~~ Actor physics ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
804 
805  BIND_SYNC(set_actor_location) << [this](
808  {
810  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
811  if (!CarlaActor)
812  {
813  return RespondError(
814  "set_actor_location",
816  " Actor Id: " + FString::FromInt(ActorId));
817  }
818 
819  CarlaActor->SetActorGlobalLocation(
820  Location, ETeleportType::TeleportPhysics);
821  return R<void>::Success();
822  };
823 
824  BIND_SYNC(set_actor_transform) << [this](
827  {
829  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
830  if (!CarlaActor)
831  {
832  return RespondError(
833  "set_actor_transform",
835  " Actor Id: " + FString::FromInt(ActorId));
836  }
837 
838  CarlaActor->SetActorGlobalTransform(
839  Transform, ETeleportType::TeleportPhysics);
840  return R<void>::Success();
841  };
842 
843  BIND_SYNC(set_walker_state) << [this] (
846  float Speed) -> R<void>
847  {
849  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
850  if (!CarlaActor)
851  {
852  return RespondError(
853  "set_walker_state",
855  " Actor Id: " + FString::FromInt(ActorId));
856  }
857 
858  // apply walker transform
859  ECarlaServerResponse Response =
860  CarlaActor->SetWalkerState(
861  Transform,
862  cr::WalkerControl(
863  Transform.GetForwardVector(), Speed, false));
864  if (Response != ECarlaServerResponse::Success)
865  {
866  return RespondError(
867  "set_walker_state",
868  Response,
869  " Actor Id: " + FString::FromInt(ActorId));
870  }
871  return R<void>::Success();
872  };
873 
874  BIND_SYNC(set_actor_target_velocity) << [this](
876  cr::Vector3D vector) -> R<void>
877  {
879  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
880  if (!CarlaActor)
881  {
882  return RespondError(
883  "set_actor_target_velocity",
885  " Actor Id: " + FString::FromInt(ActorId));
886  }
887  ECarlaServerResponse Response =
888  CarlaActor->SetActorTargetVelocity(vector.ToCentimeters().ToFVector());
889  if (Response != ECarlaServerResponse::Success)
890  {
891  return RespondError(
892  "set_actor_target_velocity",
893  Response,
894  " Actor Id: " + FString::FromInt(ActorId));
895  }
896  return R<void>::Success();
897  };
898 
899  BIND_SYNC(set_actor_target_angular_velocity) << [this](
901  cr::Vector3D vector) -> R<void>
902  {
904  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
905  if (!CarlaActor)
906  {
907  return RespondError(
908  "set_actor_target_angular_velocity",
910  " Actor Id: " + FString::FromInt(ActorId));
911  }
912  ECarlaServerResponse Response =
913  CarlaActor->SetActorTargetAngularVelocity(vector.ToFVector());
914  if (Response != ECarlaServerResponse::Success)
915  {
916  return RespondError(
917  "set_actor_target_angular_velocity",
918  Response,
919  " Actor Id: " + FString::FromInt(ActorId));
920  }
921  return R<void>::Success();
922  };
923 
924  BIND_SYNC(enable_actor_constant_velocity) << [this](
926  cr::Vector3D vector) -> R<void>
927  {
929  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
930  if (!CarlaActor)
931  {
932  return RespondError(
933  "enable_actor_constant_velocity",
935  " Actor Id: " + FString::FromInt(ActorId));
936  }
937 
938  ECarlaServerResponse Response =
939  CarlaActor->EnableActorConstantVelocity(vector.ToCentimeters().ToFVector());
940  if (Response != ECarlaServerResponse::Success)
941  {
942  return RespondError(
943  "enable_actor_constant_velocity",
944  Response,
945  " Actor Id: " + FString::FromInt(ActorId));
946  }
947 
948  return R<void>::Success();
949  };
950 
951  BIND_SYNC(disable_actor_constant_velocity) << [this](
953  {
955  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
956  if (!CarlaActor)
957  {
958  return RespondError(
959  "disable_actor_constant_velocity",
961  " Actor Id: " + FString::FromInt(ActorId));
962  }
963 
964  ECarlaServerResponse Response =
965  CarlaActor->DisableActorConstantVelocity();
966  if (Response != ECarlaServerResponse::Success)
967  {
968  return RespondError(
969  "disable_actor_constant_velocity",
970  Response,
971  " Actor Id: " + FString::FromInt(ActorId));
972  }
973 
974  return R<void>::Success();
975  };
976 
977  BIND_SYNC(add_actor_impulse) << [this](
979  cr::Vector3D vector) -> R<void>
980  {
982  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
983  if (!CarlaActor)
984  {
985  return RespondError(
986  "add_actor_impulse",
988  " Actor Id: " + FString::FromInt(ActorId));
989  }
990 
991  ECarlaServerResponse Response =
992  CarlaActor->AddActorImpulse(vector.ToCentimeters().ToFVector());
993  if (Response != ECarlaServerResponse::Success)
994  {
995  return RespondError(
996  "add_actor_impulse",
997  Response,
998  " Actor Id: " + FString::FromInt(ActorId));
999  }
1000  return R<void>::Success();
1001  };
1002 
1003  BIND_SYNC(add_actor_impulse_at_location) << [this](
1005  cr::Vector3D impulse,
1006  cr::Vector3D location) -> R<void>
1007  {
1009  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1010  if (!CarlaActor)
1011  {
1012  return RespondError(
1013  "add_actor_impulse_at_location",
1015  " Actor Id: " + FString::FromInt(ActorId));
1016  }
1017  FVector UELocation = location.ToCentimeters().ToFVector();
1018  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1019  ALargeMapManager* LargeMap = GameMode->GetLMManager();
1020  if (LargeMap)
1021  {
1022  UELocation = LargeMap->GlobalToLocalLocation(UELocation);
1023  }
1024  ECarlaServerResponse Response =
1025  CarlaActor->AddActorImpulseAtLocation(impulse.ToCentimeters().ToFVector(), UELocation);
1026  if (Response != ECarlaServerResponse::Success)
1027  {
1028  return RespondError(
1029  "add_actor_impulse_at_location",
1030  Response,
1031  " Actor Id: " + FString::FromInt(ActorId));
1032  }
1033 
1034  return R<void>::Success();
1035  };
1036 
1037  BIND_SYNC(add_actor_force) << [this](
1039  cr::Vector3D vector) -> R<void>
1040  {
1042  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1043  if (!CarlaActor)
1044  {
1045  return RespondError(
1046  "add_actor_force",
1048  " Actor Id: " + FString::FromInt(ActorId));
1049  }
1050  ECarlaServerResponse Response =
1051  CarlaActor->AddActorForce(vector.ToCentimeters().ToFVector());
1052  if (Response != ECarlaServerResponse::Success)
1053  {
1054  return RespondError(
1055  "add_actor_force",
1056  Response,
1057  " Actor Id: " + FString::FromInt(ActorId));
1058  }
1059  return R<void>::Success();
1060  };
1061 
1062  BIND_SYNC(add_actor_force_at_location) << [this](
1064  cr::Vector3D force,
1065  cr::Vector3D location) -> R<void>
1066  {
1068  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1069  if (!CarlaActor)
1070  {
1071  return RespondError(
1072  "add_actor_force_at_location",
1074  " Actor Id: " + FString::FromInt(ActorId));
1075  }
1076  FVector UELocation = location.ToCentimeters().ToFVector();
1077  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1078  ALargeMapManager* LargeMap = GameMode->GetLMManager();
1079  if (LargeMap)
1080  {
1081  UELocation = LargeMap->GlobalToLocalLocation(UELocation);
1082  }
1083  ECarlaServerResponse Response =
1084  CarlaActor->AddActorForceAtLocation(UELocation, force.ToCentimeters().ToFVector());
1085  if (Response != ECarlaServerResponse::Success)
1086  {
1087  return RespondError(
1088  "add_actor_force_at_location",
1089  Response,
1090  " Actor Id: " + FString::FromInt(ActorId));
1091  }
1092  return R<void>::Success();
1093  };
1094 
1095  BIND_SYNC(add_actor_angular_impulse) << [this](
1097  cr::Vector3D vector) -> R<void>
1098  {
1100  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1101  if (!CarlaActor)
1102  {
1103  return RespondError(
1104  "add_actor_angular_impulse",
1106  " Actor Id: " + FString::FromInt(ActorId));
1107  }
1108  ECarlaServerResponse Response =
1109  CarlaActor->AddActorAngularImpulse(vector.ToFVector());
1110  if (Response != ECarlaServerResponse::Success)
1111  {
1112  return RespondError(
1113  "add_actor_angular_impulse",
1114  Response,
1115  " Actor Id: " + FString::FromInt(ActorId));
1116  }
1117  return R<void>::Success();
1118  };
1119 
1120  BIND_SYNC(add_actor_torque) << [this](
1122  cr::Vector3D vector) -> R<void>
1123  {
1125  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1126  if (!CarlaActor)
1127  {
1128  return RespondError(
1129  "add_actor_torque",
1131  " Actor Id: " + FString::FromInt(ActorId));
1132  }
1133  ECarlaServerResponse Response =
1134  CarlaActor->AddActorTorque(vector.ToFVector());
1135  if (Response != ECarlaServerResponse::Success)
1136  {
1137  return RespondError(
1138  "add_actor_torque",
1139  Response,
1140  " Actor Id: " + FString::FromInt(ActorId));
1141  }
1142  return R<void>::Success();
1143  };
1144 
1145  BIND_SYNC(get_physics_control) << [this](
1147  {
1149  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1150  if (!CarlaActor)
1151  {
1152  return RespondError(
1153  "get_physics_control",
1155  " Actor Id: " + FString::FromInt(ActorId));
1156  }
1158  ECarlaServerResponse Response =
1159  CarlaActor->GetPhysicsControl(PhysicsControl);
1160  if (Response != ECarlaServerResponse::Success)
1161  {
1162  return RespondError(
1163  "get_physics_control",
1164  Response,
1165  " Actor Id: " + FString::FromInt(ActorId));
1166  }
1167  return cr::VehiclePhysicsControl(PhysicsControl);
1168  };
1169 
1170  BIND_SYNC(get_vehicle_light_state) << [this](
1172  {
1174  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1175  if (!CarlaActor)
1176  {
1177  return RespondError(
1178  "get_vehicle_light_state",
1180  " Actor Id: " + FString::FromInt(ActorId));
1181  }
1182  FVehicleLightState LightState;
1183  ECarlaServerResponse Response =
1184  CarlaActor->GetVehicleLightState(LightState);
1185  if (Response != ECarlaServerResponse::Success)
1186  {
1187  return RespondError(
1188  "get_vehicle_light_state",
1189  Response,
1190  " Actor Id: " + FString::FromInt(ActorId));
1191  }
1192  return cr::VehicleLightState(LightState);
1193  };
1194 
1195  BIND_SYNC(apply_physics_control) << [this](
1197  cr::VehiclePhysicsControl PhysicsControl) -> R<void>
1198  {
1200  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1201  if (!CarlaActor)
1202  {
1203  return RespondError(
1204  "apply_physics_control",
1206  " Actor Id: " + FString::FromInt(ActorId));
1207  }
1208  ECarlaServerResponse Response =
1210  if (Response != ECarlaServerResponse::Success)
1211  {
1212  return RespondError(
1213  "apply_physics_control",
1214  Response,
1215  " Actor Id: " + FString::FromInt(ActorId));
1216  }
1217  return R<void>::Success();
1218  };
1219 
1220  BIND_SYNC(set_vehicle_light_state) << [this](
1222  cr::VehicleLightState LightState) -> R<void>
1223  {
1225  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1226  if (!CarlaActor)
1227  {
1228  return RespondError(
1229  "set_vehicle_light_state",
1231  " Actor Id: " + FString::FromInt(ActorId));
1232  }
1233  ECarlaServerResponse Response =
1234  CarlaActor->SetVehicleLightState(FVehicleLightState(LightState));
1235  if (Response != ECarlaServerResponse::Success)
1236  {
1237  return RespondError(
1238  "set_vehicle_light_state",
1239  Response,
1240  " Actor Id: " + FString::FromInt(ActorId));
1241  }
1242  return R<void>::Success();
1243  };
1244 
1245 
1246  BIND_SYNC(open_vehicle_door) << [this](
1248  cr::VehicleDoor DoorIdx) -> R<void>
1249  {
1251  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1252  if (!CarlaActor)
1253  {
1254  return RespondError(
1255  "open_vehicle_door",
1257  " Actor Id: " + FString::FromInt(ActorId));
1258  }
1259  ECarlaServerResponse Response =
1260  CarlaActor->OpenVehicleDoor(static_cast<EVehicleDoor>(DoorIdx));
1261  if (Response != ECarlaServerResponse::Success)
1262  {
1263  return RespondError(
1264  "open_vehicle_door",
1265  Response,
1266  " Actor Id: " + FString::FromInt(ActorId));
1267  }
1268  return R<void>::Success();
1269  };
1270 
1271  BIND_SYNC(close_vehicle_door) << [this](
1273  cr::VehicleDoor DoorIdx) -> R<void>
1274  {
1276  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1277  if (!CarlaActor)
1278  {
1279  return RespondError(
1280  "close_vehicle_door",
1282  " Actor Id: " + FString::FromInt(ActorId));
1283  }
1284  ECarlaServerResponse Response =
1285  CarlaActor->CloseVehicleDoor(static_cast<EVehicleDoor>(DoorIdx));
1286  if (Response != ECarlaServerResponse::Success)
1287  {
1288  return RespondError(
1289  "close_vehicle_door",
1290  Response,
1291  " Actor Id: " + FString::FromInt(ActorId));
1292  }
1293  return R<void>::Success();
1294  };
1295 
1296  BIND_SYNC(set_wheel_steer_direction) << [this](
1298  cr::VehicleWheelLocation WheelLocation,
1299  float AngleInDeg) -> R<void>
1300  {
1302  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1303  if(!CarlaActor){
1304  return RespondError(
1305  "set_wheel_steer_direction",
1307  " Actor Id: " + FString::FromInt(ActorId));
1308  }
1309  ECarlaServerResponse Response =
1310  CarlaActor->SetWheelSteerDirection(
1311  static_cast<EVehicleWheelLocation>(WheelLocation), AngleInDeg);
1312  if (Response != ECarlaServerResponse::Success)
1313  {
1314  return RespondError(
1315  "set_wheel_steer_direction",
1316  Response,
1317  " Actor Id: " + FString::FromInt(ActorId));
1318  }
1319  return R<void>::Success();
1320  };
1321 
1322  BIND_SYNC(get_wheel_steer_angle) << [this](
1323  const cr::ActorId ActorId,
1324  cr::VehicleWheelLocation WheelLocation) -> R<float>
1325  {
1327  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1328  if(!CarlaActor){
1329  return RespondError(
1330  "get_wheel_steer_angle",
1332  " Actor Id: " + FString::FromInt(ActorId));
1333  }
1334  float Angle;
1335  ECarlaServerResponse Response =
1336  CarlaActor->GetWheelSteerAngle(
1337  static_cast<EVehicleWheelLocation>(WheelLocation), Angle);
1338  if (Response != ECarlaServerResponse::Success)
1339  {
1340  return RespondError(
1341  "get_wheel_steer_angle",
1342  Response,
1343  " Actor Id: " + FString::FromInt(ActorId));
1344  }
1345  return Angle;
1346  };
1347 
1348  BIND_SYNC(set_actor_simulate_physics) << [this](
1350  bool bEnabled) -> R<void>
1351  {
1353  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1354  if (!CarlaActor)
1355  {
1356  return RespondError(
1357  "set_actor_simulate_physics",
1359  " Actor Id: " + FString::FromInt(ActorId));
1360  }
1361  ECarlaServerResponse Response =
1362  CarlaActor->SetActorSimulatePhysics(bEnabled);
1363  if (Response != ECarlaServerResponse::Success)
1364  {
1365  return RespondError(
1366  "set_actor_simulate_physics",
1367  Response,
1368  " Actor Id: " + FString::FromInt(ActorId));
1369  }
1370  return R<void>::Success();
1371  };
1372 
1373  BIND_SYNC(set_actor_enable_gravity) << [this](
1375  bool bEnabled) -> R<void>
1376  {
1378  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1379  if (!CarlaActor)
1380  {
1381  return RespondError(
1382  "set_actor_enable_gravity",
1384  " Actor Id: " + FString::FromInt(ActorId));
1385  }
1386  ECarlaServerResponse Response =
1387  CarlaActor->SetActorEnableGravity(bEnabled);
1388  if (Response != ECarlaServerResponse::Success)
1389  {
1390  return RespondError(
1391  "set_actor_enable_gravity",
1392  Response,
1393  " Actor Id: " + FString::FromInt(ActorId));
1394  }
1395  return R<void>::Success();
1396  };
1397 
1398  // ~~ Apply control ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1399 
1400  BIND_SYNC(apply_control_to_vehicle) << [this](
1402  cr::VehicleControl Control) -> R<void>
1403  {
1405  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1406  if (!CarlaActor)
1407  {
1408  return RespondError(
1409  "apply_control_to_vehicle",
1411  " Actor Id: " + FString::FromInt(ActorId));
1412  }
1413  ECarlaServerResponse Response =
1414  CarlaActor->ApplyControlToVehicle(Control, EVehicleInputPriority::Client);
1415  if (Response != ECarlaServerResponse::Success)
1416  {
1417  return RespondError(
1418  "apply_control_to_vehicle",
1419  Response,
1420  " Actor Id: " + FString::FromInt(ActorId));
1421  }
1422  return R<void>::Success();
1423  };
1424 
1425  BIND_SYNC(apply_ackermann_control_to_vehicle) << [this](
1427  cr::VehicleAckermannControl Control) -> R<void>
1428  {
1430  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1431  if (!CarlaActor)
1432  {
1433  return RespondError(
1434  "apply_ackermann_control_to_vehicle",
1436  " Actor Id: " + FString::FromInt(ActorId));
1437  }
1438  ECarlaServerResponse Response =
1439  CarlaActor->ApplyAckermannControlToVehicle(Control, EVehicleInputPriority::Client);
1440  if (Response != ECarlaServerResponse::Success)
1441  {
1442  return RespondError(
1443  "apply_ackermann_control_to_vehicle",
1444  Response,
1445  " Actor Id: " + FString::FromInt(ActorId));
1446  }
1447  return R<void>::Success();
1448  };
1449 
1450  BIND_SYNC(get_ackermann_controller_settings) << [this](
1452  {
1454  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1455  if (!CarlaActor)
1456  {
1457  return RespondError(
1458  "get_ackermann_controller_settings",
1460  " Actor Id: " + FString::FromInt(ActorId));
1461  }
1463  ECarlaServerResponse Response =
1464  CarlaActor->GetAckermannControllerSettings(Settings);
1465  if (Response != ECarlaServerResponse::Success)
1466  {
1467  return RespondError(
1468  "get_ackermann_controller_settings",
1469  Response,
1470  " Actor Id: " + FString::FromInt(ActorId));
1471  }
1472  return cr::AckermannControllerSettings(Settings);
1473  };
1474 
1475  BIND_SYNC(apply_ackermann_controller_settings) << [this](
1477  cr::AckermannControllerSettings AckermannSettings) -> R<void>
1478  {
1480  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1481  if (!CarlaActor)
1482  {
1483  return RespondError(
1484  "apply_ackermann_controller_settings",
1486  " Actor Id: " + FString::FromInt(ActorId));
1487  }
1488  ECarlaServerResponse Response =
1489  CarlaActor->ApplyAckermannControllerSettings(FAckermannControllerSettings(AckermannSettings));
1490  if (Response != ECarlaServerResponse::Success)
1491  {
1492  return RespondError(
1493  "apply_ackermann_controller_settings",
1494  Response,
1495  " Actor Id: " + FString::FromInt(ActorId));
1496  }
1497  return R<void>::Success();
1498  };
1499 
1500  BIND_SYNC(apply_control_to_walker) << [this](
1502  cr::WalkerControl Control) -> R<void>
1503  {
1505  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1506  if (!CarlaActor)
1507  {
1508  return RespondError(
1509  "apply_control_to_walker",
1511  " Actor Id: " + FString::FromInt(ActorId));
1512  }
1513  ECarlaServerResponse Response =
1514  CarlaActor->ApplyControlToWalker(Control);
1515  if (Response != ECarlaServerResponse::Success)
1516  {
1517  return RespondError(
1518  "apply_control_to_walker",
1519  Response,
1520  " Actor Id: " + FString::FromInt(ActorId));
1521  }
1522  return R<void>::Success();
1523  };
1524 
1525  BIND_SYNC(get_bones_transform) << [this](
1527  {
1529  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1530  if (!CarlaActor)
1531  {
1532  return RespondError(
1533  "get_bones_transform",
1535  " Actor Id: " + FString::FromInt(ActorId));
1536  }
1537  FWalkerBoneControlOut Bones;
1538  ECarlaServerResponse Response =
1539  CarlaActor->GetBonesTransform(Bones);
1540  if (Response != ECarlaServerResponse::Success)
1541  {
1542  return RespondError(
1543  "get_bones_transform",
1544  Response,
1545  " Actor Id: " + FString::FromInt(ActorId));
1546  }
1547 
1548  std::vector<carla::rpc::BoneTransformDataOut> BoneData;
1549  for (auto Bone : Bones.BoneTransforms)
1550  {
1552  Data.bone_name = std::string(TCHAR_TO_UTF8(*Bone.Get<0>()));
1553  FWalkerBoneControlOutData Transforms = Bone.Get<1>();
1554  Data.world = Transforms.World;
1555  Data.component = Transforms.Component;
1556  Data.relative = Transforms.Relative;
1557  BoneData.push_back(Data);
1558  }
1559  return carla::rpc::WalkerBoneControlOut(BoneData);
1560  };
1561 
1562  BIND_SYNC(set_bones_transform) << [this](
1565  {
1567  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1568  if (!CarlaActor)
1569  {
1570  return RespondError(
1571  "set_bones_transform",
1573  " Actor Id: " + FString::FromInt(ActorId));
1574  }
1575 
1577  ECarlaServerResponse Response = CarlaActor->SetBonesTransform(Bones2);
1578  if (Response != ECarlaServerResponse::Success)
1579  {
1580  return RespondError(
1581  "set_bones_transform",
1582  Response,
1583  " Actor Id: " + FString::FromInt(ActorId));
1584  }
1585 
1586  return R<void>::Success();
1587  };
1588 
1589  BIND_SYNC(blend_pose) << [this](
1591  float Blend) -> R<void>
1592  {
1594  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1595  if (!CarlaActor)
1596  {
1597  return RespondError(
1598  "blend_pose",
1600  " Actor Id: " + FString::FromInt(ActorId));
1601  }
1602 
1603  ECarlaServerResponse Response = CarlaActor->BlendPose(Blend);
1604  if (Response != ECarlaServerResponse::Success)
1605  {
1606  return RespondError(
1607  "blend_pose",
1608  Response,
1609  " Actor Id: " + FString::FromInt(ActorId));
1610  }
1611 
1612  return R<void>::Success();
1613  };
1614 
1615  BIND_SYNC(get_pose_from_animation) << [this](
1617  {
1619  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1620  if (!CarlaActor)
1621  {
1622  return RespondError(
1623  "get_pose_from_animation",
1625  " Actor Id: " + FString::FromInt(ActorId));
1626  }
1627 
1628  ECarlaServerResponse Response = CarlaActor->GetPoseFromAnimation();
1629  if (Response != ECarlaServerResponse::Success)
1630  {
1631  return RespondError(
1632  "get_pose_from_animation",
1633  Response,
1634  " Actor Id: " + FString::FromInt(ActorId));
1635  }
1636 
1637  return R<void>::Success();
1638  };
1639 
1640  BIND_SYNC(set_actor_autopilot) << [this](
1642  bool bEnabled) -> R<void>
1643  {
1645  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1646  if (!CarlaActor)
1647  {
1648  return RespondError(
1649  "set_actor_autopilot",
1651  " Actor Id: " + FString::FromInt(ActorId));
1652  }
1653  ECarlaServerResponse Response =
1654  CarlaActor->SetActorAutopilot(bEnabled);
1655  if (Response != ECarlaServerResponse::Success)
1656  {
1657  return RespondError(
1658  "set_actor_autopilot",
1659  Response,
1660  " Actor Id: " + FString::FromInt(ActorId));
1661  }
1662  return R<void>::Success();
1663  };
1664 
1665  BIND_SYNC(show_vehicle_debug_telemetry) << [this](
1667  bool bEnabled) -> R<void>
1668  {
1670  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1671  if (!CarlaActor)
1672  {
1673  return RespondError(
1674  "show_vehicle_debug_telemetry",
1676  " Actor Id: " + FString::FromInt(ActorId));
1677  }
1678  ECarlaServerResponse Response =
1679  CarlaActor->ShowVehicleDebugTelemetry(bEnabled);
1680  if (Response != ECarlaServerResponse::Success)
1681  {
1682  return RespondError(
1683  "show_vehicle_debug_telemetry",
1684  Response,
1685  " Actor Id: " + FString::FromInt(ActorId));
1686  }
1687  return R<void>::Success();
1688  };
1689 
1690  BIND_SYNC(enable_carsim) << [this](
1692  std::string SimfilePath) -> R<void>
1693  {
1695  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1696  if (!CarlaActor)
1697  {
1698  return RespondError(
1699  "enable_carsim",
1701  " Actor Id: " + FString::FromInt(ActorId));
1702  }
1703  ECarlaServerResponse Response =
1704  CarlaActor->EnableCarSim(carla::rpc::ToFString(SimfilePath));
1705  if (Response != ECarlaServerResponse::Success)
1706  {
1707  return RespondError(
1708  "enable_carsim",
1709  Response,
1710  " Actor Id: " + FString::FromInt(ActorId));
1711  }
1712  return R<void>::Success();
1713  };
1714 
1715  BIND_SYNC(use_carsim_road) << [this](
1717  bool bEnabled) -> R<void>
1718  {
1720  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1721  if (!CarlaActor)
1722  {
1723  return RespondError(
1724  "use_carsim_road",
1726  " Actor Id: " + FString::FromInt(ActorId));
1727  }
1728  ECarlaServerResponse Response =
1729  CarlaActor->UseCarSimRoad(bEnabled);
1730  if (Response != ECarlaServerResponse::Success)
1731  {
1732  return RespondError(
1733  "use_carsim_road",
1734  Response,
1735  " Actor Id: " + FString::FromInt(ActorId));
1736  }
1737  return R<void>::Success();
1738  };
1739 
1740  BIND_SYNC(enable_chrono_physics) << [this](
1742  uint64_t MaxSubsteps,
1743  float MaxSubstepDeltaTime,
1744  std::string VehicleJSON,
1745  std::string PowertrainJSON,
1746  std::string TireJSON,
1747  std::string BaseJSONPath) -> R<void>
1748  {
1750  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1751  if (!CarlaActor)
1752  {
1753  return RespondError(
1754  "enable_chrono_physics",
1756  " Actor Id: " + FString::FromInt(ActorId));
1757  }
1758  ECarlaServerResponse Response =
1759  CarlaActor->EnableChronoPhysics(
1760  MaxSubsteps, MaxSubstepDeltaTime,
1761  cr::ToFString(VehicleJSON),
1762  cr::ToFString(PowertrainJSON),
1763  cr::ToFString(TireJSON),
1764  cr::ToFString(BaseJSONPath));
1765  if (Response != ECarlaServerResponse::Success)
1766  {
1767  return RespondError(
1768  "enable_chrono_physics",
1769  Response,
1770  " Actor Id: " + FString::FromInt(ActorId));
1771  }
1772  return R<void>::Success();
1773  };
1774 
1775  // ~~ Traffic lights ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1776 
1777  BIND_SYNC(set_traffic_light_state) << [this](
1779  cr::TrafficLightState trafficLightState) -> R<void>
1780  {
1782  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1783  if (!CarlaActor)
1784  {
1785  return RespondError(
1786  "set_traffic_light_state",
1788  " Actor Id: " + FString::FromInt(ActorId));
1789  }
1790  ECarlaServerResponse Response =
1791  CarlaActor->SetTrafficLightState(
1792  static_cast<ETrafficLightState>(trafficLightState));
1793  if (Response != ECarlaServerResponse::Success)
1794  {
1795  return RespondError(
1796  "set_traffic_light_state",
1797  Response,
1798  " Actor Id: " + FString::FromInt(ActorId));
1799  }
1800  return R<void>::Success();
1801  };
1802 
1803  BIND_SYNC(set_traffic_light_green_time) << [this](
1805  float GreenTime) -> R<void>
1806  {
1808  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1809  if (!CarlaActor)
1810  {
1811  return RespondError(
1812  "set_traffic_light_green_time",
1814  " Actor Id: " + FString::FromInt(ActorId));
1815  }
1816  ECarlaServerResponse Response =
1817  CarlaActor->SetLightGreenTime(GreenTime);
1818  if (Response != ECarlaServerResponse::Success)
1819  {
1820  return RespondError(
1821  "set_traffic_light_green_time",
1822  Response,
1823  " Actor Id: " + FString::FromInt(ActorId));
1824  }
1825  return R<void>::Success();
1826  };
1827 
1828  BIND_SYNC(set_traffic_light_yellow_time) << [this](
1830  float YellowTime) -> R<void>
1831  {
1833  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1834  if (!CarlaActor)
1835  {
1836  return RespondError(
1837  "set_traffic_light_yellow_time",
1839  " Actor Id: " + FString::FromInt(ActorId));
1840  }
1841  ECarlaServerResponse Response =
1842  CarlaActor->SetLightYellowTime(YellowTime);
1843  if (Response != ECarlaServerResponse::Success)
1844  {
1845  return RespondError(
1846  "set_traffic_light_yellow_time",
1847  Response,
1848  " Actor Id: " + FString::FromInt(ActorId));
1849  }
1850  return R<void>::Success();
1851  };
1852 
1853  BIND_SYNC(set_traffic_light_red_time) << [this](
1855  float RedTime) -> R<void>
1856  {
1858  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1859  if (!CarlaActor)
1860  {
1861  return RespondError(
1862  "set_traffic_light_red_time",
1864  " Actor Id: " + FString::FromInt(ActorId));
1865  }
1866  ECarlaServerResponse Response =
1867  CarlaActor->SetLightRedTime(RedTime);
1868  if (Response != ECarlaServerResponse::Success)
1869  {
1870  return RespondError(
1871  "set_traffic_light_red_time",
1872  Response,
1873  " Actor Id: " + FString::FromInt(ActorId));
1874  }
1875  return R<void>::Success();
1876  };
1877 
1878  BIND_SYNC(freeze_traffic_light) << [this](
1880  bool Freeze) -> R<void>
1881  {
1883  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1884  if (!CarlaActor)
1885  {
1886  return RespondError(
1887  "freeze_traffic_light",
1889  " Actor Id: " + FString::FromInt(ActorId));
1890  }
1891  ECarlaServerResponse Response =
1892  CarlaActor->FreezeTrafficLight(Freeze);
1893  if (Response != ECarlaServerResponse::Success)
1894  {
1895  return RespondError(
1896  "freeze_traffic_light",
1897  Response,
1898  " Actor Id: " + FString::FromInt(ActorId));
1899  }
1900  return R<void>::Success();
1901  };
1902 
1903  BIND_SYNC(reset_traffic_light_group) << [this](
1905  {
1907  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1908  if (!CarlaActor)
1909  {
1910  return RespondError(
1911  "reset_traffic_light_group",
1913  " Actor Id: " + FString::FromInt(ActorId));
1914  }
1915  ECarlaServerResponse Response =
1916  CarlaActor->ResetTrafficLightGroup();
1917  if (Response != ECarlaServerResponse::Success)
1918  {
1919  return RespondError(
1920  "reset_traffic_light_group",
1921  Response,
1922  " Actor Id: " + FString::FromInt(ActorId));
1923  }
1924  return R<void>::Success();
1925  };
1926 
1927  BIND_SYNC(reset_all_traffic_lights) << [this]() -> R<void>
1928  {
1930  for (TActorIterator<ATrafficLightGroup> It(Episode->GetWorld()); It; ++It)
1931  {
1932  It->ResetGroup();
1933  }
1934  return R<void>::Success();
1935  };
1936 
1937  BIND_SYNC(freeze_all_traffic_lights) << [this]
1938  (bool frozen) -> R<void>
1939  {
1941  auto* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
1942  if (!GameMode)
1943  {
1944  RESPOND_ERROR("unable to find CARLA game mode");
1945  }
1946  auto* TraffiLightManager = GameMode->GetTrafficLightManager();
1947  TraffiLightManager->SetFrozen(frozen);
1948  return R<void>::Success();
1949  };
1950 
1951  BIND_SYNC(get_vehicle_light_states) << [this]() -> R<cr::VehicleLightStateList>
1952  {
1955 
1956  auto It = Episode->GetActorRegistry().begin();
1957  for (; It != Episode->GetActorRegistry().end(); ++It)
1958  {
1959  const FCarlaActor& View = *(It.Value().Get());
1961  {
1962  if(View.IsDormant())
1963  {
1964  // todo: implement
1965  }
1966  else
1967  {
1968  auto Actor = View.GetActor();
1969  if (!Actor->IsPendingKill())
1970  {
1971  const ACarlaWheeledVehicle *Vehicle = Cast<ACarlaWheeledVehicle>(Actor);
1972  List.emplace_back(
1973  View.GetActorId(),
1974  cr::VehicleLightState(Vehicle->GetVehicleLightState()).GetLightStateAsValue());
1975  }
1976  }
1977  }
1978  }
1979  return List;
1980  };
1981 
1982  BIND_SYNC(get_group_traffic_lights) << [this](
1983  const cr::ActorId ActorId) -> R<std::vector<cr::ActorId>>
1984  {
1986  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
1987  if (!CarlaActor)
1988  {
1989  RESPOND_ERROR("unable to get group traffic lights: actor not found");
1990  }
1991  if (CarlaActor->IsDormant())
1992  {
1993  //todo implement
1994  return std::vector<cr::ActorId>();
1995  }
1996  else
1997  {
1998  auto TrafficLight = Cast<ATrafficLightBase>(CarlaActor->GetActor());
1999  if (TrafficLight == nullptr)
2000  {
2001  RESPOND_ERROR("unable to get group traffic lights: actor is not a traffic light");
2002  }
2003  std::vector<cr::ActorId> Result;
2004  for (auto* TLight : TrafficLight->GetGroupTrafficLights())
2005  {
2006  auto* View = Episode->FindCarlaActor(TLight);
2007  if (View)
2008  {
2009  Result.push_back(View->GetActorId());
2010  }
2011  }
2012  return Result;
2013  }
2014  };
2015 
2016  BIND_SYNC(get_light_boxes) << [this](
2017  const cr::ActorId ActorId) -> R<std::vector<cg::BoundingBox>>
2018  {
2020  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2021  if (!CarlaActor)
2022  {
2023  return RespondError(
2024  "get_light_boxes",
2026  " Actor Id: " + FString::FromInt(ActorId));
2027  }
2028  if (CarlaActor->IsDormant())
2029  {
2030  return RespondError(
2031  "get_light_boxes",
2033  " Actor Id: " + FString::FromInt(ActorId));
2034  }
2035  else
2036  {
2037  ATrafficLightBase* TrafficLight = Cast<ATrafficLightBase>(CarlaActor->GetActor());
2038  if (!TrafficLight)
2039  {
2040  return RespondError(
2041  "get_light_boxes",
2043  " Actor Id: " + FString::FromInt(ActorId));
2044  }
2045  TArray<FBoundingBox> Result;
2046  TArray<uint8> OutTag;
2048  TrafficLight, Result, OutTag,
2049  static_cast<uint8>(carla::rpc::CityObjectLabel::TrafficLight));
2050  return MakeVectorFromTArray<cg::BoundingBox>(Result);
2051  }
2052  };
2053 
2054  // ~~ GBuffer tokens ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2055  BIND_SYNC(get_gbuffer_token) << [this](const cr::ActorId ActorId, uint32_t GBufferId) -> R<std::vector<unsigned char>>
2056  {
2058  FCarlaActor* CarlaActor = Episode->FindCarlaActor(ActorId);
2059  if(!CarlaActor)
2060  {
2061  return RespondError(
2062  "get_gbuffer_token",
2064  " Actor Id: " + FString::FromInt(ActorId));
2065  }
2066  if (CarlaActor->IsDormant())
2067  {
2068  return RespondError(
2069  "get_gbuffer_token",
2071  " Actor Id: " + FString::FromInt(ActorId));
2072  }
2073  ASceneCaptureSensor* Sensor = Cast<ASceneCaptureSensor>(CarlaActor->GetActor());
2074  if (!Sensor)
2075  {
2076  return RespondError(
2077  "get_gbuffer_token",
2079  " Actor Id: " + FString::FromInt(ActorId));
2080  }
2081 
2082  switch (GBufferId)
2083  {
2084  case 0:
2085  {
2086  const auto &Token = Sensor->CameraGBuffers.SceneColor.GetToken();
2087  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2088  }
2089  case 1:
2090  {
2091  const auto &Token = Sensor->CameraGBuffers.SceneDepth.GetToken();
2092  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2093  }
2094  case 2:
2095  {
2096  const auto& Token = Sensor->CameraGBuffers.SceneStencil.GetToken();
2097  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2098  }
2099  case 3:
2100  {
2101  const auto &Token = Sensor->CameraGBuffers.GBufferA.GetToken();
2102  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2103  }
2104  case 4:
2105  {
2106  const auto &Token = Sensor->CameraGBuffers.GBufferB.GetToken();
2107  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2108  }
2109  case 5:
2110  {
2111  const auto &Token = Sensor->CameraGBuffers.GBufferC.GetToken();
2112  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2113  }
2114  case 6:
2115  {
2116  const auto &Token = Sensor->CameraGBuffers.GBufferD.GetToken();
2117  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2118  }
2119  case 7:
2120  {
2121  const auto &Token = Sensor->CameraGBuffers.GBufferE.GetToken();
2122  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2123  }
2124  case 8:
2125  {
2126  const auto &Token = Sensor->CameraGBuffers.GBufferF.GetToken();
2127  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2128  }
2129  case 9:
2130  {
2131  const auto &Token = Sensor->CameraGBuffers.Velocity.GetToken();
2132  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2133  }
2134  case 10:
2135  {
2136  const auto &Token = Sensor->CameraGBuffers.SSAO.GetToken();
2137  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2138  }
2139  case 11:
2140  {
2141  const auto& Token = Sensor->CameraGBuffers.CustomDepth.GetToken();
2142  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2143  }
2144  case 12:
2145  {
2146  const auto& Token = Sensor->CameraGBuffers.CustomStencil.GetToken();
2147  return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2148  }
2149  default:
2150  UE_LOG(LogCarla, Error, TEXT("Requested invalid GBuffer ID %u"), GBufferId);
2151  return {};
2152  }
2153  };
2154 
2155  // ~~ Logging and playback ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2156 
2157  BIND_SYNC(start_recorder) << [this](std::string name, bool AdditionalData) -> R<std::string>
2158  {
2160  return R<std::string>(Episode->StartRecorder(name, AdditionalData));
2161  };
2162 
2163  BIND_SYNC(stop_recorder) << [this]() -> R<void>
2164  {
2166  Episode->GetRecorder()->Stop();
2167  return R<void>::Success();
2168  };
2169 
2170  BIND_SYNC(show_recorder_file_info) << [this](
2171  std::string name,
2172  bool show_all) -> R<std::string>
2173  {
2176  name,
2177  show_all));
2178  };
2179 
2180  BIND_SYNC(show_recorder_collisions) << [this](
2181  std::string name,
2182  char type1,
2183  char type2) -> R<std::string>
2184  {
2187  name,
2188  type1,
2189  type2));
2190  };
2191 
2192  BIND_SYNC(show_recorder_actors_blocked) << [this](
2193  std::string name,
2194  double min_time,
2195  double min_distance) -> R<std::string>
2196  {
2199  name,
2200  min_time,
2201  min_distance));
2202  };
2203 
2204  BIND_SYNC(replay_file) << [this](
2205  std::string name,
2206  double start,
2207  double duration,
2208  uint32_t follow_id,
2209  bool replay_sensors) -> R<std::string>
2210  {
2213  name,
2214  start,
2215  duration,
2216  follow_id,
2217  replay_sensors));
2218  };
2219 
2220  BIND_SYNC(set_replayer_time_factor) << [this](double time_factor) -> R<void>
2221  {
2223  Episode->GetRecorder()->SetReplayerTimeFactor(time_factor);
2224  return R<void>::Success();
2225  };
2226 
2227  BIND_SYNC(set_replayer_ignore_hero) << [this](bool ignore_hero) -> R<void>
2228  {
2230  Episode->GetRecorder()->SetReplayerIgnoreHero(ignore_hero);
2231  return R<void>::Success();
2232  };
2233 
2234  BIND_SYNC(stop_replayer) << [this](bool keep_actors) -> R<void>
2235  {
2237  Episode->GetRecorder()->StopReplayer(keep_actors);
2238  return R<void>::Success();
2239  };
2240 
2241  // ~~ Draw debug shapes ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2242 
2243  BIND_SYNC(draw_debug_shape) << [this](const cr::DebugShape &shape) -> R<void>
2244  {
2246  auto *World = Episode->GetWorld();
2247  check(World != nullptr);
2248  FDebugShapeDrawer Drawer(*World);
2249  Drawer.Draw(shape);
2250  return R<void>::Success();
2251  };
2252 
2253  // ~~ Apply commands in batch ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2254 
2255  using C = cr::Command;
2256  using CR = cr::CommandResponse;
2257  using ActorId = carla::ActorId;
2258 
2259  auto parse_result = [](ActorId id, const auto &response) {
2260  return response.HasError() ? CR{response.GetError()} : CR{id};
2261  };
2262 
2263 #define MAKE_RESULT(operation) return parse_result(c.actor, operation);
2264 
2265  auto command_visitor = carla::Functional::MakeRecursiveOverload(
2266  [=](auto self, const C::SpawnActor &c) -> CR {
2267  auto result = c.parent.has_value() ?
2268  spawn_actor_with_parent(
2269  c.description,
2270  c.transform,
2271  *c.parent,
2272  cr::AttachmentType::Rigid) :
2273  spawn_actor(c.description, c.transform);
2274  if (!result.HasError())
2275  {
2276  ActorId id = result.Get().id;
2277  auto set_id = carla::Functional::MakeOverload(
2278  [](C::SpawnActor &) {},
2279  [](C::ConsoleCommand &) {},
2280  [id](auto &s) { s.actor = id; });
2281  for (auto command : c.do_after)
2282  {
2283  boost::variant2::visit(set_id, command.command);
2284  boost::variant2::visit(self, command.command);
2285  }
2286  return id;
2287  }
2288  return result.GetError();
2289  },
2290  [=](auto, const C::DestroyActor &c) { MAKE_RESULT(destroy_actor(c.actor)); },
2291  [=](auto, const C::ApplyVehicleControl &c) { MAKE_RESULT(apply_control_to_vehicle(c.actor, c.control)); },
2292  [=](auto, const C::ApplyVehicleAckermannControl &c) { MAKE_RESULT(apply_ackermann_control_to_vehicle(c.actor, c.control)); },
2293  [=](auto, const C::ApplyWalkerControl &c) { MAKE_RESULT(apply_control_to_walker(c.actor, c.control)); },
2294  [=](auto, const C::ApplyVehiclePhysicsControl &c) { MAKE_RESULT(apply_physics_control(c.actor, c.physics_control)); },
2295  [=](auto, const C::ApplyTransform &c) { MAKE_RESULT(set_actor_transform(c.actor, c.transform)); },
2296  [=](auto, const C::ApplyTargetVelocity &c) { MAKE_RESULT(set_actor_target_velocity(c.actor, c.velocity)); },
2297  [=](auto, const C::ApplyTargetAngularVelocity &c) { MAKE_RESULT(set_actor_target_angular_velocity(c.actor, c.angular_velocity)); },
2298  [=](auto, const C::ApplyImpulse &c) { MAKE_RESULT(add_actor_impulse(c.actor, c.impulse)); },
2299  [=](auto, const C::ApplyForce &c) { MAKE_RESULT(add_actor_force(c.actor, c.force)); },
2300  [=](auto, const C::ApplyAngularImpulse &c) { MAKE_RESULT(add_actor_angular_impulse(c.actor, c.impulse)); },
2301  [=](auto, const C::ApplyTorque &c) { MAKE_RESULT(add_actor_torque(c.actor, c.torque)); },
2302  [=](auto, const C::SetSimulatePhysics &c) { MAKE_RESULT(set_actor_simulate_physics(c.actor, c.enabled)); },
2303  [=](auto, const C::SetEnableGravity &c) { MAKE_RESULT(set_actor_enable_gravity(c.actor, c.enabled)); },
2304  // TODO: SetAutopilot should be removed. This is the old way to control the vehicles
2305  [=](auto, const C::SetAutopilot &c) { MAKE_RESULT(set_actor_autopilot(c.actor, c.enabled)); },
2306  [=](auto, const C::ShowDebugTelemetry &c) { MAKE_RESULT(show_vehicle_debug_telemetry(c.actor, c.enabled)); },
2307  [=](auto, const C::SetVehicleLightState &c) { MAKE_RESULT(set_vehicle_light_state(c.actor, c.light_state)); },
2308 // [=](auto, const C::OpenVehicleDoor &c) { MAKE_RESULT(open_vehicle_door(c.actor, c.door_idx)); },
2309 // [=](auto, const C::CloseVehicleDoor &c) { MAKE_RESULT(close_vehicle_door(c.actor, c.door_idx)); },
2310  [=](auto, const C::ApplyWalkerState &c) { MAKE_RESULT(set_walker_state(c.actor, c.transform, c.speed)); },
2311  [=](auto, const C::ConsoleCommand& c) -> CR { return console_command(c.cmd); },
2312  [=](auto, const C::SetTrafficLightState& c) { MAKE_RESULT(set_traffic_light_state(c.actor, c.traffic_light_state)); },
2313  [=](auto, const C::ApplyLocation& c) { MAKE_RESULT(set_actor_location(c.actor, c.location)); }
2314  );
2315 
2316 #undef MAKE_RESULT
2317 
2318  BIND_SYNC(apply_batch) << [=](
2319  const std::vector<cr::Command> &commands,
2320  bool do_tick_cue)
2321  {
2322  std::vector<CR> result;
2323  result.reserve(commands.size());
2324  for (const auto &command : commands)
2325  {
2326  result.emplace_back(boost::variant2::visit(command_visitor, command.command));
2327  }
2328  if (do_tick_cue)
2329  {
2330  tick_cue();
2331  }
2332  return result;
2333  };
2334 
2335  // ~~ Light Subsystem ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2336 
2337  BIND_SYNC(query_lights_state) << [this](std::string client) -> R<std::vector<cr::LightState>>
2338  {
2340  std::vector<cr::LightState> result;
2341  auto *World = Episode->GetWorld();
2342  if(World) {
2343  UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
2344  result = CarlaLightSubsystem->GetLights(FString(client.c_str()));
2345  }
2346  return result;
2347  };
2348 
2349  BIND_SYNC(update_lights_state) << [this]
2350  (std::string client, const std::vector<cr::LightState>& lights, bool discard_client) -> R<void>
2351  {
2353  auto *World = Episode->GetWorld();
2354  if(World) {
2355  UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
2356  CarlaLightSubsystem->SetLights(FString(client.c_str()), lights, discard_client);
2357  }
2358  return R<void>::Success();
2359  };
2360 
2361  BIND_SYNC(update_day_night_cycle) << [this]
2362  (std::string client, const bool active) -> R<void>
2363  {
2365  auto *World = Episode->GetWorld();
2366  if(World) {
2367  UCarlaLightSubsystem* CarlaLightSubsystem = World->GetSubsystem<UCarlaLightSubsystem>();
2368  CarlaLightSubsystem->SetDayNightCycle(active);
2369  }
2370  return R<void>::Success();
2371  };
2372 
2373 
2374  // ~~ Ray Casting ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2375 
2376  BIND_SYNC(project_point) << [this]
2377  (cr::Location Location, cr::Vector3D Direction, float SearchDistance)
2378  -> R<std::pair<bool,cr::LabelledPoint>>
2379  {
2381  auto *World = Episode->GetWorld();
2382  constexpr float meter_to_centimeter = 100.0f;
2383  FVector UELocation = Location;
2384  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
2385  ALargeMapManager* LargeMap = GameMode->GetLMManager();
2386  if (LargeMap)
2387  {
2388  UELocation = LargeMap->GlobalToLocalLocation(UELocation);
2389  }
2390  return URayTracer::ProjectPoint(UELocation, Direction.ToFVector(),
2391  meter_to_centimeter * SearchDistance, World);
2392  };
2393 
2394  BIND_SYNC(cast_ray) << [this]
2395  (cr::Location StartLocation, cr::Location EndLocation)
2396  -> R<std::vector<cr::LabelledPoint>>
2397  {
2399  auto *World = Episode->GetWorld();
2400  FVector UEStartLocation = StartLocation;
2401  FVector UEEndLocation = EndLocation;
2402  ACarlaGameModeBase* GameMode = UCarlaStatics::GetGameMode(Episode->GetWorld());
2403  ALargeMapManager* LargeMap = GameMode->GetLMManager();
2404  if (LargeMap)
2405  {
2406  UEStartLocation = LargeMap->GlobalToLocalLocation(UEStartLocation);
2407  UEEndLocation = LargeMap->GlobalToLocalLocation(UEEndLocation);
2408  }
2409  return URayTracer::CastRay(StartLocation, EndLocation, World);
2410  };
2411 
2412 }
2413 
2414 // =============================================================================
2415 // -- Undef helper macros ------------------------------------------------------
2416 // =============================================================================
2417 
2418 #undef BIND_ASYNC
2419 #undef BIND_SYNC
2420 #undef REQUIRE_CARLA_EPISODE
2421 #undef RESPOND_ERROR_FSTRING
2422 #undef RESPOND_ERROR
2423 #undef CARLA_ENSURE_GAME_THREAD
2424 
2425 // =============================================================================
2426 // -- FCarlaServer -------------------------------------------------------
2427 // =============================================================================
2428 
2430 
2432  Stop();
2433 }
2434 
2435 FDataMultiStream FCarlaServer::Start(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
2436 {
2437  Pimpl = MakeUnique<FPimpl>(RPCPort, StreamingPort, SecondaryPort);
2438  StreamingPort = Pimpl->StreamingServer.GetLocalEndpoint().port();
2439  SecondaryPort = Pimpl->SecondaryServer->GetLocalEndpoint().port();
2440 
2441  UE_LOG(
2442  LogCarlaServer,
2443  Log,
2444  TEXT("Initialized CarlaServer: Ports(rpc=%d, streaming=%d, secondary=%d)"),
2445  RPCPort,
2446  StreamingPort,
2447  SecondaryPort);
2448  return Pimpl->BroadcastStream;
2449 }
2450 
2452 {
2453  check(Pimpl != nullptr);
2454  UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName());
2455  Pimpl->Episode = &Episode;
2456 }
2457 
2459 {
2460  check(Pimpl != nullptr);
2461  Pimpl->Episode = nullptr;
2462 }
2463 
2464 void FCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads)
2465 {
2466  check(Pimpl != nullptr);
2467  /// @todo Define better the number of threads each server gets.
2468  int ThreadsPerServer = std::max(2u, NumberOfWorkerThreads / 3u);
2469  int32_t RPCThreads;
2470  int32_t StreamingThreads;
2471  int32_t SecondaryThreads;
2472 
2473  UE_LOG(LogCarla, Log, TEXT("FCommandLine %s"), FCommandLine::Get());
2474 
2475  if(!FParse::Value(FCommandLine::Get(), TEXT("-RPCThreads="), RPCThreads))
2476  {
2477  RPCThreads = ThreadsPerServer;
2478  }
2479  if(!FParse::Value(FCommandLine::Get(), TEXT("-StreamingThreads="), StreamingThreads))
2480  {
2481  StreamingThreads = ThreadsPerServer;
2482  }
2483  if(!FParse::Value(FCommandLine::Get(), TEXT("-SecondaryThreads="), SecondaryThreads))
2484  {
2485  SecondaryThreads = ThreadsPerServer;
2486  }
2487 
2488  UE_LOG(LogCarla, Log, TEXT("FCarlaServer AsyncRun %d, RPCThreads %d, StreamingThreads %d, SecondaryThreads %d"),
2489  NumberOfWorkerThreads, RPCThreads, StreamingThreads, SecondaryThreads);
2490 
2491  Pimpl->Server.AsyncRun(RPCThreads);
2492  Pimpl->StreamingServer.AsyncRun(StreamingThreads);
2493  Pimpl->SecondaryServer->AsyncRun(SecondaryThreads);
2494 }
2495 
2496 void FCarlaServer::RunSome(uint32 Milliseconds)
2497 {
2498  TRACE_CPUPROFILER_EVENT_SCOPE_STR(__FUNCTION__);
2499  Pimpl->Server.SyncRunFor(carla::time_duration::milliseconds(Milliseconds));
2500 }
2501 
2503 {
2504  (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release);
2505 }
2506 
2508 {
2509  auto k = Pimpl->TickCuesReceived.fetch_sub(1, std::memory_order_acquire);
2510  bool flag = (k > 0);
2511  if (!flag)
2512  (void)Pimpl->TickCuesReceived.fetch_add(1, std::memory_order_release);
2513  return flag;
2514 }
2515 
2517 {
2518  if (Pimpl)
2519  {
2520  Pimpl->Server.Stop();
2521  Pimpl->SecondaryServer->Stop();
2522  }
2523 }
2524 
2526 {
2527  check(Pimpl != nullptr);
2528  return Pimpl->StreamingServer.MakeStream();
2529 }
2530 
2531 std::shared_ptr<carla::multigpu::Router> FCarlaServer::GetSecondaryServer()
2532 {
2533  return Pimpl->GetSecondaryServer();
2534 }
2535 
2537 {
2538  return Pimpl->StreamingServer;
2539 }
carla::streaming::Stream BroadcastStream
FCarlaActor * FindCarlaActor(FCarlaActor::IdType ActorId)
Find a Carla actor by id.
Definition: CarlaEpisode.h:172
carla::streaming::Server & GetStreamingServer()
virtual ECarlaServerResponse SetVehicleLightState(const FVehicleLightState &)
Definition: CarlaActor.h:271
TArray< FEnvironmentObject > GetEnvironmentObjects(uint8 QueriedTag=0xFF) const
void ApplyTextureToActor(AActor *Actor, UTexture2D *Texture, const carla::rpc::MaterialParameter &TextureParam)
FDataStream OpenStream() const
FCameraGBufferUint8 GBufferF
auto end() const noexcept
std::vector< carla::rpc::LightState > GetLights(FString Client)
FPimpl(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
Definition: CarlaServer.cpp:96
static FString StatusToString(EActorSpawnResultStatus Status)
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.
void StopReplayer(bool KeepActors=false)
bool DestroyActor(AActor *Actor)
Definition: CarlaEpisode.h:251
const char * _name
FCameraGBufferUint8 SceneDepth
virtual ECarlaServerResponse SetWheelSteerDirection(const EVehicleWheelLocation &, float)
Definition: CarlaActor.h:276
AWeather * GetWeather() const
Definition: CarlaEpisode.h:149
std::string ShowFileCollisions(std::string Name, char Type1, char Type2)
void SetDayNightCycle(const bool active)
void SetMapLayer(int32 MapLayer)
auto operator<<(FuncT func)
carla::streaming::detail::token_type GetToken(carla::streaming::detail::stream_id_type sensor_id)
virtual ECarlaServerResponse SetActorEnableGravity(bool bEnabled)
Definition: CarlaActor.cpp:581
AActor * GetActor()
Definition: CarlaActor.h:90
FVector GlobalToLocalLocation(const FVector &InLocation) const
FString GetStringError(ECarlaServerResponse Response)
carla::rpc::ResponseError RespondError(const FString &FuncName, const FString &ErrorMessage, const FString &ExtraInfo="")
EAttachmentType
Definition: ActorAttacher.h:20
virtual ECarlaServerResponse SetBonesTransform(const FWalkerBoneControlIn &)
Definition: CarlaActor.h:401
The game instance contains elements that must be kept alive in between levels.
static TArray< uint8 > Load(FString MapName)
Return the Navigation Mesh Binary associated to MapName, or empty if the such file wasn&#39;t serialized...
#define MAKE_RESULT(operation)
FCameraGBufferUint8 CustomStencil
rpc::ActorId ActorId
Definition: ActorId.h:18
FCameraGBufferUint8 SceneStencil
static auto MakeRecursiveOverload(FuncTs &&... fs)
Definition: Functional.h:33
auto begin() const noexcept
carla::rpc::Actor SerializeActor(FCarlaActor *CarlaActor) const
Create a serializable object describing the actor.
void SetReplayerTimeFactor(double TimeFactor)
virtual ECarlaServerResponse DisableActorConstantVelocity()
Definition: CarlaActor.h:236
FDataMultiStream Start(uint16_t RPCPort, uint16_t StreamingPort, uint16_t SecondaryPort)
std::string ShowFileActorsBlocked(std::string Name, double MinTime=30, double MinDistance=10)
A streaming server.
std::vector< std::pair< ActorId, VehicleLightState::flag_type > > VehicleLightStateList
TArray< FTransform > GetRecommendedSpawnPoints() const
Return the list of recommended spawn points for vehicles.
#define RESPOND_ERROR_FSTRING(fstr)
std::map< uint16_t, std::string > TrafficManagerInfo
Map of pairs < port , ip > with all the Traffic Managers active in the simulation.
auto GetToken() const
Return the token that allows subscribing to this sensor&#39;s stream.
void EnableEnvironmentObjects(const TSet< uint64 > &EnvObjectIds, bool Enable)
static TArray< FString > GetAllMapNames()
FCameraGBufferUint8 GBufferE
virtual ECarlaServerResponse BlendPose(float Blend)
Definition: CarlaActor.h:406
void PutActorToSleep(carla::rpc::ActorId ActorId)
Definition: CarlaEpisode.h:279
virtual ECarlaServerResponse GetPhysicsControl(FVehiclePhysicsControl &)
Definition: CarlaActor.h:241
virtual ECarlaServerResponse ApplyAckermannControllerSettings(const FAckermannControllerSettings &)
Definition: CarlaActor.h:313
void UnLoadMapLayer(int32 MapLayers)
void OnActorSpawned(const FCarlaActor &CarlaActor)
uint32_t stream_id_type
Definition: Types.h:18
virtual ECarlaServerResponse ApplyControlToVehicle(const FVehicleControl &, const EVehicleInputPriority &)
Definition: CarlaActor.h:286
AActor * FindActorByName(const FString &ActorName)
UTexture2D * CreateUETexture(const carla::rpc::TextureColor &Texture)
static T Get(carla::rpc::Response< T > &response)
bg::model::box< Point3D > Box
Definition: InMemoryMap.h:45
virtual ECarlaServerResponse SetTrafficLightState(const ETrafficLightState &)
Definition: CarlaActor.h:346
void NotifyEndEpisode()
static ACarlaGameModeBase * GetGameMode(const UObject *WorldContextObject)
Definition: CarlaStatics.h:58
static void GetTrafficLightBoundingBox(const ATrafficLightBase *TrafficLight, TArray< FBoundingBox > &OutBB, TArray< uint8 > &OutTag, uint8 InTagQueried=0xFF)
geom::Vector3D Vector3D
Definition: rpc/Vector3D.h:14
const FString & GetMapName() const
Return the name of the map loaded in this episode.
Definition: CarlaEpisode.h:92
std::atomic_size_t TickCuesReceived
static uint64_t GetFrameCounter()
Definition: CarlaEngine.h:64
#define BIND_ASYNC(name)
virtual ECarlaServerResponse EnableChronoPhysics(uint64_t, float, const FString &, const FString &, const FString &, const FString &)
Definition: CarlaActor.h:338
geom::Location Location
Definition: rpc/Location.h:14
void SetActorGlobalLocation(const FVector &Location, ETeleportType Teleport=ETeleportType::TeleportPhysics)
Definition: CarlaActor.cpp:281
void Draw(const carla::rpc::DebugShape &Shape)
ECarlaServerResponse AddActorImpulse(const FVector &Impulse)
Definition: CarlaActor.cpp:431
#define BIND_SYNC(name)
ECarlaServerResponse SetActorTargetAngularVelocity(const FVector &AngularVelocity)
Definition: CarlaActor.cpp:410
void LoadMapLayer(int32 MapLayers)
void RunSome(uint32 Milliseconds)
const FActorRegistry & GetActorRegistry() const
Definition: CarlaEpisode.h:154
virtual ECarlaServerResponse CloseVehicleDoor(const EVehicleDoor)
Definition: CarlaActor.h:261
std::string StartRecorder(std::string name, bool AdditionalData)
ECarlaServerResponse AddActorForceAtLocation(const FVector &Force, const FVector &Location)
Definition: CarlaActor.cpp:495
ECarlaServerResponse AddActorTorque(const FVector &Torque)
Definition: CarlaActor.cpp:539
static UCarlaGameInstance * GetGameInstance(const UObject *WorldContextObject)
Definition: CarlaStatics.h:63
ECarlaServerResponse
carla::SharedPtr< cc::Actor > Actor
virtual ECarlaServerResponse FreezeTrafficLight(bool)
Definition: CarlaActor.h:416
virtual ECarlaServerResponse EnableActorConstantVelocity(const FVector &)
Definition: CarlaActor.h:231
A simulation episode.
Definition: CarlaEpisode.h:37
std::shared_ptr< carla::multigpu::Router > SecondaryServer
An RPC server in which functions can be bind to run synchronously or asynchronously.
Definition: rpc/Server.h:37
virtual ECarlaServerResponse GetPoseFromAnimation()
Definition: CarlaActor.h:411
FCameraGBufferUint8 GBufferD
std::string ReplayFile(std::string Name, double TimeStart, double Duration, uint32_t FollowId, bool ReplaySensors)
FCameraGBufferUint8 SSAO
TPair< EActorSpawnResultStatus, FCarlaActor * > SpawnActorWithInfo(const FTransform &Transform, FActorDescription thisActorDescription, FCarlaActor::IdType DesiredId=0)
Spawns an actor based on ActorDescription at Transform.
FCameraGBufferUint8 GBufferA
void SetActorState(carla::rpc::ActorState InState)
Definition: CarlaActor.h:110
Response< ActorId > CommandResponse
virtual ECarlaServerResponse ResetTrafficLightGroup()
Definition: CarlaActor.h:421
void SetAttachmentType(carla::rpc::AttachmentType InAttachmentType)
Definition: CarlaActor.h:140
bool LoadNewEpisode(const FString &MapString, bool ResetSettings=true)
Load a new map and start a new episode.
const TArray< FActorDefinition > & GetActorDefinitions() const
Return the list of actor definitions that are available to be spawned this episode.
Definition: CarlaEpisode.h:123
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
virtual ECarlaServerResponse GetBonesTransform(FWalkerBoneControlOut &)
Definition: CarlaActor.h:396
#define RESPOND_ERROR(str)
virtual ECarlaServerResponse ApplyControlToWalker(const FWalkerControl &)
Definition: CarlaActor.h:386
static std::vector< T > MakeVectorFromTArray(const TArray< Other > &Array)
Definition: CarlaServer.cpp:83
Token token() const
Token associated with this stream.
Definition: detail/Stream.h:35
FCameraGBufferUint8 SceneColor
auto GetId() const
Return the unique id of this episode.
Definition: CarlaEpisode.h:85
std::shared_ptr< carla::multigpu::Router > GetSecondaryServer()
void SetLights(FString Client, std::vector< carla::rpc::LightState > LightsToSet, bool DiscardClient=false)
void SetReplayerIgnoreHero(bool IgnoreHero)
constexpr size_t milliseconds() const noexcept
Definition: Time.h:58
virtual ECarlaServerResponse SetLightGreenTime(float)
Definition: CarlaActor.h:361
TArray< FString > GetNamesOfAllActors()
static FString GetXODR(const UWorld *World)
Return the OpenDrive XML associated to MapName, or empty if the file is not found.
uint32_t ActorId
Definition: ActorId.h:14
FCameraGBufferUint8 CustomDepth
bool TickCueReceived()
ACarlaRecorder * GetRecorder() const
Definition: CarlaEpisode.h:304
virtual ECarlaServerResponse SetLightYellowTime(float)
Definition: CarlaActor.h:366
carla::rpc::Server Server
virtual ECarlaServerResponse SetLightRedTime(float)
Definition: CarlaActor.h:371
ALargeMapManager * GetLMManager() const
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
Base class for sensors using a USceneCaptureComponent2D for rendering the scene.
virtual ECarlaServerResponse SetActorAutopilot(bool, bool bKeepState=false)
Definition: CarlaActor.h:318
FString GetActorDescriptionFromStream(carla::streaming::detail::stream_id_type StreamId)
Get the description of the Carla actor (sensor) using specific stream id.
Definition: CarlaEpisode.h:189
carla::rpc::Server & _server
ECarlaServerResponse SetActorTargetVelocity(const FVector &Velocity)
Definition: CarlaActor.cpp:389
virtual ECarlaServerResponse OpenVehicleDoor(const EVehicleDoor)
Definition: CarlaActor.h:256
virtual ECarlaServerResponse EnableCarSim(const FString &)
Definition: CarlaActor.h:328
FTransform LocalToGlobalTransform(const FTransform &InTransform) const
TUniquePtr< FPimpl > Pimpl
Definition: CarlaServer.h:53
APawn * GetSpectatorPawn() const
Definition: CarlaEpisode.h:143
void AttachActors(AActor *Child, AActor *Parent, EAttachmentType InAttachmentType=EAttachmentType::Rigid)
Attach Child to Parent.
void AddChildren(IdType ChildId)
Definition: CarlaActor.h:125
virtual ECarlaServerResponse UseCarSimRoad(bool)
Definition: CarlaActor.h:333
static std::pair< bool, carla::rpc::LabelledPoint > ProjectPoint(FVector StartLocation, FVector Direction, float MaxDistance, UWorld *World)
Definition: RayTracer.cpp:46
std::string ShowFileInfo(std::string Name, bool bShowAll=false)
static ALargeMapManager * GetLargeMapManager(const UObject *WorldContextObject)
Definition: CarlaStatics.h:100
carla::streaming::Server StreamingServer
ECarlaServerResponse AddActorImpulseAtLocation(const FVector &Impulse, const FVector &Location)
Definition: CarlaActor.cpp:451
TArray< FBoundingBox > GetAllBBsOfLevel(uint8 TagQueried=0xFF) const
FCameraGBufferUint8 GBufferC
FCameraGBufferUint8 Velocity
bool IsDormant() const
Definition: CarlaActor.h:70
Base class for the CARLA Game Mode.
virtual ECarlaServerResponse SetActorSimulatePhysics(bool bEnabled)
Definition: CarlaActor.cpp:559
virtual ECarlaServerResponse GetVehicleLightState(FVehicleLightState &)
Definition: CarlaActor.h:251
const FEpisodeSettings & GetSettings() const
Definition: CarlaEpisode.h:72
void SetParent(IdType InParentId)
Definition: CarlaActor.h:115
IdType GetActorId() const
Definition: CarlaActor.h:80
virtual ECarlaServerResponse ApplyAckermannControlToVehicle(const FVehicleAckermannControl &, const EVehicleInputPriority &)
Definition: CarlaActor.h:292
ECarlaServerResponse AddActorForce(const FVector &Force)
Definition: CarlaActor.cpp:475
UCarlaEpisode * Episode
Texture< sensor::data::Color > TextureColor
Definition: Texture.h:66
virtual ECarlaServerResponse ApplyPhysicsControl(const FVehiclePhysicsControl &)
Definition: CarlaActor.h:266
const FString GetFullMapPath() const
Base class for CARLA wheeled vehicles.
virtual ECarlaServerResponse GetWheelSteerAngle(const EVehicleWheelLocation &, float &)
Definition: CarlaActor.h:281
struct ASceneCaptureSensor::@0 CameraGBuffers
Texture< FloatColor > TextureFloatColor
Definition: Texture.h:67
void AsyncRun(uint32 NumberOfWorkerThreads)
virtual ECarlaServerResponse GetAckermannControllerSettings(FAckermannControllerSettings &)
Definition: CarlaActor.h:308
void SetActorGlobalTransform(const FTransform &Transform, ETeleportType Teleport=ETeleportType::TeleportPhysics)
Definition: CarlaActor.cpp:332
FCameraGBufferUint8 GBufferB
ECarlaServerResponse AddActorAngularImpulse(const FVector &AngularInpulse)
Definition: CarlaActor.cpp:519
#define REQUIRE_CARLA_EPISODE()
geom::Transform Transform
Definition: rpc/Transform.h:16
FVector LocalToGlobalLocation(const FVector &InLocation) const
constexpr ServerBinder(const char *name, carla::rpc::Server &srv, bool sync)
virtual ECarlaServerResponse ShowVehicleDebugTelemetry(bool)
Definition: CarlaActor.h:323
virtual ECarlaServerResponse SetWalkerState(const FTransform &Transform, carla::rpc::WalkerControl WalkerControl)
Definition: CarlaActor.h:379
ActorType GetActorType() const
Definition: CarlaActor.h:85
A view over an actor and its properties.
Definition: CarlaActor.h:23
FVehicleLightState GetVehicleLightState() const
void ApplySettings(const FEpisodeSettings &Settings)
void SetSynchronousMode(bool is_synchro)
static std::vector< carla::rpc::LabelledPoint > CastRay(FVector StartLocation, FVector EndLocation, UWorld *World)
Definition: RayTracer.cpp:15
void NotifyBeginEpisode(UCarlaEpisode &Episode)