233 BIND_SYNC(get_traffic_manager_running) << [
this] (uint16_t port) ->
R<std::pair<std::string, uint16_t>>
237 return std::pair<std::string, uint16_t>(it->second, it->first);
239 return std::pair<std::string, uint16_t>(
"",0);
243 BIND_SYNC(add_traffic_manager_running) << [
this] (std::pair<std::string, uint16_t> trafficManagerInfo) ->
R<bool>
245 uint16_t port = trafficManagerInfo.second;
249 std::pair<uint16_t, std::string>(port, trafficManagerInfo.first));
268 return carla::version();
283 BIND_ASYNC(get_available_maps) << [
this]() ->
R<std::vector<std::string>>
286 std::vector<std::string> result;
287 result.reserve(MapNames.Num());
288 for (
const auto &MapName : MapNames)
290 if (MapName.Contains(
"/Sublevels/"))
292 if (MapName.Contains(
"/BaseMap/"))
294 if (MapName.Contains(
"/BaseLargeMap/"))
296 if (MapName.Contains(
"_Tile_"))
299 result.emplace_back(cr::FromFString(MapName));
304 BIND_SYNC(load_new_episode) << [
this](
const std::string &map_name,
const bool reset_settings, cr::MapLayer MapLayers) ->
R<void>
313 GameInstance->
SetMapLayer(
static_cast<int32
>(MapLayers));
317 FString Str(TEXT(
"Map '"));
318 Str += cr::ToFString(map_name);
319 Str += TEXT(
"' not found");
354 BIND_SYNC(copy_opendrive_to_file) << [
this](
const std::string &opendrive, cr::OpendriveGenerationParameters Params) ->
R<void>
364 BIND_SYNC(apply_color_texture_to_objects) << [
this](
365 const std::vector<std::string> &actors_name,
366 const cr::MaterialParameter& parameter,
367 const cr::TextureColor& Texture) ->
R<void>
375 TArray<AActor*> ActorsToPaint;
376 for(
const std::string& actor_name : actors_name)
381 ActorsToPaint.Add(ActorToPaint);
385 if(!ActorsToPaint.Num())
392 for(
AActor* ActorToPaint : ActorsToPaint)
402 BIND_SYNC(apply_float_color_texture_to_objects) << [
this](
403 const std::vector<std::string> &actors_name,
404 const cr::MaterialParameter& parameter,
405 const cr::TextureFloatColor& Texture) ->
R<void>
413 TArray<AActor*> ActorsToPaint;
414 for(
const std::string& actor_name : actors_name)
419 ActorsToPaint.Add(ActorToPaint);
423 if(!ActorsToPaint.Num())
430 for(
AActor* ActorToPaint : ActorsToPaint)
440 BIND_SYNC(get_names_of_all_objects) << [
this]() ->
R<std::vector<std::string>>
449 std::vector<std::string> NamesStd;
450 for (
const FString &Name : NamesFString)
452 NamesStd.emplace_back(cr::FromFString(Name));
471 FString MapDir = FullMapPath.RightChop(FullMapPath.Find(
"Content/", ESearchCase::CaseSensitive) + 8);
474 cr::FromFString(MapDir),
475 MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
484 BIND_SYNC(get_navigation_mesh) << [
this]() ->
R<std::vector<uint8_t>>
489 std::vector<uint8_t> Result(FileContents.Num());
490 memcpy(&Result[0], FileContents.GetData(), FileContents.Num());
494 BIND_SYNC(get_required_files) << [
this](std::string folder =
"") ->
R<std::vector<std::string>>
499 if (folder[folder.size() - 1] !=
'/' && folder[folder.size() - 1] !=
'\\') {
506 const auto folderDir = mapDir +
"/" + folder.c_str();
510 TArray<FString> Files;
511 IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName +
".xodr"),
true,
false,
false);
512 IFileManager::Get().FindFilesRecursive(Files, *folderDir, *(fileName +
".bin"),
true,
false,
false);
515 std::vector<std::string> result;
516 for (
auto File : Files) {
517 File.RemoveFromStart(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
518 result.emplace_back(TCHAR_TO_UTF8(*File));
523 BIND_SYNC(request_file) << [
this](std::string name) ->
R<std::vector<uint8_t>>
528 FString path(FPaths::ConvertRelativePathToFull(FPaths::ProjectContentDir()));
529 path.Append(name.c_str());
532 TArray<uint8_t> Content;
533 FFileHelper::LoadFileToArray(Content, *path, 0);
534 std::vector<uint8_t> Result(Content.Num());
535 memcpy(&Result[0], Content.GetData(), Content.Num());
546 BIND_SYNC(set_episode_settings) << [
this](
547 const cr::EpisodeSettings &settings) ->
R<uint64_t>
567 BIND_SYNC(get_actor_definitions) << [
this]() ->
R<std::vector<cr::ActorDefinition>>
584 BIND_SYNC(get_all_level_BBs) << [
this](uint8 QueriedTag) ->
R<std::vector<cg::BoundingBox>>
587 TArray<FBoundingBox> Result;
597 for(
auto& Box : Result)
602 return MakeVectorFromTArray<cg::BoundingBox>(Result);
605 BIND_SYNC(get_environment_objects) << [
this](uint8 QueriedTag) ->
R<std::vector<cr::EnvironmentObject>>
617 for(
auto& Object : Result)
622 return MakeVectorFromTArray<cr::EnvironmentObject>(Result);
625 BIND_SYNC(enable_environment_objects) << [
this](std::vector<uint64_t> EnvObjectIds,
bool Enable) ->
R<void>
634 TSet<uint64> EnvObjectIdsSet;
635 for(uint64 Id : EnvObjectIds)
637 EnvObjectIdsSet.Emplace(Id);
650 if (Weather ==
nullptr)
654 return Weather->GetCurrentWeather();
657 BIND_SYNC(set_weather_parameters) << [
this](
658 const cr::WeatherParameters &weather) ->
R<void>
662 if (Weather ==
nullptr)
666 Weather->ApplyWeather(weather);
676 if (GameMode ==
nullptr)
678 RESPOND_ERROR(
"get_imui_gravity error: unable to get carla gamemode");
687 if (GameMode ==
nullptr)
689 RESPOND_ERROR(
"get_imui_gravity error: unable to get carla gamemode");
698 const std::vector<FCarlaActor::IdType> &ids) ->
R<std::vector<cr::Actor>>
701 std::vector<cr::Actor> Result;
702 Result.reserve(ids.size());
703 for (
auto &&Id : ids)
715 cr::ActorDescription Description,
722 if (Result.Key != EActorSpawnResultStatus::Success)
724 UE_LOG(LogCarla, Error, TEXT(
"Actor not Spawned"));
737 BIND_SYNC(spawn_actor_with_parent) << [
this](
738 cr::ActorDescription Description,
739 const cr::Transform &Transform,
740 cr::ActorId ParentId,
741 cr::AttachmentType InAttachmentType,
747 if (Result.Key != EActorSpawnResultStatus::Success)
760 if (!ParentCarlaActor)
762 RESPOND_ERROR(
"unable to attach actor: parent actor not found");
769 #if defined(WITH_ROS2)
771 if (ROS2->IsEnabled())
778 if (Attr.Key ==
"ros_name")
780 const std::string value = std::string(TCHAR_TO_UTF8(*Attr.Value.Value));
781 ROS2->AddActorParentRosName(
static_cast<void*
>(CarlaActor->
GetActor()),
static_cast<void*
>(CurrentActor->
GetActor()));
797 FString(socket_name.c_str()));
815 UE_LOG(LogCarla, Log, TEXT(
"CarlaServer destroy_actor %d"), ActorId);
829 APlayerController* PController= UGameplayStatics::GetPlayerController(
Episode->GetWorld(), 0);
832 auto result = PController->ConsoleCommand(UTF8_TO_TCHAR(cmd.c_str()),
true);
834 result.Contains(FString(TEXT(
"Command not recognized"))) ||
835 result.Contains(FString(TEXT(
"Error")))
838 return GEngine->Exec(
Episode->GetWorld(), UTF8_TO_TCHAR(cmd.c_str()));
845 bool ForceInPrimary =
false;
850 ForceInPrimary =
true;
855 if (Desc ==
"" || Desc ==
"sensor.other.collision")
857 ForceInPrimary =
true;
863 UE_LOG(LogCarla, Log, TEXT(
"Sensor %d '%s' created in secondary server"), sensor_id, *Desc);
869 UE_LOG(LogCarla, Log, TEXT(
"Sensor %d '%s' created in primary server"), sensor_id, *Desc);
878 bool ForceInPrimary =
false;
883 ForceInPrimary =
true;
888 if (Desc ==
"" || Desc ==
"sensor.other.collision")
890 ForceInPrimary =
true;
910 bool ForceInPrimary =
false;
915 ForceInPrimary =
true;
920 if (Desc ==
"" || Desc ==
"sensor.other.collision")
922 ForceInPrimary =
true;
942 bool ForceInPrimary =
false;
947 ForceInPrimary =
true;
952 if (Desc ==
"" || Desc ==
"sensor.other.collision")
954 ForceInPrimary =
true;
972 std::string message) ->
R<void>
981 " Actor Id: " + FString::FromInt(ActorId));
989 " Actor Id: " + FString::FromInt(ActorId));
997 " Actor Id: " + FString::FromInt(ActorId));
1000 Sensor->
Send(cr::ToFString(message));
1006 BIND_SYNC(set_actor_location) << [
this](
1007 cr::ActorId ActorId,
1008 cr::Location Location) ->
R<void>
1015 "set_actor_location",
1017 " Actor Id: " + FString::FromInt(ActorId));
1021 Location, ETeleportType::TeleportPhysics);
1025 BIND_SYNC(set_actor_transform) << [
this](
1026 cr::ActorId ActorId,
1027 cr::Transform Transform) ->
R<void>
1034 "set_actor_transform",
1036 " Actor Id: " + FString::FromInt(ActorId));
1040 Transform, ETeleportType::TeleportPhysics);
1045 cr::ActorId ActorId,
1046 cr::Transform Transform,
1056 " Actor Id: " + FString::FromInt(ActorId));
1070 " Actor Id: " + FString::FromInt(ActorId));
1075 BIND_SYNC(set_actor_target_velocity) << [
this](
1076 cr::ActorId ActorId,
1077 cr::Vector3D vector) ->
R<void>
1084 "set_actor_target_velocity",
1086 " Actor Id: " + FString::FromInt(ActorId));
1093 "set_actor_target_velocity",
1095 " Actor Id: " + FString::FromInt(ActorId));
1100 BIND_SYNC(set_actor_target_angular_velocity) << [
this](
1101 cr::ActorId ActorId,
1102 cr::Vector3D vector) ->
R<void>
1109 "set_actor_target_angular_velocity",
1111 " Actor Id: " + FString::FromInt(ActorId));
1118 "set_actor_target_angular_velocity",
1120 " Actor Id: " + FString::FromInt(ActorId));
1125 BIND_SYNC(enable_actor_constant_velocity) << [
this](
1126 cr::ActorId ActorId,
1127 cr::Vector3D vector) ->
R<void>
1134 "enable_actor_constant_velocity",
1136 " Actor Id: " + FString::FromInt(ActorId));
1144 "enable_actor_constant_velocity",
1146 " Actor Id: " + FString::FromInt(ActorId));
1152 BIND_SYNC(disable_actor_constant_velocity) << [
this](
1153 cr::ActorId ActorId) ->
R<void>
1160 "disable_actor_constant_velocity",
1162 " Actor Id: " + FString::FromInt(ActorId));
1170 "disable_actor_constant_velocity",
1172 " Actor Id: " + FString::FromInt(ActorId));
1179 cr::ActorId ActorId,
1180 cr::Vector3D vector) ->
R<void>
1187 "add_actor_impulse",
1189 " Actor Id: " + FString::FromInt(ActorId));
1197 "add_actor_impulse",
1199 " Actor Id: " + FString::FromInt(ActorId));
1204 BIND_SYNC(add_actor_impulse_at_location) << [
this](
1205 cr::ActorId ActorId,
1206 cr::Vector3D impulse,
1207 cr::Vector3D location) ->
R<void>
1214 "add_actor_impulse_at_location",
1216 " Actor Id: " + FString::FromInt(ActorId));
1218 FVector UELocation = location.ToCentimeters().ToFVector();
1230 "add_actor_impulse_at_location",
1232 " Actor Id: " + FString::FromInt(ActorId));
1239 cr::ActorId ActorId,
1240 cr::Vector3D vector) ->
R<void>
1249 " Actor Id: " + FString::FromInt(ActorId));
1252 CarlaActor->
AddActorForce(vector.ToCentimeters().ToFVector());
1258 " Actor Id: " + FString::FromInt(ActorId));
1263 BIND_SYNC(add_actor_force_at_location) << [
this](
1264 cr::ActorId ActorId,
1266 cr::Vector3D location) ->
R<void>
1273 "add_actor_force_at_location",
1275 " Actor Id: " + FString::FromInt(ActorId));
1277 FVector UELocation = location.ToCentimeters().ToFVector();
1289 "add_actor_force_at_location",
1291 " Actor Id: " + FString::FromInt(ActorId));
1296 BIND_SYNC(add_actor_angular_impulse) << [
this](
1297 cr::ActorId ActorId,
1298 cr::Vector3D vector) ->
R<void>
1305 "add_actor_angular_impulse",
1307 " Actor Id: " + FString::FromInt(ActorId));
1314 "add_actor_angular_impulse",
1316 " Actor Id: " + FString::FromInt(ActorId));
1322 cr::ActorId ActorId,
1323 cr::Vector3D vector) ->
R<void>
1332 " Actor Id: " + FString::FromInt(ActorId));
1341 " Actor Id: " + FString::FromInt(ActorId));
1346 BIND_SYNC(get_actor_component_world_transform) << [
this](
1347 cr::ActorId ActorId,
1355 "get_actor_component_world_transform",
1357 " Actor Id: " + FString::FromInt(ActorId));
1361 TArray<UActorComponent*> Components;
1362 CarlaActor->
GetActor()->GetComponents(Components);
1364 USceneComponent* Component =
nullptr;
1365 for(
auto Cmp : Components)
1367 if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
1369 if(SCMP->GetName() == componentName.c_str())
1380 "get_actor_component_world_transform",
1382 " Component Name: " + FString(componentName.c_str()));
1385 FTransform ComponentWorldTransform = Component->GetComponentTransform();
1386 return cr::Transform(ComponentWorldTransform);
1390 BIND_SYNC(get_actor_component_relative_transform) << [
this](
1391 cr::ActorId ActorId,
1399 "get_actor_component_relative_transform",
1401 " Actor Id: " + FString::FromInt(ActorId));
1405 TArray<UActorComponent*> Components;
1406 CarlaActor->
GetActor()->GetComponents(Components);
1408 USceneComponent* Component =
nullptr;
1409 for(
auto Cmp : Components)
1411 if(USceneComponent* SCMP = Cast<USceneComponent>(Cmp))
1413 if(SCMP->GetName() == componentName.c_str())
1424 "get_actor_component_world_transform",
1426 " Component Name: " + FString(componentName.c_str()));
1429 FTransform ComponentRelativeTransform = Component->GetRelativeTransform();
1430 return cr::Transform(ComponentRelativeTransform);
1434 BIND_SYNC(get_actor_bone_world_transforms) << [
this](
1435 cr::ActorId ActorId) ->
R<std::vector<cr::Transform>>
1442 "get_actor_bone_world_transforms",
1444 " Actor Id: " + FString::FromInt(ActorId));
1448 TArray<FTransform> BoneWorldTransforms;
1449 TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
1450 CarlaActor->
GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
1451 if(!SkinnedMeshComponents[0])
1454 "get_actor_bone_world_transforms",
1456 " Component Name: SkinnedMeshComponent ");
1460 for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
1462 const int32 NumBones = SkinnedMeshComponent->GetNumBones();
1463 for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
1465 FTransform WorldTransform = SkinnedMeshComponent->GetComponentTransform();
1466 FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, WorldTransform);
1467 BoneWorldTransforms.Add(BoneTransform);
1470 return MakeVectorFromTArray<cr::Transform>(BoneWorldTransforms);
1475 BIND_SYNC(get_actor_bone_relative_transforms) << [
this](
1476 cr::ActorId ActorId) ->
R<std::vector<cr::Transform>>
1483 "get_actor_bone_relative_transforms",
1485 " Actor Id: " + FString::FromInt(ActorId));
1489 TArray<FTransform> BoneRelativeTransforms;
1490 TArray<USkinnedMeshComponent*> SkinnedMeshComponents;
1491 CarlaActor->
GetActor()->GetComponents<USkinnedMeshComponent>(SkinnedMeshComponents);
1492 if(!SkinnedMeshComponents[0])
1495 "get_actor_bone_relative_transforms",
1497 " Component Name: SkinnedMeshComponent ");
1501 for(USkinnedMeshComponent* SkinnedMeshComponent : SkinnedMeshComponents)
1503 const int32 NumBones = SkinnedMeshComponent->GetNumBones();
1504 for (int32 BoneIndex = 0; BoneIndex < NumBones; ++BoneIndex)
1506 FTransform BoneTransform = SkinnedMeshComponent->GetBoneTransform(BoneIndex, FTransform::Identity);
1507 BoneRelativeTransforms.Add(BoneTransform);
1510 return MakeVectorFromTArray<cr::Transform>(BoneRelativeTransforms);
1515 BIND_SYNC(get_actor_component_names) << [
this](
1516 cr::ActorId ActorId) ->
R<std::vector<std::string>>
1523 "get_actor_component_names",
1525 " Actor Id: " + FString::FromInt(ActorId));
1529 TArray<UActorComponent*> Components;
1530 CarlaActor->
GetActor()->GetComponents(Components);
1531 std::vector<std::string> ComponentNames;
1532 for(
auto Cmp : Components)
1534 FString ComponentName = Cmp->GetName();
1535 ComponentNames.push_back(TCHAR_TO_UTF8(*ComponentName));
1537 return ComponentNames;
1541 BIND_SYNC(get_actor_bone_names) << [
this](
1542 cr::ActorId ActorId) ->
R<std::vector<std::string>>
1549 "get_actor_bone_names",
1551 " Actor Id: " + FString::FromInt(ActorId));
1555 USkinnedMeshComponent* SkinnedMeshComponent = CarlaActor->
GetActor()->FindComponentByClass<USkinnedMeshComponent>();
1556 if(!SkinnedMeshComponent)
1559 "get_actor_bone_names",
1561 " Component Name: SkinnedMeshComponent ");
1565 TArray<FName> BoneNames;
1566 SkinnedMeshComponent->GetBoneNames(BoneNames);
1567 TArray<std::string> StringBoneNames;
1568 for (
const FName& Name : BoneNames)
1570 FString FBoneName = Name.ToString();
1571 std::string StringBoneName = TCHAR_TO_UTF8(*FBoneName);
1572 StringBoneNames.Add(StringBoneName);
1574 return MakeVectorFromTArray<std::string>(StringBoneNames);
1579 BIND_SYNC(get_actor_socket_world_transforms) << [
this](
1580 cr::ActorId ActorId) ->
R<std::vector<cr::Transform>>
1587 "get_actor_socket_world_transforms",
1589 " Actor Id: " + FString::FromInt(ActorId));
1593 TArray<FTransform> SocketWorldTransforms;
1594 TArray<UActorComponent*> Components;
1595 CarlaActor->
GetActor()->GetComponents(Components);
1596 for(UActorComponent* ActorComponent : Components)
1598 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1600 const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
1601 for (
const FName& SocketName : SocketNames)
1603 FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName);
1604 SocketWorldTransforms.Add(SocketTransform);
1608 return MakeVectorFromTArray<cr::Transform>(SocketWorldTransforms);
1612 BIND_SYNC(get_actor_socket_relative_transforms) << [
this](
1613 cr::ActorId ActorId) ->
R<std::vector<cr::Transform>>
1620 "get_actor_socket_relative_transforms",
1622 " Actor Id: " + FString::FromInt(ActorId));
1626 TArray<FTransform> SocketRelativeTransforms;
1627 TArray<UActorComponent*> Components;
1628 CarlaActor->
GetActor()->GetComponents(Components);
1629 for(UActorComponent* ActorComponent : Components)
1631 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1633 const TArray<FName>& SocketNames = SceneComponent->GetAllSocketNames();
1634 for (
const FName& SocketName : SocketNames)
1636 FTransform SocketTransform = SceneComponent->GetSocketTransform(SocketName, ERelativeTransformSpace::RTS_Actor);
1637 SocketRelativeTransforms.Add(SocketTransform);
1641 return MakeVectorFromTArray<cr::Transform>(SocketRelativeTransforms);
1645 BIND_SYNC(get_actor_socket_names) << [
this](
1646 cr::ActorId ActorId) ->
R<std::vector<std::string>>
1653 "get_actor_socket_names",
1655 " Actor Id: " + FString::FromInt(ActorId));
1659 TArray<FName> SocketNames;
1660 std::vector<std::string> StringSocketNames;
1661 TArray<UActorComponent*> Components;
1662 CarlaActor->
GetActor()->GetComponents(Components);
1663 for(UActorComponent* ActorComponent : Components)
1665 if(USceneComponent* SceneComponent = Cast<USceneComponent>(ActorComponent))
1667 SocketNames = SceneComponent->GetAllSocketNames();
1668 for (
const FName& Name : SocketNames)
1670 FString FSocketName = Name.ToString();
1671 std::string StringSocketName = TCHAR_TO_UTF8(*FSocketName);
1672 StringSocketNames.push_back(StringSocketName);
1676 return StringSocketNames;
1680 BIND_SYNC(get_physics_control) << [
this](
1688 "get_physics_control",
1690 " Actor Id: " + FString::FromInt(ActorId));
1698 "get_physics_control",
1700 " Actor Id: " + FString::FromInt(ActorId));
1705 BIND_SYNC(get_vehicle_light_state) << [
this](
1713 "get_vehicle_light_state",
1715 " Actor Id: " + FString::FromInt(ActorId));
1723 "get_vehicle_light_state",
1725 " Actor Id: " + FString::FromInt(ActorId));
1727 return cr::VehicleLightState(LightState);
1730 BIND_SYNC(apply_physics_control) << [
this](
1731 cr::ActorId ActorId,
1739 "apply_physics_control",
1741 " Actor Id: " + FString::FromInt(ActorId));
1748 "apply_physics_control",
1750 " Actor Id: " + FString::FromInt(ActorId));
1755 BIND_SYNC(set_vehicle_light_state) << [
this](
1756 cr::ActorId ActorId,
1757 cr::VehicleLightState LightState) ->
R<void>
1764 "set_vehicle_light_state",
1766 " Actor Id: " + FString::FromInt(ActorId));
1773 "set_vehicle_light_state",
1775 " Actor Id: " + FString::FromInt(ActorId));
1782 cr::ActorId ActorId,
1783 cr::VehicleDoor DoorIdx) ->
R<void>
1790 "open_vehicle_door",
1792 " Actor Id: " + FString::FromInt(ActorId));
1799 "open_vehicle_door",
1801 " Actor Id: " + FString::FromInt(ActorId));
1806 BIND_SYNC(close_vehicle_door) << [
this](
1807 cr::ActorId ActorId,
1808 cr::VehicleDoor DoorIdx) ->
R<void>
1815 "close_vehicle_door",
1817 " Actor Id: " + FString::FromInt(ActorId));
1824 "close_vehicle_door",
1826 " Actor Id: " + FString::FromInt(ActorId));
1831 BIND_SYNC(set_wheel_steer_direction) << [
this](
1832 cr::ActorId ActorId,
1833 cr::VehicleWheelLocation WheelLocation,
1840 "set_wheel_steer_direction",
1842 " Actor Id: " + FString::FromInt(ActorId));
1850 "set_wheel_steer_direction",
1852 " Actor Id: " + FString::FromInt(ActorId));
1857 BIND_SYNC(get_wheel_steer_angle) << [
this](
1858 const cr::ActorId ActorId,
1859 cr::VehicleWheelLocation WheelLocation) ->
R<float>
1865 "get_wheel_steer_angle",
1867 " Actor Id: " + FString::FromInt(ActorId));
1876 "get_wheel_steer_angle",
1878 " Actor Id: " + FString::FromInt(ActorId));
1883 BIND_SYNC(set_actor_simulate_physics) << [
this](
1884 cr::ActorId ActorId,
1892 "set_actor_simulate_physics",
1894 " Actor Id: " + FString::FromInt(ActorId));
1901 "set_actor_simulate_physics",
1903 " Actor Id: " + FString::FromInt(ActorId));
1908 BIND_SYNC(set_actor_collisions) << [
this](
1909 cr::ActorId ActorId,
1917 "set_actor_collisions",
1919 " Actor Id: " + FString::FromInt(ActorId));
1926 "set_actor_collisions",
1928 " Actor Id: " + FString::FromInt(ActorId));
1934 cr::ActorId ActorId) ->
R<void>
1943 " Actor Id: " + FString::FromInt(ActorId));
1952 " Actor Id: " + FString::FromInt(ActorId));
1957 BIND_SYNC(set_actor_enable_gravity) << [
this](
1958 cr::ActorId ActorId,
1966 "set_actor_enable_gravity",
1968 " Actor Id: " + FString::FromInt(ActorId));
1975 "set_actor_enable_gravity",
1977 " Actor Id: " + FString::FromInt(ActorId));
1984 BIND_SYNC(apply_control_to_vehicle) << [
this](
1985 cr::ActorId ActorId,
1986 cr::VehicleControl Control) ->
R<void>
1993 "apply_control_to_vehicle",
1995 " Actor Id: " + FString::FromInt(ActorId));
2002 "apply_control_to_vehicle",
2004 " Actor Id: " + FString::FromInt(ActorId));
2009 BIND_SYNC(apply_ackermann_control_to_vehicle) << [
this](
2010 cr::ActorId ActorId,
2011 cr::VehicleAckermannControl Control) ->
R<void>
2018 "apply_ackermann_control_to_vehicle",
2020 " Actor Id: " + FString::FromInt(ActorId));
2027 "apply_ackermann_control_to_vehicle",
2029 " Actor Id: " + FString::FromInt(ActorId));
2034 BIND_SYNC(get_ackermann_controller_settings) << [
this](
2042 "get_ackermann_controller_settings",
2044 " Actor Id: " + FString::FromInt(ActorId));
2052 "get_ackermann_controller_settings",
2054 " Actor Id: " + FString::FromInt(ActorId));
2056 return cr::AckermannControllerSettings(Settings);
2059 BIND_SYNC(apply_ackermann_controller_settings) << [
this](
2060 cr::ActorId ActorId,
2061 cr::AckermannControllerSettings AckermannSettings) ->
R<void>
2068 "apply_ackermann_controller_settings",
2070 " Actor Id: " + FString::FromInt(ActorId));
2077 "apply_ackermann_controller_settings",
2079 " Actor Id: " + FString::FromInt(ActorId));
2084 BIND_SYNC(apply_control_to_walker) << [
this](
2085 cr::ActorId ActorId,
2086 cr::WalkerControl Control) ->
R<void>
2093 "apply_control_to_walker",
2095 " Actor Id: " + FString::FromInt(ActorId));
2102 "apply_control_to_walker",
2104 " Actor Id: " + FString::FromInt(ActorId));
2109 BIND_SYNC(get_bones_transform) << [
this](
2117 "get_bones_transform",
2119 " Actor Id: " + FString::FromInt(ActorId));
2127 "get_bones_transform",
2129 " Actor Id: " + FString::FromInt(ActorId));
2132 std::vector<carla::rpc::BoneTransformDataOut> BoneData;
2136 Data.
bone_name = std::string(TCHAR_TO_UTF8(*Bone.Get<0>()));
2141 BoneData.push_back(Data);
2146 BIND_SYNC(set_bones_transform) << [
this](
2147 cr::ActorId ActorId,
2155 "set_bones_transform",
2157 " Actor Id: " + FString::FromInt(ActorId));
2165 "set_bones_transform",
2167 " Actor Id: " + FString::FromInt(ActorId));
2174 cr::ActorId ActorId,
2184 " Actor Id: " + FString::FromInt(ActorId));
2193 " Actor Id: " + FString::FromInt(ActorId));
2199 BIND_SYNC(get_pose_from_animation) << [
this](
2200 cr::ActorId ActorId) ->
R<void>
2207 "get_pose_from_animation",
2209 " Actor Id: " + FString::FromInt(ActorId));
2216 "get_pose_from_animation",
2218 " Actor Id: " + FString::FromInt(ActorId));
2224 BIND_SYNC(set_actor_autopilot) << [
this](
2225 cr::ActorId ActorId,
2233 "set_actor_autopilot",
2235 " Actor Id: " + FString::FromInt(ActorId));
2242 "set_actor_autopilot",
2244 " Actor Id: " + FString::FromInt(ActorId));
2249 BIND_SYNC(get_telemetry_data) << [
this](
2257 "get_telemetry_data",
2259 " Actor Id: " + FString::FromInt(ActorId));
2267 "get_telemetry_data",
2269 " Actor Id: " + FString::FromInt(ActorId));
2271 return cr::VehicleTelemetryData(TelemetryData);
2274 BIND_SYNC(show_vehicle_debug_telemetry) << [
this](
2275 cr::ActorId ActorId,
2283 "show_vehicle_debug_telemetry",
2285 " Actor Id: " + FString::FromInt(ActorId));
2292 "show_vehicle_debug_telemetry",
2294 " Actor Id: " + FString::FromInt(ActorId));
2300 cr::ActorId ActorId,
2301 std::string SimfilePath) ->
R<void>
2310 " Actor Id: " + FString::FromInt(ActorId));
2313 CarlaActor->
EnableCarSim(carla::rpc::ToFString(SimfilePath));
2319 " Actor Id: " + FString::FromInt(ActorId));
2325 cr::ActorId ActorId,
2335 " Actor Id: " + FString::FromInt(ActorId));
2344 " Actor Id: " + FString::FromInt(ActorId));
2349 BIND_SYNC(enable_chrono_physics) << [
this](
2350 cr::ActorId ActorId,
2351 uint64_t MaxSubsteps,
2352 float MaxSubstepDeltaTime,
2353 std::string VehicleJSON,
2354 std::string PowertrainJSON,
2355 std::string TireJSON,
2356 std::string BaseJSONPath) ->
R<void>
2363 "enable_chrono_physics",
2365 " Actor Id: " + FString::FromInt(ActorId));
2369 MaxSubsteps, MaxSubstepDeltaTime,
2370 cr::ToFString(VehicleJSON),
2371 cr::ToFString(PowertrainJSON),
2372 cr::ToFString(TireJSON),
2373 cr::ToFString(BaseJSONPath));
2377 "enable_chrono_physics",
2379 " Actor Id: " + FString::FromInt(ActorId));
2384 BIND_SYNC(restore_physx_physics) << [
this](
2385 cr::ActorId ActorId) ->
R<void>
2392 "restore_physx_physics",
2394 " Actor Id: " + FString::FromInt(ActorId));
2401 "restore_physx_physics",
2403 " Actor Id: " + FString::FromInt(ActorId));
2410 BIND_SYNC(set_traffic_light_state) << [
this](
2411 cr::ActorId ActorId,
2412 cr::TrafficLightState trafficLightState) ->
R<void>
2419 "set_traffic_light_state",
2421 " Actor Id: " + FString::FromInt(ActorId));
2429 "set_traffic_light_state",
2431 " Actor Id: " + FString::FromInt(ActorId));
2436 BIND_SYNC(set_traffic_light_green_time) << [
this](
2437 cr::ActorId ActorId,
2445 "set_traffic_light_green_time",
2447 " Actor Id: " + FString::FromInt(ActorId));
2454 "set_traffic_light_green_time",
2456 " Actor Id: " + FString::FromInt(ActorId));
2461 BIND_SYNC(set_traffic_light_yellow_time) << [
this](
2462 cr::ActorId ActorId,
2470 "set_traffic_light_yellow_time",
2472 " Actor Id: " + FString::FromInt(ActorId));
2479 "set_traffic_light_yellow_time",
2481 " Actor Id: " + FString::FromInt(ActorId));
2486 BIND_SYNC(set_traffic_light_red_time) << [
this](
2487 cr::ActorId ActorId,
2495 "set_traffic_light_red_time",
2497 " Actor Id: " + FString::FromInt(ActorId));
2504 "set_traffic_light_red_time",
2506 " Actor Id: " + FString::FromInt(ActorId));
2511 BIND_SYNC(freeze_traffic_light) << [
this](
2512 cr::ActorId ActorId,
2520 "freeze_traffic_light",
2522 " Actor Id: " + FString::FromInt(ActorId));
2529 "freeze_traffic_light",
2531 " Actor Id: " + FString::FromInt(ActorId));
2536 BIND_SYNC(reset_traffic_light_group) << [
this](
2537 cr::ActorId ActorId) ->
R<void>
2544 "reset_traffic_light_group",
2546 " Actor Id: " + FString::FromInt(ActorId));
2553 "reset_traffic_light_group",
2555 " Actor Id: " + FString::FromInt(ActorId));
2563 for (TActorIterator<ATrafficLightGroup> It(
Episode->GetWorld()); It; ++It)
2570 BIND_SYNC(freeze_all_traffic_lights) << [
this]
2579 auto* TraffiLightManager = GameMode->GetTrafficLightManager();
2580 TraffiLightManager->SetFrozen(frozen);
2587 cr::VehicleLightStateList List;
2602 if (!Actor->IsPendingKill())
2607 cr::VehicleLightState(
Vehicle->GetVehicleLightState()).GetLightStateAsValue());
2615 BIND_SYNC(get_group_traffic_lights) << [
this](
2616 const cr::ActorId ActorId) ->
R<std::vector<cr::ActorId>>
2622 RESPOND_ERROR(
"unable to get group traffic lights: actor not found");
2627 return std::vector<cr::ActorId>();
2634 RESPOND_ERROR(
"unable to get group traffic lights: actor is not a traffic light");
2636 std::vector<cr::ActorId> Result;
2637 for (
auto* TLight :
TrafficLight->GetGroupTrafficLights())
2642 Result.push_back(View->GetActorId());
2650 const cr::ActorId ActorId) ->
R<std::vector<cg::BoundingBox>>
2659 " Actor Id: " + FString::FromInt(ActorId));
2666 " Actor Id: " + FString::FromInt(ActorId));
2676 " Actor Id: " + FString::FromInt(ActorId));
2678 TArray<FBoundingBox> Result;
2679 TArray<uint8> OutTag;
2683 return MakeVectorFromTArray<cg::BoundingBox>(Result);
2688 BIND_SYNC(get_gbuffer_token) << [
this](
const cr::ActorId ActorId, uint32_t GBufferId) ->
R<std::vector<unsigned char>>
2695 "get_gbuffer_token",
2697 " Actor Id: " + FString::FromInt(ActorId));
2702 "get_gbuffer_token",
2704 " Actor Id: " + FString::FromInt(ActorId));
2710 "get_gbuffer_token",
2712 " Actor Id: " + FString::FromInt(ActorId));
2720 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2725 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2730 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2735 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2740 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2745 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2750 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2755 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2760 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2765 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2770 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2775 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2780 return std::vector<unsigned char>(std::begin(Token.data), std::end(Token.data));
2783 UE_LOG(LogCarla, Error, TEXT(
"Requested invalid GBuffer ID %u"), GBufferId);
2803 BIND_SYNC(show_recorder_file_info) << [
this](
2813 BIND_SYNC(show_recorder_collisions) << [
this](
2825 BIND_SYNC(show_recorder_actors_blocked) << [
this](
2853 BIND_SYNC(set_replayer_time_factor) << [
this](
double time_factor) ->
R<void>
2867 BIND_SYNC(set_replayer_ignore_spectator) << [
this](
bool ignore_spectator) ->
R<void>
2883 BIND_SYNC(draw_debug_shape) << [
this](
const cr::DebugShape &shape) ->
R<void>
2886 auto *World =
Episode->GetWorld();
2887 check(World !=
nullptr);
2895 using C = cr::Command;
2896 using CR = cr::CommandResponse;
2899 auto parse_result = [](ActorId id,
const auto &response) {
2900 return response.HasError() ? CR{response.GetError()} : CR{
id};
2903#define MAKE_RESULT(operation) return parse_result(c.actor, operation);
2906 [=](
auto self,
const C::SpawnActor &c) -> CR {
2907 auto result = c.parent.has_value() ?
2908 spawn_actor_with_parent(
2912 cr::AttachmentType::Rigid,
2914 spawn_actor(c.description, c.transform);
2915 if (!result.HasError())
2917 ActorId
id = result.Get().id;
2919 [](C::SpawnActor &) {},
2920 [](C::ConsoleCommand &) {},
2921 [id](
auto &s) { s.actor = id; });
2922 for (
auto command : c.do_after)
2924 boost::variant2::visit(set_id, command.command);
2925 boost::variant2::visit(self, command.command);
2929 return result.GetError();
2931 [=](
auto,
const C::DestroyActor &c) {
MAKE_RESULT(destroy_actor(c.actor)); },
2932 [=](
auto,
const C::ApplyVehicleControl &c) {
MAKE_RESULT(apply_control_to_vehicle(c.actor, c.control)); },
2933 [=](
auto,
const C::ApplyVehicleAckermannControl &c) {
MAKE_RESULT(apply_ackermann_control_to_vehicle(c.actor, c.control)); },
2934 [=](
auto,
const C::ApplyWalkerControl &c) {
MAKE_RESULT(apply_control_to_walker(c.actor, c.control)); },
2935 [=](
auto,
const C::ApplyVehiclePhysicsControl &c) {
MAKE_RESULT(apply_physics_control(c.actor, c.physics_control)); },
2936 [=](
auto,
const C::ApplyTransform &c) {
MAKE_RESULT(set_actor_transform(c.actor, c.transform)); },
2937 [=](
auto,
const C::ApplyTargetVelocity &c) {
MAKE_RESULT(set_actor_target_velocity(c.actor, c.velocity)); },
2938 [=](
auto,
const C::ApplyTargetAngularVelocity &c) {
MAKE_RESULT(set_actor_target_angular_velocity(c.actor, c.angular_velocity)); },
2939 [=](
auto,
const C::ApplyImpulse &c) {
MAKE_RESULT(add_actor_impulse(c.actor, c.impulse)); },
2940 [=](
auto,
const C::ApplyForce &c) {
MAKE_RESULT(add_actor_force(c.actor, c.force)); },
2941 [=](
auto,
const C::ApplyAngularImpulse &c) {
MAKE_RESULT(add_actor_angular_impulse(c.actor, c.impulse)); },
2942 [=](
auto,
const C::ApplyTorque &c) {
MAKE_RESULT(add_actor_torque(c.actor, c.torque)); },
2943 [=](
auto,
const C::SetSimulatePhysics &c) {
MAKE_RESULT(set_actor_simulate_physics(c.actor, c.enabled)); },
2944 [=](
auto,
const C::SetEnableGravity &c) {
MAKE_RESULT(set_actor_enable_gravity(c.actor, c.enabled)); },
2946 [=](
auto,
const C::SetAutopilot &c) {
MAKE_RESULT(set_actor_autopilot(c.actor, c.enabled)); },
2947 [=](
auto,
const C::ShowDebugTelemetry &c) {
MAKE_RESULT(show_vehicle_debug_telemetry(c.actor, c.enabled)); },
2948 [=](
auto,
const C::SetVehicleLightState &c) {
MAKE_RESULT(set_vehicle_light_state(c.actor, c.light_state)); },
2951 [=](
auto,
const C::ApplyWalkerState &c) {
MAKE_RESULT(set_walker_state(c.actor, c.transform, c.speed)); },
2952 [=](
auto,
const C::ConsoleCommand& c) -> CR {
return console_command(c.cmd); },
2953 [=](
auto,
const C::SetTrafficLightState& c) {
MAKE_RESULT(set_traffic_light_state(c.actor, c.traffic_light_state)); },
2954 [=](
auto,
const C::ApplyLocation& c) {
MAKE_RESULT(set_actor_location(c.actor, c.location)); }
2960 const std::vector<cr::Command> &commands,
2963 std::vector<CR> result;
2964 result.reserve(commands.size());
2965 for (
const auto &command : commands)
2967 result.emplace_back(boost::variant2::visit(command_visitor, command.command));
2978 BIND_SYNC(query_lights_state) << [
this](std::string client) ->
R<std::vector<cr::LightState>>
2981 std::vector<cr::LightState> result;
2982 auto *World =
Episode->GetWorld();
2985 result = CarlaLightSubsystem->
GetLights(FString(client.c_str()));
2990 BIND_SYNC(update_lights_state) << [
this]
2991 (std::string client,
const std::vector<cr::LightState>& lights,
bool discard_client) ->
R<void>
2994 auto *World =
Episode->GetWorld();
2997 CarlaLightSubsystem->
SetLights(FString(client.c_str()), lights, discard_client);
3002 BIND_SYNC(update_day_night_cycle) << [
this]
3003 (std::string client,
const bool active) ->
R<void>
3006 auto *World =
Episode->GetWorld();
3018 (cr::Location Location, cr::Vector3D Direction,
float SearchDistance)
3019 ->
R<std::pair<bool,cr::LabelledPoint>>
3022 auto *World =
Episode->GetWorld();
3023 constexpr float meter_to_centimeter = 100.0f;
3024 FVector UELocation = Location;
3032 meter_to_centimeter * SearchDistance, World);
3036 (cr::Location StartLocation, cr::Location EndLocation)
3037 ->
R<std::vector<cr::LabelledPoint>>
3040 auto *World =
Episode->GetWorld();
3041 FVector UEStartLocation = StartLocation;
3042 FVector UEEndLocation = EndLocation;