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