Refactor the server to always return a Response object, move some functionality to UCarlaEpisode

This commit is contained in:
nsubiron 2019-01-27 13:25:11 +01:00
parent 7a21d8a061
commit 027362bb48
17 changed files with 525 additions and 411 deletions

View File

@ -55,12 +55,7 @@ namespace client {
const ActorBlueprint &blueprint, const ActorBlueprint &blueprint,
const geom::Transform &transform, const geom::Transform &transform,
Actor *parent_actor) { Actor *parent_actor) {
try { return _episode.Lock()->SpawnActor(blueprint, transform, parent_actor);
return _episode.Lock()->SpawnActor(blueprint, transform, parent_actor);
} catch (const std::exception &e) {
log_warning("SpawnActor: failed with:", e.what());
throw;
}
} }
SharedPtr<Actor> World::TrySpawnActor( SharedPtr<Actor> World::TrySpawnActor(
@ -69,7 +64,7 @@ namespace client {
Actor *parent_actor) noexcept { Actor *parent_actor) noexcept {
try { try {
return SpawnActor(blueprint, transform, parent_actor); return SpawnActor(blueprint, transform, parent_actor);
} catch (const std::exception &) { } catch (const std::exception &e) {
return nullptr; return nullptr;
} }
} }

View File

@ -10,6 +10,7 @@
#include "carla/rpc/ActorDescription.h" #include "carla/rpc/ActorDescription.h"
#include "carla/rpc/Client.h" #include "carla/rpc/Client.h"
#include "carla/rpc/DebugShape.h" #include "carla/rpc/DebugShape.h"
#include "carla/rpc/Response.h"
#include "carla/rpc/VehicleControl.h" #include "carla/rpc/VehicleControl.h"
#include "carla/rpc/WalkerControl.h" #include "carla/rpc/WalkerControl.h"
#include "carla/streaming/Client.h" #include "carla/streaming/Client.h"
@ -20,6 +21,15 @@ namespace carla {
namespace client { namespace client {
namespace detail { namespace detail {
template <typename T>
static T Get(carla::rpc::Response<T> &response) {
return response.Get();
}
static bool Get(carla::rpc::Response<void> &) {
return true;
}
// =========================================================================== // ===========================================================================
// -- Client::Pimpl ---------------------------------------------------------- // -- Client::Pimpl ----------------------------------------------------------
// =========================================================================== // ===========================================================================
@ -35,8 +45,14 @@ namespace detail {
} }
template <typename T, typename... Args> template <typename T, typename... Args>
T CallAndWait(const std::string &function, Args &&... args) { auto CallAndWait(const std::string &function, Args &&... args) {
return rpc_client.call(function, std::forward<Args>(args)...).template as<T>(); auto object = rpc_client.call(function, std::forward<Args>(args)...);
using R = typename carla::rpc::Response<T>;
auto response = object.template as<R>();
if (response.HasError()) {
throw_exception(std::runtime_error(response.GetError().What()));
}
return Get(response);
} }
template <typename... Args> template <typename... Args>
@ -121,7 +137,13 @@ namespace detail {
} }
bool Client::DestroyActor(const rpc::Actor &actor) { bool Client::DestroyActor(const rpc::Actor &actor) {
return _pimpl->CallAndWait<bool>("destroy_actor", actor); try {
return _pimpl->CallAndWait<void>("destroy_actor", actor);
} catch (const std::exception &e) {
log_error("failed to destroy actor:", actor.id, actor.description.id);
log_error(e.what());
return false;
}
} }
void Client::SetActorLocation(const rpc::Actor &actor, const geom::Location &location) { void Client::SetActorLocation(const rpc::Actor &actor, const geom::Location &location) {

View File

@ -15,22 +15,26 @@
static FActorView::ActorType FActorRegistry_GetActorType(const FActorView &View) static FActorView::ActorType FActorRegistry_GetActorType(const FActorView &View)
{ {
if (View.IsValid()) if (!View.IsValid())
{ {
if (nullptr != Cast<ACarlaWheeledVehicle>(View.GetActor())) return FActorView::ActorType::INVALID;
{ }
return FActorView::ActorType::Vehicle; else if (nullptr != Cast<ACarlaWheeledVehicle>(View.GetActor()))
} {
else if (nullptr != Cast<ACharacter>(View.GetActor())) return FActorView::ActorType::Vehicle;
{ }
return FActorView::ActorType::Walker; else if (nullptr != Cast<ACharacter>(View.GetActor()))
} {
else if (nullptr != Cast<ATrafficLightBase>(View.GetActor())) return FActorView::ActorType::Walker;
{ }
return FActorView::ActorType::TrafficLight; else if (nullptr != Cast<ATrafficLightBase>(View.GetActor()))
} {
return FActorView::ActorType::TrafficLight;
}
else
{
return FActorView::ActorType::Other;
} }
return FActorView::ActorType::Other;
} }
static FString GetRelevantTagAsString(const TSet<ECityObjectLabel> &SemanticTags) static FString GetRelevantTagAsString(const TSet<ECityObjectLabel> &SemanticTags)
@ -73,7 +77,7 @@ FActorView FActorRegistry::Register(AActor &Actor, FActorDescription Description
void FActorRegistry::Deregister(IdType Id) void FActorRegistry::Deregister(IdType Id)
{ {
check(Contains(Id)); check(Contains(Id));
AActor *Actor = FindActor(Id); AActor *Actor = Find(Id).GetActor();
check(Actor != nullptr); check(Actor != nullptr);
ActorDatabase.erase(Id); ActorDatabase.erase(Id);
Actors.Remove(Id); Actors.Remove(Id);
@ -83,15 +87,17 @@ void FActorRegistry::Deregister(IdType Id)
void FActorRegistry::Deregister(AActor *Actor) void FActorRegistry::Deregister(AActor *Actor)
{ {
check(Actor != nullptr);
auto View = Find(Actor); auto View = Find(Actor);
check(View.IsValid()); check(View.GetActor() == Actor);
Deregister(View.GetActorId()); Deregister(View.GetActorId());
} }
FActorView FActorRegistry::FindOrFake(AActor *Actor) const FActorView FActorRegistry::FindOrFake(AActor *Actor) const
{ {
auto View = Find(Actor); auto View = Find(Actor);
return View.IsValid() ? View : MakeView(0u, *Actor, FActorDescription{}); const bool bFakeActor = (View.GetActor() == nullptr) && (Actor != nullptr);
return bFakeActor ? MakeView(0u, *Actor, FActorDescription{}) : View;
} }
FActorView FActorRegistry::MakeView( FActorView FActorRegistry::MakeView(

View File

@ -76,12 +76,6 @@ public:
return PtrToId != nullptr ? Find(*PtrToId) : FActorView(); return PtrToId != nullptr ? Find(*PtrToId) : FActorView();
} }
AActor *FindActor(IdType Id) const
{
auto View = Find(Id);
return View.IsValid() ? View.GetActor() : nullptr;
}
/// If the actor is not found in the registry, create a fake actor view. The /// If the actor is not found in the registry, create a fake actor view. The
/// returned FActorView has some information about the @a Actor but will have /// returned FActorView has some information about the @a Actor but will have
/// an invalid id. /// an invalid id.

View File

@ -21,7 +21,8 @@ public:
Other, Other,
Vehicle, Vehicle,
Walker, Walker,
TrafficLight TrafficLight,
INVALID
}; };
FActorView() = default; FActorView() = default;
@ -30,7 +31,7 @@ public:
bool IsValid() const bool IsValid() const
{ {
return (TheActor != nullptr) && Info.IsValid(); return (TheActor != nullptr) && !TheActor->IsPendingKill();
} }
IdType GetActorId() const IdType GetActorId() const

View File

@ -7,6 +7,8 @@
#include "Carla.h" #include "Carla.h"
#include "Carla/Game/CarlaEpisode.h" #include "Carla/Game/CarlaEpisode.h"
#include "Carla/Sensor/Sensor.h"
#include "Carla/Util/BoundingBoxCalculator.h"
#include "Carla/Vehicle/VehicleSpawnPoint.h" #include "Carla/Vehicle/VehicleSpawnPoint.h"
#include "EngineUtils.h" #include "EngineUtils.h"
@ -38,7 +40,7 @@ UCarlaEpisode::UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
return ++COUNTER; return ++COUNTER;
}()) {} }()) {}
TArray<FTransform> UCarlaEpisode::GetRecommendedStartTransforms() const TArray<FTransform> UCarlaEpisode::GetRecommendedSpawnPoints() const
{ {
TArray<FTransform> SpawnPoints; TArray<FTransform> SpawnPoints;
for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It) { for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It) {
@ -47,22 +49,29 @@ TArray<FTransform> UCarlaEpisode::GetRecommendedStartTransforms() const
return SpawnPoints; return SpawnPoints;
} }
const AWorldObserver *UCarlaEpisode::StartWorldObserver(carla::streaming::MultiStream Stream) carla::rpc::Actor UCarlaEpisode::SerializeActor(FActorView ActorView) const
{ {
UE_LOG(LogCarla, Log, TEXT("Starting AWorldObserver sensor")); carla::rpc::Actor Actor;
check(WorldObserver == nullptr); if (ActorView.IsValid())
auto *World = GetWorld(); {
check(World != nullptr); Actor = ActorView.GetActorInfo()->SerializedData;
WorldObserver = World->SpawnActorDeferred<AWorldObserver>( auto Parent = ActorView.GetActor()->GetOwner();
AWorldObserver::StaticClass(), if (Parent != nullptr)
FTransform(), {
nullptr, Actor.parent_id = FindActor(Parent).GetActorId();
nullptr, }
ESpawnActorCollisionHandlingMethod::AlwaysSpawn); } else {
WorldObserver->SetEpisode(*this); UE_LOG(LogCarla, Warning, TEXT("Trying to serialize invalid actor"));
WorldObserver->SetStream(std::move(Stream)); }
UGameplayStatics::FinishSpawningActor(WorldObserver, FTransform()); return Actor;
return WorldObserver; }
void UCarlaEpisode::AttachActors(AActor *Child, AActor *Parent)
{
check(Child != nullptr);
check(Parent != nullptr);
Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform);
Child->SetOwner(Parent);
} }
void UCarlaEpisode::InitializeAtBeginPlay() void UCarlaEpisode::InitializeAtBeginPlay()

View File

@ -10,6 +10,12 @@
#include "Carla/Sensor/WorldObserver.h" #include "Carla/Sensor/WorldObserver.h"
#include "Carla/Weather/Weather.h" #include "Carla/Weather/Weather.h"
#include "GameFramework/Pawn.h"
#include <compiler/disable-ue4-macros.h>
#include <carla/rpc/Actor.h>
#include <compiler/enable-ue4-macros.h>
#include "CarlaEpisode.generated.h" #include "CarlaEpisode.generated.h"
/// A simulation episode. /// A simulation episode.
@ -20,21 +26,51 @@ class CARLA_API UCarlaEpisode : public UObject
{ {
GENERATED_BODY() GENERATED_BODY()
// ===========================================================================
// -- Constructor ------------------------------------------------------------
// ===========================================================================
public: public:
UCarlaEpisode(const FObjectInitializer &ObjectInitializer); UCarlaEpisode(const FObjectInitializer &ObjectInitializer);
// ===========================================================================
// -- Retrieve info about this episode ---------------------------------------
// ===========================================================================
public:
/// Return the unique id of this episode.
auto GetId() const auto GetId() const
{ {
return Id; return Id;
} }
/// Return the name of the map loaded in this episode.
UFUNCTION(BlueprintCallable) UFUNCTION(BlueprintCallable)
const FString &GetMapName() const const FString &GetMapName() const
{ {
return MapName; return MapName;
} }
/// Return the list of actor definitions that are available to be spawned this
/// episode.
UFUNCTION(BlueprintCallable)
const TArray<FActorDefinition> &GetActorDefinitions() const
{
return ActorDispatcher.GetActorDefinitions();
}
/// Return the list of recommended spawn points for vehicles.
UFUNCTION(BlueprintCallable)
TArray<FTransform> GetRecommendedSpawnPoints() const;
// ===========================================================================
// -- Retrieve special actors ------------------------------------------------
// ===========================================================================
public:
UFUNCTION(BlueprintCallable) UFUNCTION(BlueprintCallable)
APawn *GetSpectatorPawn() const APawn *GetSpectatorPawn() const
{ {
@ -47,17 +83,55 @@ public:
return Weather; return Weather;
} }
/// Return the list of actor definitions that are available to be spawned this const AWorldObserver *GetWorldObserver() const
/// episode.
UFUNCTION(BlueprintCallable)
const TArray<FActorDefinition> &GetActorDefinitions() const
{ {
return ActorDispatcher.GetActorDefinitions(); return WorldObserver;
} }
/// Return the list of recommended start positions. const FActorRegistry &GetActorRegistry() const
UFUNCTION(BlueprintCallable) {
TArray<FTransform> GetRecommendedStartTransforms() const; return ActorDispatcher.GetActorRegistry();
}
// ===========================================================================
// -- Actor look up methods --------------------------------------------------
// ===========================================================================
public:
/// Find a Carla actor by id.
///
/// If the actor is not found or is pending kill, the returned view is
/// invalid.
FActorView FindActor(FActorView::IdType ActorId) const
{
return ActorDispatcher.GetActorRegistry().Find(ActorId);
}
/// Find the actor view of @a Actor.
///
/// If the actor is not found or is pending kill, the returned view is
/// invalid.
FActorView FindActor(AActor *Actor) const
{
return ActorDispatcher.GetActorRegistry().Find(Actor);
}
/// Find the actor view of @a Actor. If the actor is not found, a "fake" view
/// is returned emulating an existing Carla actor. Use this to return views
/// over static actors present in the map.
///
/// If the actor is pending kill, the returned view is invalid.
FActorView FindOrFakeActor(AActor *Actor) const
{
return ActorDispatcher.GetActorRegistry().FindOrFake(Actor);
}
// ===========================================================================
// -- Actor handling methods -------------------------------------------------
// ===========================================================================
public:
/// Spawns an actor based on @a ActorDescription at @a Transform. To properly /// Spawns an actor based on @a ActorDescription at @a Transform. To properly
/// despawn an actor created with this function call DestroyActor. /// despawn an actor created with this function call DestroyActor.
@ -86,6 +160,12 @@ public:
return SpawnActorWithInfo(Transform, std::move(ActorDescription)).Value.GetActor(); return SpawnActorWithInfo(Transform, std::move(ActorDescription)).Value.GetActor();
} }
/// Attach @a Child to @a Parent.
///
/// @pre Actors cannot be null.
UFUNCTION(BlueprintCallable)
void AttachActors(AActor *Child, AActor *Parent);
/// @copydoc FActorDispatcher::DestroyActor(AActor*) /// @copydoc FActorDispatcher::DestroyActor(AActor*)
UFUNCTION(BlueprintCallable) UFUNCTION(BlueprintCallable)
bool DestroyActor(AActor *Actor) bool DestroyActor(AActor *Actor)
@ -93,17 +173,18 @@ public:
return ActorDispatcher.DestroyActor(Actor); return ActorDispatcher.DestroyActor(Actor);
} }
const FActorRegistry &GetActorRegistry() const // ===========================================================================
{ // -- Other methods ----------------------------------------------------------
return ActorDispatcher.GetActorRegistry(); // ===========================================================================
}
const AWorldObserver *StartWorldObserver(carla::streaming::MultiStream Stream); public:
const AWorldObserver *GetWorldObserver() const /// Create a serializable object describing the actor.
{ carla::rpc::Actor SerializeActor(FActorView ActorView) const;
return WorldObserver;
} // ===========================================================================
// -- Private methods and members --------------------------------------------
// ===========================================================================
private: private:

View File

@ -25,7 +25,7 @@ UCarlaGameInstance::UCarlaGameInstance() {
CarlaSettings->LogSettings(); CarlaSettings->LogSettings();
} }
UCarlaGameInstance::~UCarlaGameInstance() {} UCarlaGameInstance::~UCarlaGameInstance() = default;
void UCarlaGameInstance::InitializeGameControllerIfNotPresent( void UCarlaGameInstance::InitializeGameControllerIfNotPresent(
const FMockGameControllerSettings &MockControllerSettings) const FMockGameControllerSettings &MockControllerSettings)
@ -40,7 +40,7 @@ void UCarlaGameInstance::InitializeGameControllerIfNotPresent(
} }
} }
void UCarlaGameInstance::NotifyBeginEpisode(UCarlaEpisode &Episode) void UCarlaGameInstance::StartServer()
{ {
if (!bServerIsRunning) if (!bServerIsRunning)
{ {
@ -48,10 +48,4 @@ void UCarlaGameInstance::NotifyBeginEpisode(UCarlaEpisode &Episode)
Server.AsyncRun(GetNumberOfThreadsForRPCServer()); Server.AsyncRun(GetNumberOfThreadsForRPCServer());
bServerIsRunning = true; bServerIsRunning = true;
} }
Server.NotifyBeginEpisode(Episode);
}
void UCarlaGameInstance::NotifyEndEpisode()
{
Server.NotifyEndEpisode();
} }

View File

@ -33,6 +33,9 @@ public:
void InitializeGameControllerIfNotPresent( void InitializeGameControllerIfNotPresent(
const FMockGameControllerSettings &MockControllerSettings); const FMockGameControllerSettings &MockControllerSettings);
/// Starts the Carla server if not already running.
void StartServer();
ICarlaGameControllerBase &GetGameController() ICarlaGameControllerBase &GetGameController()
{ {
check(GameController != nullptr); check(GameController != nullptr);
@ -63,14 +66,20 @@ public:
return DataRouter; return DataRouter;
} }
void NotifyBeginEpisode(UCarlaEpisode &Episode); void NotifyBeginEpisode(UCarlaEpisode &Episode)
{
Server.NotifyBeginEpisode(Episode);
}
void Tick(float /*DeltaSeconds*/) void Tick(float /*DeltaSeconds*/)
{ {
Server.RunSome(10u); /// @todo Server.RunSome(10u); /// @todo
} }
void NotifyEndEpisode(); void NotifyEndEpisode()
{
Server.NotifyEndEpisode();
}
const FTheNewCarlaServer &GetServer() const const FTheNewCarlaServer &GetServer() const
{ {

View File

@ -75,6 +75,12 @@ void ATheNewCarlaGameModeBase::InitGame(
UE_LOG(LogCarla, Error, TEXT("Missing weather class!")); UE_LOG(LogCarla, Error, TEXT("Missing weather class!"));
} }
GameInstance->StartServer();
Episode->WorldObserver = World->SpawnActor<AWorldObserver>();
Episode->WorldObserver->SetEpisode(*Episode);
Episode->WorldObserver->SetStream(GameInstance->GetServer().OpenMultiStream());
SpawnActorFactories(); SpawnActorFactories();
} }

View File

@ -50,13 +50,6 @@ void ACollisionSensor::BeginPlay()
return; return;
} }
Episode = &GameMode->GetCarlaEpisode(); Episode = &GameMode->GetCarlaEpisode();
GameInstance = Cast<UCarlaGameInstance>(GetGameInstance());
if (GameMode == nullptr)
{
UE_LOG(LogCarla, Error, TEXT("ACollisionSensor: Game instance not compatible with this sensor"));
return;
}
} }
void ACollisionSensor::OnCollisionEvent( void ACollisionSensor::OnCollisionEvent(
@ -65,16 +58,14 @@ void ACollisionSensor::OnCollisionEvent(
FVector NormalImpulse, FVector NormalImpulse,
const FHitResult &Hit) const FHitResult &Hit)
{ {
if ((Episode != nullptr) && (GameInstance != nullptr) && (Actor != nullptr) && (OtherActor != nullptr)) if ((Episode != nullptr) && (Actor != nullptr) && (OtherActor != nullptr))
{ {
const auto &Registry = Episode->GetActorRegistry();
const auto &Server = GameInstance->GetServer();
constexpr float TO_METERS = 1e-2; constexpr float TO_METERS = 1e-2;
NormalImpulse *= TO_METERS; NormalImpulse *= TO_METERS;
GetDataStream().Send_GameThread( GetDataStream().Send_GameThread(
*this, *this,
Server.SerializeActor(Registry.FindOrFake(Actor)), Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
Server.SerializeActor(Registry.FindOrFake(OtherActor)), Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),
carla::geom::Vector3D{NormalImpulse.X, NormalImpulse.Y, NormalImpulse.Z}); carla::geom::Vector3D{NormalImpulse.X, NormalImpulse.Y, NormalImpulse.Z});
} }
} }

View File

@ -41,7 +41,4 @@ private:
UPROPERTY() UPROPERTY()
const UCarlaEpisode *Episode = nullptr; const UCarlaEpisode *Episode = nullptr;
UPROPERTY()
const UCarlaGameInstance *GameInstance = nullptr;
}; };

View File

@ -32,6 +32,7 @@ public:
Stream = std::move(InStream); Stream = std::move(InStream);
} }
/// Return the token that allows subscribing to this sensor's stream.
auto GetToken() const auto GetToken() const
{ {
return Stream.GetToken(); return Stream.GetToken();

View File

@ -7,6 +7,7 @@
#include "Carla.h" #include "Carla.h"
#include "Carla/Sensor/SensorFactory.h" #include "Carla/Sensor/SensorFactory.h"
#include "Carla/Game/CarlaGameInstance.h"
#include "Carla/Sensor/Sensor.h" #include "Carla/Sensor/Sensor.h"
#include <compiler/disable-ue4-macros.h> #include <compiler/disable-ue4-macros.h>
@ -109,6 +110,15 @@ FActorSpawnResult ASensorFactory::SpawnActor(
UE_LOG(LogCarla, Error, TEXT("ASensorFactory: cannot spawn sensor into an empty world.")); UE_LOG(LogCarla, Error, TEXT("ASensorFactory: cannot spawn sensor into an empty world."));
return {}; return {};
} }
UCarlaGameInstance *GameInstance = Cast<UCarlaGameInstance>(
UGameplayStatics::GetGameInstance(World));
if (GameInstance == nullptr)
{
UE_LOG(LogCarla, Error, TEXT("ASensorFactory: cannot spawn sensor, incompatible game instance."));
return {};
}
auto *Sensor = World->SpawnActorDeferred<ASensor>( auto *Sensor = World->SpawnActorDeferred<ASensor>(
Description.Class, Description.Class,
Transform, Transform,
@ -122,6 +132,7 @@ FActorSpawnResult ASensorFactory::SpawnActor(
else else
{ {
Sensor->Set(Description); Sensor->Set(Description);
Sensor->SetDataStream(GameInstance->GetServer().OpenStream());
} }
UGameplayStatics::FinishSpawningActor(Sensor, Transform); UGameplayStatics::FinishSpawningActor(Sensor, Transform);
return FActorSpawnResult{Sensor}; return FActorSpawnResult{Sensor};

View File

@ -22,11 +22,12 @@ class CARLA_API AWorldObserver : public AActor
public: public:
/// Prevent this sensor to be spawned by users.
using not_spawnable = void; using not_spawnable = void;
AWorldObserver(const FObjectInitializer& ObjectInitializer); AWorldObserver(const FObjectInitializer& ObjectInitializer);
/// Set the episode that will observe. /// Set the episode that will be observed.
void SetEpisode(UCarlaEpisode &InEpisode) void SetEpisode(UCarlaEpisode &InEpisode)
{ {
checkf(Episode == nullptr, TEXT("Cannot set episode twice!")); checkf(Episode == nullptr, TEXT("Cannot set episode twice!"));
@ -34,18 +35,19 @@ public:
} }
/// Replace the Stream associated with this sensor. /// Replace the Stream associated with this sensor.
///
/// @warning Do not change the stream after BeginPlay. It is not thread-safe.
void SetStream(FDataMultiStream InStream) void SetStream(FDataMultiStream InStream)
{ {
Stream = std::move(InStream); Stream = std::move(InStream);
} }
auto GetStreamToken() const /// Return the token that allows subscribing to this sensor's stream.
auto GetToken() const
{ {
return Stream.GetToken(); return Stream.GetToken();
} }
protected:
void Tick(float DeltaSeconds) final; void Tick(float DeltaSeconds) final;
private: private:

View File

@ -7,15 +7,11 @@
#include "Carla.h" #include "Carla.h"
#include "Carla/Server/TheNewCarlaServer.h" #include "Carla/Server/TheNewCarlaServer.h"
#include "Carla/Sensor/Sensor.h"
#include "Carla/Util/BoundingBoxCalculator.h"
#include "Carla/Util/DebugShapeDrawer.h" #include "Carla/Util/DebugShapeDrawer.h"
#include "Carla/Util/OpenDrive.h" #include "Carla/Util/OpenDrive.h"
#include "Carla/Vehicle/CarlaWheeledVehicle.h" #include "Carla/Vehicle/CarlaWheeledVehicle.h"
#include "Carla/Walker/WalkerController.h" #include "Carla/Walker/WalkerController.h"
#include "GameFramework/SpectatorPawn.h"
#include <compiler/disable-ue4-macros.h> #include <compiler/disable-ue4-macros.h>
#include <carla/Version.h> #include <carla/Version.h>
#include <carla/rpc/Actor.h> #include <carla/rpc/Actor.h>
@ -24,6 +20,7 @@
#include <carla/rpc/DebugShape.h> #include <carla/rpc/DebugShape.h>
#include <carla/rpc/EpisodeInfo.h> #include <carla/rpc/EpisodeInfo.h>
#include <carla/rpc/MapInfo.h> #include <carla/rpc/MapInfo.h>
#include <carla/rpc/Response.h>
#include <carla/rpc/Server.h> #include <carla/rpc/Server.h>
#include <carla/rpc/Transform.h> #include <carla/rpc/Transform.h>
#include <carla/rpc/Vector3D.h> #include <carla/rpc/Vector3D.h>
@ -35,6 +32,9 @@
#include <vector> #include <vector>
template <typename T>
using R = carla::rpc::Response<T>;
// ============================================================================= // =============================================================================
// -- Static local functions --------------------------------------------------- // -- Static local functions ---------------------------------------------------
// ============================================================================= // =============================================================================
@ -45,12 +45,6 @@ static std::vector<T> MakeVectorFromTArray(const TArray<Other> &Array)
return {Array.GetData(), Array.GetData() + Array.Num()}; return {Array.GetData(), Array.GetData() + Array.Num()};
} }
static void AttachActors(AActor *Child, AActor *Parent)
{
Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform);
Child->SetOwner(Parent);
}
// ============================================================================= // =============================================================================
// -- FTheNewCarlaServer::FPimpl ----------------------------------------------- // -- FTheNewCarlaServer::FPimpl -----------------------------------------------
// ============================================================================= // =============================================================================
@ -74,178 +68,120 @@ public:
private: private:
void BindActions(); void BindActions();
void RespondErrorStr(const std::string &ErrorMessage) {
UE_LOG(LogCarlaServer, Log, TEXT("Responding error, %s"), *carla::rpc::ToFString(ErrorMessage));
carla::rpc::Server::RespondError(ErrorMessage);
}
void RespondError(const FString &ErrorMessage) {
RespondErrorStr(carla::rpc::FromFString(ErrorMessage));
}
void RequireEpisode()
{
if (Episode == nullptr)
{
RespondErrorStr("episode not ready");
}
}
auto SpawnActor(const FTransform &Transform, FActorDescription Description)
{
auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
if (Result.Key != EActorSpawnResultStatus::Success)
{
RespondError(FActorSpawnResult::StatusToString(Result.Key));
}
check(Result.Value.IsValid());
return Result.Value;
}
void AttachActors(FActorView Child, FActorView Parent)
{
if (!Child.IsValid())
{
RespondErrorStr("unable to attach actor: child actor not found");
}
if (!Parent.IsValid())
{
RespondErrorStr("unable to attach actor: parent actor not found");
}
::AttachActors(Child.GetActor(), Parent.GetActor());
}
public:
carla::rpc::Actor SerializeActor(FActorView ActorView)
{
carla::rpc::Actor Actor;
Actor.id = ActorView.GetActorId();
if (ActorView.IsValid() && !ActorView.GetActor()->IsPendingKill())
{
Actor.parent_id = Episode->GetActorRegistry().Find(ActorView.GetActor()->GetOwner()).GetActorId();
Actor.description = *ActorView.GetActorDescription();
Actor.bounding_box = UBoundingBoxCalculator::GetActorBoundingBox(ActorView.GetActor());
Actor.semantic_tags.reserve(ActorView.GetSemanticTags().Num());
using tag_t = decltype(Actor.semantic_tags)::value_type;
for (auto &&Tag : ActorView.GetSemanticTags())
{
Actor.semantic_tags.emplace_back(static_cast<tag_t>(Tag));
}
auto *Sensor = Cast<ASensor>(ActorView.GetActor());
if (Sensor != nullptr)
{
auto Stream = GetSensorStream(ActorView, *Sensor);
const auto &Token = Stream.token();
Actor.stream_token = decltype(Actor.stream_token)(std::begin(Token.data), std::end(Token.data));
}
} else {
UE_LOG(LogCarla, Warning, TEXT("Trying to serialize invalid actor"));
}
return Actor;
}
private:
carla::streaming::Stream GetSensorStream(FActorView ActorView, ASensor &Sensor) {
auto id = ActorView.GetActorId();
auto it = _StreamMap.find(id);
if (it == _StreamMap.end()) {
UE_LOG(LogCarlaServer, Log, TEXT("Making a new sensor stream for '%s'"), *ActorView.GetActorDescription()->Id);
auto result = _StreamMap.emplace(id, StreamingServer.MakeStream());
check(result.second);
it = result.first;
Sensor.SetDataStream(it->second);
}
return it->second;
}
void ClearSensorStream(FActorView ActorView) {
_StreamMap.erase(ActorView.GetActorId());
}
std::unordered_map<FActorView::IdType, carla::streaming::Stream> _StreamMap;
}; };
// ============================================================================= // =============================================================================
// -- FTheNewCarlaServer::FPimpl Bind Actions ---------------------------------- // -- Define helper macros -----------------------------------------------------
// =============================================================================
#if WITH_EDITOR
# define CARLA_ENSURE_GAME_THREAD() check(IsInGameThread());
#else
# define CARLA_ENSURE_GAME_THREAD()
#endif // WITH_EDITOR
#define RESPOND_ERROR(str) { \
UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), TEXT(str)); \
return carla::rpc::ResponseError(str); }
#define RESPOND_ERROR_FSTRING(fstr) { \
UE_LOG(LogCarlaServer, Log, TEXT("Responding error: %s"), *fstr); \
return carla::rpc::ResponseError(carla::rpc::FromFString(fstr)); }
#define REQUIRE_CARLA_EPISODE() \
CARLA_ENSURE_GAME_THREAD(); \
if (Episode == nullptr) { RESPOND_ERROR("episode not ready"); }
// =============================================================================
// -- Bind Actions -------------------------------------------------------------
// ============================================================================= // =============================================================================
void FTheNewCarlaServer::FPimpl::BindActions() void FTheNewCarlaServer::FPimpl::BindActions()
{ {
namespace cr = carla::rpc; namespace cr = carla::rpc;
namespace cg = carla::geom;
Server.BindAsync("ping", []() { return true; }); Server.BindAsync("version", []() -> R<std::string>
{
return carla::version();
});
Server.BindAsync("version", []() -> std::string { return carla::version(); }); Server.BindSync("get_episode_info", [this]() -> R<cr::EpisodeInfo>
{
Server.BindSync("get_episode_info", [this]() -> cr::EpisodeInfo { REQUIRE_CARLA_EPISODE();
RequireEpisode();
auto WorldObserver = Episode->GetWorldObserver(); auto WorldObserver = Episode->GetWorldObserver();
if (WorldObserver == nullptr) { if (WorldObserver == nullptr) {
WorldObserver = Episode->StartWorldObserver(StreamingServer.MakeMultiStream()); RESPOND_ERROR("internal error: missing world observer");
} }
return {Episode->GetId(), cr::FromFString(Episode->GetMapName()), WorldObserver->GetStreamToken()}; return cr::EpisodeInfo{
Episode->GetId(),
cr::FromFString(Episode->GetMapName()),
WorldObserver->GetToken()};
}); });
Server.BindSync("get_map_info", [this]() -> cr::MapInfo { Server.BindSync("get_map_info", [this]() -> R<cr::MapInfo>
RequireEpisode(); {
REQUIRE_CARLA_EPISODE();
auto FileContents = FOpenDrive::Load(Episode->GetMapName()); auto FileContents = FOpenDrive::Load(Episode->GetMapName());
const auto &SpawnPoints = Episode->GetRecommendedStartTransforms(); const auto &SpawnPoints = Episode->GetRecommendedSpawnPoints();
std::vector<carla::geom::Transform> spawn_points; return cr::MapInfo{
spawn_points.reserve(SpawnPoints.Num());
for (const auto &Transform : SpawnPoints)
{
spawn_points.emplace_back(Transform);
}
return {
cr::FromFString(Episode->GetMapName()), cr::FromFString(Episode->GetMapName()),
cr::FromFString(FileContents), cr::FromFString(FileContents),
spawn_points}; MakeVectorFromTArray<cg::Transform>(SpawnPoints)};
}); });
Server.BindSync("get_actor_definitions", [this]() { Server.BindSync("get_actor_definitions", [this]() -> R<std::vector<cr::ActorDefinition>>
RequireEpisode(); {
REQUIRE_CARLA_EPISODE();
return MakeVectorFromTArray<cr::ActorDefinition>(Episode->GetActorDefinitions()); return MakeVectorFromTArray<cr::ActorDefinition>(Episode->GetActorDefinitions());
}); });
Server.BindSync("get_spectator", [this]() -> cr::Actor { Server.BindSync("get_spectator", [this]() -> R<cr::Actor> {
RequireEpisode(); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->GetActorRegistry().Find(Episode->GetSpectatorPawn()); auto ActorView = Episode->FindActor(Episode->GetSpectatorPawn());
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { if (!ActorView.IsValid())
RespondErrorStr("unable to find spectator"); {
RESPOND_ERROR("internal error: unable to find spectator");
} }
return SerializeActor(ActorView); return Episode->SerializeActor(ActorView);
}); });
Server.BindSync("get_weather_parameters", [this]() -> cr::WeatherParameters { Server.BindSync("get_weather_parameters", [this]() -> R<cr::WeatherParameters>
RequireEpisode(); {
REQUIRE_CARLA_EPISODE();
auto *Weather = Episode->GetWeather(); auto *Weather = Episode->GetWeather();
if (Weather == nullptr) { if (Weather == nullptr)
RespondErrorStr("unable to find weather"); {
RESPOND_ERROR("internal error: unable to find weather");
} }
return Weather->GetCurrentWeather(); return Weather->GetCurrentWeather();
}); });
Server.BindSync("set_weather_parameters", [this](const cr::WeatherParameters &weather) { Server.BindSync("set_weather_parameters", [this](
RequireEpisode(); const cr::WeatherParameters &weather) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto *Weather = Episode->GetWeather(); auto *Weather = Episode->GetWeather();
if (Weather == nullptr) { if (Weather == nullptr)
RespondErrorStr("unable to find weather"); {
RESPOND_ERROR("internal error: unable to find weather");
} }
Weather->ApplyWeather(weather); Weather->ApplyWeather(weather);
return R<void>::Success();
}); });
Server.BindSync("get_actors_by_id", [this](const std::vector<FActorView::IdType> &ids) { Server.BindSync("get_actors_by_id", [this](
RequireEpisode(); const std::vector<FActorView::IdType> &ids) -> R<std::vector<cr::Actor>>
{
REQUIRE_CARLA_EPISODE();
std::vector<cr::Actor> Result; std::vector<cr::Actor> Result;
Result.reserve(ids.size()); Result.reserve(ids.size());
const auto &Registry = Episode->GetActorRegistry(); for (auto &&Id : ids)
for (auto &&Id : ids) { {
auto View = Registry.Find(Id); auto View = Episode->FindActor(Id);
if (View.IsValid()) { if (View.IsValid())
Result.emplace_back(SerializeActor(View)); {
Result.emplace_back(Episode->SerializeActor(View));
} }
} }
return Result; return Result;
@ -253,237 +189,287 @@ void FTheNewCarlaServer::FPimpl::BindActions()
Server.BindSync("spawn_actor", [this]( Server.BindSync("spawn_actor", [this](
cr::ActorDescription Description, cr::ActorDescription Description,
const cr::Transform &Transform) -> cr::Actor { const cr::Transform &Transform) -> R<cr::Actor>
RequireEpisode(); {
return SerializeActor(SpawnActor(Transform, Description)); REQUIRE_CARLA_EPISODE();
auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
if (Result.Key != EActorSpawnResultStatus::Success)
{
RESPOND_ERROR_FSTRING(FActorSpawnResult::StatusToString(Result.Key));
}
if (!Result.Value.IsValid())
{
RESPOND_ERROR("internal error: actor could not be spawned");
}
return Episode->SerializeActor(Result.Value);
}); });
Server.BindSync("spawn_actor_with_parent", [this]( Server.BindSync("spawn_actor_with_parent", [this](
cr::ActorDescription Description, cr::ActorDescription Description,
const cr::Transform &Transform, const cr::Transform &Transform,
cr::Actor Parent) -> cr::Actor { cr::Actor Parent) -> R<cr::Actor>
RequireEpisode(); {
auto ActorView = SpawnActor(Transform, Description); REQUIRE_CARLA_EPISODE();
auto ParentActorView = Episode->GetActorRegistry().Find(Parent.id); auto Result = Episode->SpawnActorWithInfo(Transform, std::move(Description));
AttachActors(ActorView, ParentActorView); if (Result.Key != EActorSpawnResultStatus::Success)
return SerializeActor(ActorView); {
RESPOND_ERROR_FSTRING(FActorSpawnResult::StatusToString(Result.Key));
}
if (!Result.Value.IsValid())
{
RESPOND_ERROR("internal error: actor could not be spawned");
}
auto ParentActorView = Episode->FindActor(Parent.id);
if (!ParentActorView.IsValid())
{
RESPOND_ERROR("unable to attach actor: parent actor not found");
}
Episode->AttachActors(Result.Value.GetActor(), ParentActorView.GetActor());
return Episode->SerializeActor(Result.Value);
}); });
Server.BindSync("destroy_actor", [this](cr::Actor Actor) { Server.BindSync("destroy_actor", [this](cr::Actor Actor) -> R<void>
RequireEpisode(); {
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); REQUIRE_CARLA_EPISODE();
if (!ActorView.IsValid()) { auto ActorView = Episode->FindActor(Actor.id);
UE_LOG(LogCarlaServer, Warning, TEXT("unable to destroy actor: not found")); if (!ActorView.IsValid())
return false; {
RESPOND_ERROR("unable to destroy actor: not found");
} }
ClearSensorStream(ActorView); if (!Episode->DestroyActor(ActorView.GetActor()))
return Episode->DestroyActor(ActorView.GetActor()); {
RESPOND_ERROR("internal error: unable to destroy actor");
}
return R<void>::Success();
}); });
Server.BindSync("attach_actors", [this](cr::Actor Child, cr::Actor Parent) { Server.BindSync("attach_actors", [this](
RequireEpisode(); cr::Actor Child,
auto &Registry = Episode->GetActorRegistry(); cr::Actor Parent) -> R<void>
AttachActors(Registry.Find(Child.id), Registry.Find(Parent.id)); {
}); REQUIRE_CARLA_EPISODE();
auto ChildView = Episode->FindActor(Child.id);
Server.BindSync("get_actor_location", [this](cr::Actor Actor) -> cr::Location { if (!ChildView.IsValid())
RequireEpisode(); {
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); RESPOND_ERROR("unable to attach actor: child actor not found");
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to get actor location: actor not found");
} }
return {ActorView.GetActor()->GetActorLocation()}; auto ParentView = Episode->FindActor(Parent.id);
}); if (!ParentView.IsValid())
{
Server.BindSync("get_actor_transform", [this](cr::Actor Actor) -> cr::Transform { RESPOND_ERROR("unable to attach actor: parent actor not found");
RequireEpisode();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to get actor transform: actor not found");
} }
return {ActorView.GetActor()->GetActorTransform()}; Episode->AttachActors(ChildView.GetActor(), ParentView.GetActor());
}); return R<void>::Success();
Server.BindSync("get_actor_velocity", [this](cr::Actor Actor) -> cr::Vector3D {
RequireEpisode();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to get actor velocity: actor not found");
}
return cr::Vector3D(ActorView.GetActor()->GetRootComponent()->GetComponentVelocity()).ToMeters();
});
Server.BindSync("get_actor_angular_velocity", [this](cr::Actor Actor) -> cr::Vector3D {
RequireEpisode();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to get actor angular velocity: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr) {
RespondErrorStr("unable to get actor angular velocity: not supported by actor");
}
return cr::Vector3D(RootComponent->GetPhysicsAngularVelocityInDegrees());
});
Server.BindSync("set_actor_angular_velocity", [this](
cr::Actor Actor,
cr::Vector3D vector) {
RequireEpisode();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to set actor angular velocity: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr) {
RespondErrorStr("unable to set actor angular velocity: not supported by actor");
}
RootComponent->SetPhysicsAngularVelocityInDegrees(
vector,
false,
"None");
});
Server.BindSync("set_actor_velocity", [this](
cr::Actor Actor,
cr::Vector3D vector) {
RequireEpisode();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to set actor velocity: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr) {
RespondErrorStr("unable to set actor velocity: not supported by actor");
}
RootComponent->SetPhysicsLinearVelocity(
vector.ToCentimeters(),
false,
"None");
});
Server.BindSync("add_actor_impulse", [this](
cr::Actor Actor,
cr::Vector3D vector) {
RequireEpisode();
auto ActorView = Episode->GetActorRegistry().Find(Actor.id);
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
RespondErrorStr("unable to add actor impulse: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr) {
RespondErrorStr("unable to add actor impulse: not supported by actor");
}
RootComponent->AddImpulse(
vector.ToCentimeters(),
"None",
false);
}); });
Server.BindSync("set_actor_location", [this]( Server.BindSync("set_actor_location", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Location Location) { cr::Location Location) -> R<void>
RequireEpisode(); {
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); REQUIRE_CARLA_EPISODE();
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { auto ActorView = Episode->FindActor(Actor.id);
RespondErrorStr("unable to set actor location: actor not found"); if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set actor location: actor not found");
} }
// This function only works with teleport physics, to reset speeds we need
// another method.
/// @todo print error instead of returning false.
ActorView.GetActor()->SetActorRelativeLocation( ActorView.GetActor()->SetActorRelativeLocation(
Location, Location,
false, false,
nullptr, nullptr,
ETeleportType::TeleportPhysics); ETeleportType::TeleportPhysics);
return R<void>::Success();
}); });
Server.BindSync("set_actor_transform", [this]( Server.BindSync("set_actor_transform", [this](
cr::Actor Actor, cr::Actor Actor,
cr::Transform Transform) { cr::Transform Transform) -> R<void>
RequireEpisode(); {
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); REQUIRE_CARLA_EPISODE();
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { auto ActorView = Episode->FindActor(Actor.id);
RespondErrorStr("unable to set actor transform: actor not found"); if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set actor transform: actor not found");
} }
// This function only works with teleport physics, to reset speeds we need
// another method.
ActorView.GetActor()->SetActorRelativeTransform( ActorView.GetActor()->SetActorRelativeTransform(
Transform, Transform,
false, false,
nullptr, nullptr,
ETeleportType::TeleportPhysics); ETeleportType::TeleportPhysics);
return R<void>::Success();
}); });
Server.BindSync("set_actor_simulate_physics", [this](cr::Actor Actor, bool bEnabled) { Server.BindSync("set_actor_velocity", [this](
RequireEpisode(); cr::Actor Actor,
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); cr::Vector3D vector) -> R<void>
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { {
RespondErrorStr("unable to set actor simulate physics: actor not found"); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set actor velocity: actor not found");
} }
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent()); auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr) { if (RootComponent == nullptr)
RespondErrorStr("unable to set actor simulate physics: not supported by actor"); {
RESPOND_ERROR("unable to set actor velocity: not supported by actor");
}
RootComponent->SetPhysicsLinearVelocity(
vector.ToCentimeters(),
false,
"None");
return R<void>::Success();
});
Server.BindSync("set_actor_angular_velocity", [this](
cr::Actor Actor,
cr::Vector3D vector) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set actor angular velocity: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr)
{
RESPOND_ERROR("unable to set actor angular velocity: not supported by actor");
}
RootComponent->SetPhysicsAngularVelocityInDegrees(
vector,
false,
"None");
return R<void>::Success();
});
Server.BindSync("add_actor_impulse", [this](
cr::Actor Actor,
cr::Vector3D vector) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to add actor impulse: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr)
{
RESPOND_ERROR("unable to add actor impulse: not supported by actor");
}
RootComponent->AddImpulse(
vector.ToCentimeters(),
"None",
false);
return R<void>::Success();
});
Server.BindSync("set_actor_simulate_physics", [this](
cr::Actor Actor,
bool bEnabled) -> R<void>
{
REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set actor simulate physics: actor not found");
}
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
if (RootComponent == nullptr)
{
RESPOND_ERROR("unable to set actor simulate physics: not supported by actor");
} }
RootComponent->SetSimulatePhysics(bEnabled); RootComponent->SetSimulatePhysics(bEnabled);
return R<void>::Success();
}); });
Server.BindSync("apply_control_to_vehicle", [this](cr::Actor Actor, cr::VehicleControl Control) { Server.BindSync("apply_control_to_vehicle", [this](
RequireEpisode(); cr::Actor Actor,
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); cr::VehicleControl Control) -> R<void>
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { {
RespondErrorStr("unable to apply control: actor not found"); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to apply control: actor not found");
} }
auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor()); auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor());
if (Vehicle == nullptr) { if (Vehicle == nullptr)
RespondErrorStr("unable to apply control: actor is not a vehicle"); {
RESPOND_ERROR("unable to apply control: actor is not a vehicle");
} }
Vehicle->ApplyVehicleControl(Control); Vehicle->ApplyVehicleControl(Control);
return R<void>::Success();
}); });
Server.BindSync("apply_control_to_walker", [this](cr::Actor Actor, cr::WalkerControl Control) { Server.BindSync("apply_control_to_walker", [this](
RequireEpisode(); cr::Actor Actor,
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); cr::WalkerControl Control) -> R<void>
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { {
RespondErrorStr("unable to apply control: actor not found"); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to apply control: actor not found");
} }
auto Pawn = Cast<APawn>(ActorView.GetActor()); auto Pawn = Cast<APawn>(ActorView.GetActor());
if (Pawn == nullptr) { if (Pawn == nullptr)
RespondErrorStr("unable to apply control: actor is not a walker"); {
RESPOND_ERROR("unable to apply control: actor is not a walker");
} }
auto Controller = Cast<AWalkerController>(Pawn->GetController()); auto Controller = Cast<AWalkerController>(Pawn->GetController());
if (Controller == nullptr) { if (Controller == nullptr)
RespondErrorStr("unable to apply control: walker has an incompatible controller"); {
RESPOND_ERROR("unable to apply control: walker has an incompatible controller");
} }
Controller->ApplyWalkerControl(Control); Controller->ApplyWalkerControl(Control);
return R<void>::Success();
}); });
Server.BindSync("set_actor_autopilot", [this](cr::Actor Actor, bool bEnabled) { Server.BindSync("set_actor_autopilot", [this](
RequireEpisode(); cr::Actor Actor,
auto ActorView = Episode->GetActorRegistry().Find(Actor.id); bool bEnabled) -> R<void>
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) { {
RespondErrorStr("unable to set autopilot: actor not found"); REQUIRE_CARLA_EPISODE();
auto ActorView = Episode->FindActor(Actor.id);
if (!ActorView.IsValid())
{
RESPOND_ERROR("unable to set autopilot: actor not found");
} }
auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor()); auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor());
if (Vehicle == nullptr) { if (Vehicle == nullptr)
RespondErrorStr("unable to set autopilot: actor is not a vehicle"); {
RESPOND_ERROR("unable to set autopilot: actor does not support autopilot");
} }
auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController()); auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController());
if (Controller == nullptr) { if (Controller == nullptr)
RespondErrorStr("unable to set autopilot: vehicle has an incompatible controller"); {
RESPOND_ERROR("unable to set autopilot: vehicle controller does not support autopilot");
} }
Controller->SetAutopilot(bEnabled); Controller->SetAutopilot(bEnabled);
return R<void>::Success();
}); });
Server.BindSync("draw_debug_shape", [this](const cr::DebugShape &shape) { Server.BindSync("draw_debug_shape", [this](const cr::DebugShape &shape) -> R<void>
RequireEpisode(); {
REQUIRE_CARLA_EPISODE();
auto *World = Episode->GetWorld(); auto *World = Episode->GetWorld();
check(World != nullptr); check(World != nullptr);
FDebugShapeDrawer Drawer(*World); FDebugShapeDrawer Drawer(*World);
Drawer.Draw(shape); Drawer.Draw(shape);
return R<void>::Success();
}); });
} }
// =============================================================================
// -- Undef helper macros ------------------------------------------------------
// =============================================================================
#undef REQUIRE_CARLA_EPISODE
#undef RESPOND_ERROR_FSTRING
#undef RESPOND_ERROR
#undef CARLA_ENSURE_GAME_THREAD
// ============================================================================= // =============================================================================
// -- FTheNewCarlaServer ------------------------------------------------------- // -- FTheNewCarlaServer -------------------------------------------------------
// ============================================================================= // =============================================================================
@ -500,17 +486,20 @@ void FTheNewCarlaServer::Start(uint16_t Port)
void FTheNewCarlaServer::NotifyBeginEpisode(UCarlaEpisode &Episode) void FTheNewCarlaServer::NotifyBeginEpisode(UCarlaEpisode &Episode)
{ {
check(Pimpl != nullptr);
UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName()); UE_LOG(LogCarlaServer, Log, TEXT("New episode '%s' started"), *Episode.GetMapName());
Pimpl->Episode = &Episode; Pimpl->Episode = &Episode;
} }
void FTheNewCarlaServer::NotifyEndEpisode() void FTheNewCarlaServer::NotifyEndEpisode()
{ {
check(Pimpl != nullptr);
Pimpl->Episode = nullptr; Pimpl->Episode = nullptr;
} }
void FTheNewCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads) void FTheNewCarlaServer::AsyncRun(uint32 NumberOfWorkerThreads)
{ {
check(Pimpl != nullptr);
/// @todo Define better the number of threads each server gets. /// @todo Define better the number of threads each server gets.
auto RPCThreads = NumberOfWorkerThreads / 2u; auto RPCThreads = NumberOfWorkerThreads / 2u;
auto StreamingThreads = NumberOfWorkerThreads - RPCThreads; auto StreamingThreads = NumberOfWorkerThreads - RPCThreads;
@ -525,10 +514,18 @@ void FTheNewCarlaServer::RunSome(uint32 Milliseconds)
void FTheNewCarlaServer::Stop() void FTheNewCarlaServer::Stop()
{ {
check(Pimpl != nullptr);
Pimpl->Server.Stop(); Pimpl->Server.Stop();
} }
carla::rpc::Actor FTheNewCarlaServer::SerializeActor(FActorView View) const FDataStream FTheNewCarlaServer::OpenStream() const
{ {
return Pimpl->SerializeActor(View); check(Pimpl != nullptr);
return Pimpl->StreamingServer.MakeStream();
}
FDataMultiStream FTheNewCarlaServer::OpenMultiStream() const
{
check(Pimpl != nullptr);
return Pimpl->StreamingServer.MakeMultiStream();
} }

View File

@ -7,13 +7,10 @@
#pragma once #pragma once
#include "Carla/Actor/ActorView.h" #include "Carla/Actor/ActorView.h"
#include "Carla/Sensor/DataStream.h"
#include "CoreMinimal.h" #include "CoreMinimal.h"
#include <compiler/disable-ue4-macros.h>
#include <carla/rpc/Actor.h>
#include <compiler/enable-ue4-macros.h>
class UCarlaEpisode; class UCarlaEpisode;
class FTheNewCarlaServer class FTheNewCarlaServer
@ -36,8 +33,9 @@ public:
void Stop(); void Stop();
// This is necessary for serializing sensors properly. FDataStream OpenStream() const;
carla::rpc::Actor SerializeActor(FActorView View) const;
FDataMultiStream OpenMultiStream() const;
private: private: