diff --git a/Blueprints/Game/CarlaGameMode.uasset b/Blueprints/Game/CarlaGameMode.uasset deleted file mode 100644 index b62887a..0000000 Binary files a/Blueprints/Game/CarlaGameMode.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/2Wheeled/BP_Base2wheeledNew.uasset b/Blueprints/Vehicles/2Wheeled/BP_Base2wheeledNew.uasset deleted file mode 100644 index 66cd648..0000000 Binary files a/Blueprints/Vehicles/2Wheeled/BP_Base2wheeledNew.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/BP_EgoVehicle_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/BP_EgoVehicle_DReyeVR.uasset deleted file mode 100644 index 257fc9d..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/BP_EgoVehicle_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleAnim_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleAnim_DReyeVR.uasset deleted file mode 100644 index 853b195..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleAnim_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Mirrors/LeftMirror_DReyeVR_SM.uasset b/Blueprints/Vehicles/DReyeVR/Mirrors/LeftMirror_DReyeVR_SM.uasset deleted file mode 100644 index b7afbfc..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Mirrors/LeftMirror_DReyeVR_SM.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Mirrors/Mirror_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/Mirrors/Mirror_DReyeVR.uasset deleted file mode 100644 index 5cd7df4..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Mirrors/Mirror_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_Glass_SM.uasset b/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_Glass_SM.uasset deleted file mode 100644 index 1967b7b..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_Glass_SM.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_SM.uasset b/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_SM.uasset deleted file mode 100644 index 35f3947..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_SM.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Mirrors/RightMirror_DReyeVR_SM.uasset b/Blueprints/Vehicles/DReyeVR/Mirrors/RightMirror_DReyeVR_SM.uasset deleted file mode 100644 index 32e2864..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Mirrors/RightMirror_DReyeVR_SM.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashAttenuation.uasset b/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashAttenuation.uasset deleted file mode 100644 index 8d2f696..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashAttenuation.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineAttenuation.uasset b/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineAttenuation.uasset deleted file mode 100644 index 1612f83..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineAttenuation.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_DReyeVR.uasset deleted file mode 100644 index 86d5b08..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_PhysicsAsset_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_PhysicsAsset_DReyeVR.uasset deleted file mode 100644 index 60fdea9..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_PhysicsAsset_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_Skeleton_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_Skeleton_DReyeVR.uasset deleted file mode 100644 index 16c7d82..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_Skeleton_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_v2_DReyeVR.uasset b/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_v2_DReyeVR.uasset deleted file mode 100644 index 32a9907..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_v2_DReyeVR.uasset and /dev/null differ diff --git a/Blueprints/Vehicles/DReyeVR/Tires/BP_DReyeVR_Front.uasset b/Blueprints/Vehicles/DReyeVR/Tires/BP_DReyeVR_Front.uasset deleted file mode 100644 index 35eee43..0000000 Binary files a/Blueprints/Vehicles/DReyeVR/Tires/BP_DReyeVR_Front.uasset and /dev/null differ diff --git a/CHANGELOG.md b/CHANGELOG.md new file mode 100644 index 0000000..cf3c4db --- /dev/null +++ b/CHANGELOG.md @@ -0,0 +1,12 @@ +## DReyeVR 0.1.0 (for Carla 0.9.13) +- Replace existing `LevelScript` (`ADReyeVRLevel`) with `GameMode` (`ADReyeVRGameMode`). This allows us to not need to carry the (large) map blueprint files (ue4 binary) and we can use the vanilla Carla maps without modification. By default we spawn the EgoVehicle in the first of the recommended Carla locations, but this default behavior can be changed in the PythonAPI. For instance, you can delay spawning the EgoVehicle until via PythonAPI where you can specify the spawn transform. Existing functionality is preserved using `find_ego_vehicle` and `find_ego_sensor` which spawn the DReyeVR EgoVehicle if it does not exist in the world. +- Added `ADReyeVRFactory` as the Carla-esque spawning and registry functionality so the `EgoVehicle` and `EgoSensor` are spawned with the same "Factory" mechanisms as existing Carla vehicles/sensors/props/etc. +- Renamed DReyeVR-specific actors to be addressible in PythonAPI as `"harplab.dreyevr_$X.$id"` such as `"harplab.dreyevr_vehicle.model3"` and `"harplab.dreyevr_sensor.ego_sensor"`. Avoids conflicts with existing Carla PythonAPI scripts that may filter on `"vehicle.*"`. +- Moved all blueprint (`.uasset`) content out of the Carla content (which is now entirely untouched, no need to re-update) to a separate Content folder that lies in `/Game/Content/DReyeVR/` (renamed to support future DReyeVR blueprint changes without relying on Carla content). +- Adding check that SRanipal is within one of our recommended supported versions: `1.3.1.1`, `1.3.2.0`, & `1.3.3.0`. Also provided links in the documentation to download these versions. Additionally included a workaround for the old `patch-sranipal` which is now no longer needed. +- Added custom `LogDReyeVR` macros (`LOG`, `LOG_WARN`, `LOG_ERROR`) for improved logging with attached file, function, and line number to the message. Done in precompilation to avoid runtime performance overhead. +- Improved `make check` to ensure that a 1:1 file correspondence exists between Carla dest and DReyeVR source, and that all files have equal content. +- Improved vehicle dash with blinking turn signal and fixed bugs with inconsistent gear indicator. +- Fixed bugs and inconsistencies with replayer media control and special actions such as toggling reverse/turn signals in replay. +- Enabled cooking for `Town06` and `Town07` in package/shipping mode. +- Updated documentation and config file \ No newline at end of file diff --git a/Carla/Actor/ActorRegistry.cpp b/Carla/Actor/ActorRegistry.cpp deleted file mode 100644 index 8f20d96..0000000 --- a/Carla/Actor/ActorRegistry.cpp +++ /dev/null @@ -1,233 +0,0 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "Carla.h" -#include "Carla/Actor/ActorRegistry.h" - -#include "Carla/Game/Tagger.h" -#include "Carla/Traffic/TrafficLightBase.h" -#include "Carla/Util/BoundingBoxCalculator.h" -#include "Carla/Sensor/Sensor.h" - -namespace crp = carla::rpc; - -FActorRegistry::IdType FActorRegistry::ID_COUNTER = 0u; - -static FCarlaActor::ActorType FActorRegistry_GetActorType(const AActor *Actor) -{ - if (!Actor) - { - return FCarlaActor::ActorType::INVALID; - } - - if (nullptr != Cast(Actor)) - { - return FCarlaActor::ActorType::Vehicle; - } - else if (nullptr != Cast(Actor)) - { - return FCarlaActor::ActorType::Walker; - } - else if (nullptr != Cast(Actor)) - { - return FCarlaActor::ActorType::TrafficLight; - } - else if (nullptr != Cast(Actor)) - { - return FCarlaActor::ActorType::TrafficSign; - } - else if (nullptr != Cast(Actor)) - { - return FCarlaActor::ActorType::Sensor; - } - else - { - return FCarlaActor::ActorType::Other; - } -} - -static FString GetRelevantTagAsString(const TSet &SemanticTags) -{ - for (auto &&Tag : SemanticTags) - { - if ((Tag != crp::CityObjectLabel::None) && (Tag != crp::CityObjectLabel::Other)) - { - auto Str = ATagger::GetTagAsString(Tag).ToLower(); - return (Str.EndsWith(TEXT("s")) ? Str.LeftChop(1) : Str); - } - } - return TEXT("unknown"); -} - -FCarlaActor* FActorRegistry::Register(AActor &Actor, FActorDescription Description, IdType DesiredId) -{ - - FCarlaActor* CarlaActor = FindCarlaActor(DesiredId); - bool IsDormant = CarlaActor && (CarlaActor->IsDormant()); - if(IsDormant) - { - CarlaActor->TheActor = &Actor; - Actors.Add(DesiredId, &Actor); - Ids.Add(&Actor, DesiredId); - return CarlaActor; - } - - IdType Id = ++FActorRegistry::ID_COUNTER; - - if (DesiredId != 0 && Id != DesiredId) { - // check if the desired Id is free, then use it instead - if (!Actors.Contains(DesiredId)) - { - Id = DesiredId; - if (ID_COUNTER < Id) - ID_COUNTER = Id; - } - } - - Actors.Emplace(Id, &Actor); - if (Ids.Contains(&Actor)) - { - UE_LOG( - LogCarla, - Warning, - TEXT("This actor's memory address is already registered, " - "either you forgot to deregister the actor " - "or the actor was garbage collected.")); - } - Ids.Emplace(&Actor, Id); - - TSharedPtr View = - MakeCarlaActor(Id, Actor, std::move(Description), crp::ActorState::Active); - - TSharedPtr& Result = ActorDatabase.Emplace(Id, MoveTemp(View)); - - check(static_cast(Actors.Num()) == ActorDatabase.Num()); - return Result.Get(); -} - -void FActorRegistry::Deregister(IdType Id) -{ - FCarlaActor* CarlaActor = FindCarlaActor(Id); - - if(!CarlaActor) return; - - AActor *Actor = CarlaActor->GetActor(); - - ActorDatabase.Remove(Id); - Actors.Remove(Id); - Ids.Remove(Actor); - - CarlaActor->TheActor = nullptr; - - check(static_cast(Actors.Num()) == ActorDatabase.Num()); -} - -void FActorRegistry::Deregister(AActor *Actor) -{ - check(Actor != nullptr); - FCarlaActor* CarlaActor = FindCarlaActor(Actor); - check(CarlaActor->GetActor() == Actor); - Deregister(CarlaActor->GetActorId()); -} - -TSharedPtr FActorRegistry::MakeCarlaActor( - IdType Id, - AActor &Actor, - FActorDescription Description, - crp::ActorState InState) const -{ - auto Info = MakeShared(); - Info->Description = std::move(Description); - ATagger::GetTagsOfTaggedActor(Actor, Info->SemanticTags); - Info->BoundingBox = UBoundingBoxCalculator::GetActorBoundingBox(&Actor); - - if (Info->Description.Id.IsEmpty()) - { - // This is a fake actor, let's fake the id based on their semantic tags. - Info->Description.Id = TEXT("static.") + GetRelevantTagAsString(Info->SemanticTags); - } - - Info->SerializedData.id = Id; - Info->SerializedData.description = Info->Description; - Info->SerializedData.bounding_box = Info->BoundingBox; - Info->SerializedData.semantic_tags.reserve(Info->SemanticTags.Num()); - for (auto &&Tag : Info->SemanticTags) - { - using tag_t = decltype(Info->SerializedData.semantic_tags)::value_type; - Info->SerializedData.semantic_tags.emplace_back(static_cast(Tag)); - } - auto *Sensor = Cast(&Actor); - if (Sensor != nullptr) - { - const auto &Token = Sensor->GetToken(); - Info->SerializedData.stream_token = decltype(Info->SerializedData.stream_token)( - std::begin(Token.data), - std::end(Token.data)); - } - auto Type = FActorRegistry_GetActorType(&Actor); - TSharedPtr CarlaActor = - FCarlaActor::ConstructCarlaActor( - Id, &Actor, - std::move(Info), Type, - InState, Actor.GetWorld()); - return CarlaActor; -} - -void FActorRegistry::PutActorToSleep(FCarlaActor::IdType Id, UCarlaEpisode* CarlaEpisode) -{ - FCarlaActor* CarlaActor = FindCarlaActor(Id); - - // update id maps - Actors[Id] = nullptr; - AActor* Actor = CarlaActor->GetActor(); - if(Actor) - { - Ids.Remove(Actor); - } - - CarlaActor->PutActorToSleep(CarlaEpisode); - for (const FCarlaActor::IdType& ChildId : CarlaActor->GetChildren()) - { - PutActorToSleep(ChildId, CarlaEpisode); - } - // TODO: update id maps -} - -void FActorRegistry::WakeActorUp(FCarlaActor::IdType Id, UCarlaEpisode* CarlaEpisode) -{ - - FCarlaActor* CarlaActor = FindCarlaActor(Id); - CarlaActor->WakeActorUp(CarlaEpisode); - AActor* Actor = CarlaActor->GetActor(); - if (Actor) - { - // update ids - Actors[Id] = Actor; - Ids.Add(Actor, Id); - if (CarlaActor->GetParent()) - { - FCarlaActor* ParentView = FindCarlaActor(CarlaActor->GetParent()); - if (ParentView && !ParentView->IsDormant() && ParentView->GetActor()) - { - AActor* ParentActor = ParentView->GetActor(); - CarlaEpisode->AttachActors( - Actor, - ParentActor, - static_cast(CarlaActor->GetAttachmentType())); - } - else - { - UE_LOG(LogCarla, Error, TEXT("Failed to attach actor %d to %d during wake up"), Id, CarlaActor->GetParent()); - } - } - } - for (const FCarlaActor::IdType& ChildId : CarlaActor->GetChildren()) - { - WakeActorUp(ChildId, CarlaEpisode); - } -} diff --git a/Carla/Actor/DReyeVRCustomActor.cpp b/Carla/Actor/DReyeVRCustomActor.cpp index 83a0a7b..7f6e03b 100644 --- a/Carla/Actor/DReyeVRCustomActor.cpp +++ b/Carla/Actor/DReyeVRCustomActor.cpp @@ -76,7 +76,7 @@ bool ADReyeVRCustomActor::AssignSM(const FString &Path, UWorld *World) } else { - UE_LOG(LogTemp, Error, TEXT("Unable to create static mesh: %s"), *Path); + DReyeVR_LOG_ERROR("Unable to create static mesh: %s", *Path); return false; } ADReyeVRCustomActor::AllMeshCount++; @@ -98,14 +98,13 @@ void ADReyeVRCustomActor::AssignMat(const FString &MaterialPath) for (int i = 0; i < MAX_POSSIBLE_MATERIALS; i++) ActorMesh->SetMaterial(i, DynamicMat); else - UE_LOG(LogTemp, Error, TEXT("Unable to access material asset: %s"), *MaterialPath) + DReyeVR_LOG_ERROR("Unable to access material asset: %s", *MaterialPath) } void ADReyeVRCustomActor::Initialize(const FString &Name) { Internals.Name = Name; ADReyeVRCustomActor::ActiveCustomActors[TCHAR_TO_UTF8(*Name)] = this; - // UE_LOG(LogTemp, Log, TEXT("Initialized custom actor: %s"), *Name); } void ADReyeVRCustomActor::BeginPlay() @@ -122,7 +121,6 @@ void ADReyeVRCustomActor::BeginDestroy() void ADReyeVRCustomActor::Deactivate() { const std::string s = TCHAR_TO_UTF8(*Internals.Name); - // UE_LOG(LogTemp, Log, TEXT("Disabling custom actor: %s"), *Internals.Name); if (ADReyeVRCustomActor::ActiveCustomActors.find(s) != ADReyeVRCustomActor::ActiveCustomActors.end()) { ADReyeVRCustomActor::ActiveCustomActors.erase(s); @@ -136,7 +134,6 @@ void ADReyeVRCustomActor::Deactivate() void ADReyeVRCustomActor::Activate() { - // UE_LOG(LogTemp, Log, TEXT("Enabling custom actor: %s"), *Internals.Name); const std::string s = TCHAR_TO_UTF8(*Internals.Name); if (ADReyeVRCustomActor::ActiveCustomActors.find(s) == ADReyeVRCustomActor::ActiveCustomActors.end()) ADReyeVRCustomActor::ActiveCustomActors[s] = this; diff --git a/Carla/Carla.h b/Carla/Carla.h new file mode 100644 index 0000000..317a95d --- /dev/null +++ b/Carla/Carla.h @@ -0,0 +1,85 @@ +// Copyright 1998-2017 Epic Games, Inc. All Rights Reserved. + +// This file is included before any other file in every compile unit within the +// plugin. +#pragma once + + +#include "Util/NonCopyable.h" +#include "Logging/LogMacros.h" +#include "Modules/ModuleInterface.h" + +DECLARE_LOG_CATEGORY_EXTERN(LogCarla, Log, All); +DECLARE_LOG_CATEGORY_EXTERN(LogCarlaServer, Log, All); + +// DisplayName, GroupName, Third param is always Advanced. +// DECLARE_STATS_GROUP(TEXT("Carla"), STATGROUP_Carla, STATCAT_Advanced); +DECLARE_STATS_GROUP(TEXT("CarlaSensor"), STATGROUP_CarlaSensor, STATCAT_Advanced); + +//DECLARE_MEMORY_STAT(TEXT("CARLAMEMORY"), STATGROUP_CARLAMEMORY, STATCAT_Advanced) + +DECLARE_CYCLE_STAT(TEXT("Read RT"), STAT_CarlaSensorReadRT, STATGROUP_CarlaSensor); +DECLARE_CYCLE_STAT(TEXT("Copy Text"), STAT_CarlaSensorCopyText, STATGROUP_CarlaSensor); +DECLARE_CYCLE_STAT(TEXT("Buffer Copy"), STAT_CarlaSensorBufferCopy, STATGROUP_CarlaSensor); +DECLARE_CYCLE_STAT(TEXT("Stream Send"), STAT_CarlaSensorStreamSend, STATGROUP_CarlaSensor); + +// Options to compile with extra debug log. +#if WITH_EDITOR +// #define CARLA_AI_VEHICLES_EXTRA_LOG +// #define CARLA_AI_WALKERS_EXTRA_LOG +// #define CARLA_ROAD_GENERATOR_EXTRA_LOG +// #define CARLA_SERVER_EXTRA_LOG +// #define CARLA_TAGGER_EXTRA_LOG +// #define CARLA_WEATHER_EXTRA_LOG +#endif // WITH_EDITOR + +class FCarlaModule : public IModuleInterface +{ + void RegisterSettings(); + void UnregisterSettings(); + bool HandleSettingsSaved(); + void LoadChronoDll(); + +public: + + /** IModuleInterface implementation */ + virtual void StartupModule() override; + virtual void ShutdownModule() override; + +}; + +/////////////////////////////////////////////////////////////////////////////// +//////////////////////DReyeVR logging from CarlaUE4.h////////////////////////// +/////////////////////////////////////////////////////////////////////////////// + +// fancy logging that includes [filename::function:line] prefix +#ifndef __DReyeVR_LOG + +/// TODO: remove duplicate code! (Also defined in CarlaUE4.h) +constexpr inline const char *file_name_only(const char *path) +{ + // note since this is a constexpr function, it gets evaluated at compile time rather + // than runtime so there is no runtime performance overhead! +#ifdef _WIN32 + constexpr char os_sep = '\\'; +#else + constexpr char os_sep = '/'; +#endif + const char *filename_start = path; + while (*path) + { + if (*path++ == os_sep) // keep searching until found last os sep + filename_start = path; + } + return filename_start; // includes extension +} + + +#define __DReyeVR_LOG(msg, verbosity, ...) \ + UE_LOG(LogCarla, verbosity, TEXT("[%s::%s:%d] %s"), UTF8_TO_TCHAR(file_name_only(__FILE__)), \ + UTF8_TO_TCHAR(__func__), __LINE__, *FString::Printf(TEXT(msg), ##__VA_ARGS__)); +#endif + +#define DReyeVR_LOG(msg, ...) __DReyeVR_LOG(msg, Log, ##__VA_ARGS__); +#define DReyeVR_LOG_WARN(msg, ...) __DReyeVR_LOG(msg, Warning, ##__VA_ARGS__); +#define DReyeVR_LOG_ERROR(msg, ...) __DReyeVR_LOG(msg, Error, ##__VA_ARGS__); \ No newline at end of file diff --git a/Carla/Game/CarlaEpisode.h b/Carla/Game/CarlaEpisode.h deleted file mode 100644 index 4b27613..0000000 --- a/Carla/Game/CarlaEpisode.h +++ /dev/null @@ -1,362 +0,0 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#pragma once - -#include "Carla/Actor/ActorDispatcher.h" -#include "Carla/Recorder/CarlaRecorder.h" -#include "Carla/Sensor/WorldObserver.h" -#include "Carla/Server/CarlaServer.h" -#include "Carla/Settings/EpisodeSettings.h" -#include "Carla/Util/ActorAttacher.h" -#include "Carla/Weather/Weather.h" - -#include "GameFramework/Pawn.h" - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "CarlaEpisode.generated.h" - -/// A simulation episode. -/// -/// Each time the level is restarted a new episode is created. -UCLASS(BlueprintType, Blueprintable) -class CARLA_API UCarlaEpisode : public UObject -{ - GENERATED_BODY() - - // =========================================================================== - // -- Constructor ------------------------------------------------------------ - // =========================================================================== - -public: - - UCarlaEpisode(const FObjectInitializer &ObjectInitializer); - - // =========================================================================== - // -- Load a new episode ----------------------------------------------------- - // =========================================================================== - - /// Load a new map and start a new episode. - /// - /// If @a MapString is empty, the current map is reloaded. - UFUNCTION(BlueprintCallable) - bool LoadNewEpisode(const FString &MapString, bool ResetSettings = true); - - /// Load a new map generating the mesh from OpenDRIVE data and - /// start a new episode. - /// - /// If @a MapString is empty, it fails. - bool LoadNewOpendriveEpisode( - const FString &OpenDriveString, - const carla::rpc::OpendriveGenerationParameters &Params); - - // =========================================================================== - // -- Episode settings ------------------------------------------------------- - // =========================================================================== - - UFUNCTION(BlueprintCallable) - const FEpisodeSettings &GetSettings() const - { - return EpisodeSettings; - } - - UFUNCTION(BlueprintCallable) - void ApplySettings(const FEpisodeSettings &Settings); - - // =========================================================================== - // -- Retrieve info about this episode --------------------------------------- - // =========================================================================== - - /// Return the unique id of this episode. - auto GetId() const - { - return Id; - } - - /// Return the name of the map loaded in this episode. - UFUNCTION(BlueprintCallable) - const FString &GetMapName() const - { - return MapName; - } - - /// Game seconds since the start of this episode. - double GetElapsedGameTime() const - { - return ElapsedGameTime; - } - - /// Return the list of actor definitions that are available to be spawned this - /// episode. - UFUNCTION(BlueprintCallable) - const TArray &GetActorDefinitions() const - { - return ActorDispatcher->GetActorDefinitions(); - } - - /// Return the list of recommended spawn points for vehicles. - UFUNCTION(BlueprintCallable) - TArray GetRecommendedSpawnPoints() const; - - /// Return the GeoLocation point of the map loaded - const carla::geom::GeoLocation &GetGeoReference() const - { - return MapGeoReference; - } - - // =========================================================================== - // -- Retrieve special actors ------------------------------------------------ - // =========================================================================== - - UFUNCTION(BlueprintCallable) - APawn *GetSpectatorPawn() const - { - return Spectator; - } - - UFUNCTION(BlueprintCallable) - AWeather *GetWeather() const - { - return Weather; - } - - const FActorRegistry &GetActorRegistry() const - { - return ActorDispatcher->GetActorRegistry(); - } - - FActorRegistry &GetActorRegistry() - { - return ActorDispatcher->GetActorRegistry(); - } - - FCarlaActor* RegisterActor(AActor &Actor, FActorDescription ActorDescription, FString &Tags, FActorRegistry::IdType DesiredId = 0) - { - // first bind the already-spawned actor so it does not get spawned but found - auto FindFunctor = [&](const FTransform &Transform, const FActorDescription &Description) { - return FActorSpawnResult(&Actor); - }; - // need to create an FActorDefinition from our FActorDescription for some reason -_- - FActorDefinition ActorDefinition; - ActorDefinition.Id = ActorDescription.Id; - ActorDefinition.Class = ActorDescription.Class; - ActorDefinition.Tags = Tags; // list of comma-separated tags - ActorDispatcher->Bind(ActorDefinition, FindFunctor); - // take the UId from the ActorDefinition which has just been updated in ActorDispatcher.cpp:BindAndReturnUId - ActorDescription.UId = ActorDispatcher->GetActorDefinitions().Last().UId; - // then register this actor with the ActorDispatcher - return ActorDispatcher->RegisterActor(Actor, ActorDescription, DesiredId); - } - - - // =========================================================================== - // -- Actor look up methods -------------------------------------------------- - // =========================================================================== - - /// Find a Carla actor by id. - /// - /// If the actor is not found or is pending kill, the returned view is - /// invalid. - FCarlaActor* FindCarlaActor(FCarlaActor::IdType ActorId) - { - return ActorDispatcher->GetActorRegistry().FindCarlaActor(ActorId); - } - - /// Find the actor view of @a Actor. - /// - /// If the actor is not found or is pending kill, the returned view is - /// invalid. - FCarlaActor* FindCarlaActor(AActor *Actor) const - { - return ActorDispatcher->GetActorRegistry().FindCarlaActor(Actor); - } - - // =========================================================================== - // -- Actor handling methods ------------------------------------------------- - // =========================================================================== - - /// Spawns an actor based on @a ActorDescription at @a Transform. To properly - /// despawn an actor created with this function call DestroyActor. - /// - /// @return A pair containing the result of the spawn function and a view over - /// the actor and its properties. If the status is different of Success the - /// view is invalid. - TPair SpawnActorWithInfo( - const FTransform &Transform, - FActorDescription thisActorDescription, - FCarlaActor::IdType DesiredId = 0); - - /// Spawns an actor based on @a ActorDescription at @a Transform. - /// - /// @return the actor to be spawned - AActor* ReSpawnActorWithInfo( - const FTransform &Transform, - FActorDescription thisActorDescription) - { - FTransform NewTransform = Transform; - auto result = ActorDispatcher->ReSpawnActor(NewTransform, thisActorDescription); - if (Recorder->IsEnabled()) - { - // do something? - } - - return result; - } - - /// Spawns an actor based on @a ActorDescription at @a Transform. To properly - /// despawn an actor created with this function call DestroyActor. - /// - /// @return nullptr on failure. - /// - /// @note Special overload for blueprints. - UFUNCTION(BlueprintCallable) - AActor *SpawnActor( - const FTransform &Transform, - FActorDescription ActorDescription) - { - 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, - EAttachmentType InAttachmentType = EAttachmentType::Rigid); - - /// @copydoc FActorDispatcher::DestroyActor(AActor*) - UFUNCTION(BlueprintCallable) - bool DestroyActor(AActor *Actor) - { - FCarlaActor* CarlaActor = FindCarlaActor(Actor); - if (CarlaActor) - { - carla::rpc::ActorId ActorId = CarlaActor->GetActorId(); - return DestroyActor(ActorId); - } - return false; - } - - bool DestroyActor(carla::rpc::ActorId ActorId) - { - if (Recorder->IsEnabled()) - { - // recorder event - CarlaRecorderEventDel RecEvent{ActorId}; - Recorder->AddEvent(std::move(RecEvent)); - } - - return ActorDispatcher->DestroyActor(ActorId); - } - - void PutActorToSleep(carla::rpc::ActorId ActorId) - { - ActorDispatcher->PutActorToSleep(ActorId, this); - } - - void WakeActorUp(carla::rpc::ActorId ActorId) - { - ActorDispatcher->WakeActorUp(ActorId, this); - } - - // =========================================================================== - // -- Other methods ---------------------------------------------------------- - // =========================================================================== - - /// Create a serializable object describing the actor. - carla::rpc::Actor SerializeActor(FCarlaActor* CarlaActor) const; - - /// Create a serializable object describing the actor. - /// Can be used to serialized actors that are not in the registry - carla::rpc::Actor SerializeActor(AActor* Actor) const; - - // =========================================================================== - // -- Private methods and members -------------------------------------------- - // =========================================================================== - - ACarlaRecorder *GetRecorder() const - { - return Recorder; - } - - void SetRecorder(ACarlaRecorder *Rec) - { - Recorder = Rec; - } - - CarlaReplayer *GetReplayer() const - { - return Recorder->GetReplayer(); - } - - std::string StartRecorder(std::string name, bool AdditionalData); - - FIntVector GetCurrentMapOrigin() const { return CurrentMapOrigin; } - - void SetCurrentMapOrigin(const FIntVector& NewOrigin) { CurrentMapOrigin = NewOrigin; } - -private: - - friend class ACarlaGameModeBase; - friend class FCarlaEngine; - - void InitializeAtBeginPlay(); - - void EndPlay(); - - void RegisterActorFactory(ACarlaActorFactory &ActorFactory) - { - ActorDispatcher->Bind(ActorFactory); - } - - std::pair TryToCreateReplayerActor( - FVector &Location, - FVector &Rotation, - FActorDescription &ActorDesc, - unsigned int desiredId); - - bool SetActorSimulatePhysics(FCarlaActor &CarlaActor, bool bEnabled); - - void TickTimers(float DeltaSeconds) - { - ElapsedGameTime += DeltaSeconds; - } - - const uint64 Id = 0u; - - double ElapsedGameTime = 0.0; - - UPROPERTY(VisibleAnywhere) - FString MapName; - - UPROPERTY(VisibleAnywhere) - FEpisodeSettings EpisodeSettings; - - UPROPERTY(VisibleAnywhere) - UActorDispatcher *ActorDispatcher = nullptr; - - UPROPERTY(VisibleAnywhere) - APawn *Spectator = nullptr; - - UPROPERTY(VisibleAnywhere) - AWeather *Weather = nullptr; - - ACarlaRecorder *Recorder = nullptr; - - carla::geom::GeoLocation MapGeoReference; - - FIntVector CurrentMapOrigin; -}; diff --git a/Carla/Game/CarlaGameModeBase.h b/Carla/Game/CarlaGameModeBase.h new file mode 100644 index 0000000..f02d621 --- /dev/null +++ b/Carla/Game/CarlaGameModeBase.h @@ -0,0 +1,194 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#pragma once + +#include "CoreMinimal.h" +#include "GameFramework/GameModeBase.h" + +#include +#include +#include +#include +#include + +#include "Carla/Actor/CarlaActorFactory.h" +#include "Carla/Game/CarlaEpisode.h" +#include "Carla/Game/CarlaGameInstance.h" +#include "Carla/Game/TaggerDelegate.h" +#include "Carla/OpenDrive/OpenDrive.h" +#include "Carla/Recorder/CarlaRecorder.h" +#include "Carla/Sensor/SceneCaptureSensor.h" +#include "Carla/Settings/CarlaSettingsDelegate.h" +#include "Carla/Traffic/TrafficLightManager.h" +#include "Carla/Util/ObjectRegister.h" +#include "Carla/Weather/Weather.h" +#include "MapGen/LargeMapManager.h" + +#include "CarlaGameModeBase.generated.h" + +/// Base class for the CARLA Game Mode. +UCLASS(HideCategories=(ActorTick)) +class CARLA_API ACarlaGameModeBase : public AGameModeBase +{ + GENERATED_BODY() + +public: + + ACarlaGameModeBase(const FObjectInitializer& ObjectInitializer); + + const UCarlaEpisode &GetCarlaEpisode() const + { + check(Episode != nullptr); + return *Episode; + } + + const boost::optional& GetMap() const { + return Map; + } + + const FString GetFullMapPath() const; + + // get path relative to Content folder + const FString GetRelativeMapPath() const; + + UFUNCTION(Exec, Category = "CARLA Game Mode") + void DebugShowSignals(bool enable); + + UFUNCTION(BlueprintCallable, Category = "CARLA Game Mode") + ATrafficLightManager* GetTrafficLightManager(); + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable) + const TArray& GetSpawnPointsTransforms() const{ + return SpawnPointsTransforms; + } + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + TArray GetAllBBsOfLevel(uint8 TagQueried = 0xFF) const; + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + TArray GetEnvironmentObjects(uint8 QueriedTag = 0xFF) const + { + return ObjectRegister->GetEnvironmentObjects(QueriedTag); + } + + void EnableEnvironmentObjects(const TSet& EnvObjectIds, bool Enable); + + void EnableOverlapEvents(); + + void CheckForEmptyMeshes(); + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + void LoadMapLayer(int32 MapLayers); + + UFUNCTION(Category = "Carla Game Mode", BlueprintCallable, CallInEditor, Exec) + void UnLoadMapLayer(int32 MapLayers); + + UFUNCTION(Category = "Carla Game Mode") + ULevel* GetULevelFromName(FString LevelName); + + UFUNCTION(BlueprintCallable, Category = "Carla Game Mode") + void OnLoadStreamLevel(); + + UFUNCTION(BlueprintCallable, Category = "Carla Game Mode") + void OnUnloadStreamLevel(); + + ALargeMapManager* GetLMManager() const { + return LMManager; + } + + AActor* FindActorByName(const FString& ActorName); + + UTexture2D* CreateUETexture(const carla::rpc::TextureColor& Texture); + UTexture2D* CreateUETexture(const carla::rpc::TextureFloatColor& Texture); + + void ApplyTextureToActor( + AActor* Actor, + UTexture2D* Texture, + const carla::rpc::MaterialParameter& TextureParam); + + TArray GetNamesOfAllActors(); + +protected: + + void InitGame(const FString &MapName, const FString &Options, FString &ErrorMessage) override; + + void RestartPlayer(AController *NewPlayer) override; + + void BeginPlay() override; + + void EndPlay(const EEndPlayReason::Type EndPlayReason) override; + + void Tick(float DeltaSeconds) override; + + /// The class of Weather to spawn. + UPROPERTY(Category = "CARLA Game Mode", EditAnywhere) + TSubclassOf WeatherClass; + + /// List of actor spawners that will be used to define and spawn the actors + /// available in game. + UPROPERTY(Category = "CARLA Game Mode", EditAnywhere) + TSet> ActorFactories; + +private: + + void SpawnActorFactories(); + + void StoreSpawnPoints(); + + void GenerateSpawnPoints(); + + void ParseOpenDrive(); + + void RegisterEnvironmentObjects(); + + void ConvertMapLayerMaskToMapNames(int32 MapLayer, TArray& OutLevelNames); + + void OnEpisodeSettingsChanged(const FEpisodeSettings &Settings); + + UPROPERTY() + UCarlaGameInstance *GameInstance = nullptr; + + UPROPERTY() + UTaggerDelegate *TaggerDelegate = nullptr; + + UPROPERTY() + UCarlaSettingsDelegate *CarlaSettingsDelegate = nullptr; + + UPROPERTY() + UCarlaEpisode *Episode = nullptr; + + UPROPERTY() + ACarlaRecorder *Recorder = nullptr; + + UPROPERTY() + UObjectRegister* ObjectRegister = nullptr; + + UPROPERTY() + TArray SpawnPointsTransforms; + + UPROPERTY() + TArray ActorFactoryInstances; + + UPROPERTY() + ATrafficLightManager* TrafficLightManager = nullptr; + + ALargeMapManager* LMManager = nullptr; + + FDelegateHandle OnEpisodeSettingsChangeHandle; + + boost::optional Map; + + int PendingLevelsToLoad = 0; + int PendingLevelsToUnLoad = 0; + + bool ReadyToRegisterObjects = false; + + // We keep a global uuid to allow the load/unload layer methods to be called + // in the same tick + int32 LatentInfoUUID = 0; + +}; diff --git a/Carla/Recorder/CarlaRecorder.cpp b/Carla/Recorder/CarlaRecorder.cpp index 18b6d97..327ab7e 100644 --- a/Carla/Recorder/CarlaRecorder.cpp +++ b/Carla/Recorder/CarlaRecorder.cpp @@ -724,30 +724,4 @@ void ACarlaRecorder::CreateRecorderEventAdd( // Bounding box in local coordinates AddActorBoundingBox(CarlaActor); } -} - -// DReyeVR replayer functions -void ACarlaRecorder::RecPlayPause() -{ - Replayer.PlayPause(); -} - -void ACarlaRecorder::RecFastForward() -{ - Replayer.Advance(1.f); -} - -void ACarlaRecorder::RecRewind() -{ - Replayer.Advance(-1.f); -} - -void ACarlaRecorder::RecRestart() -{ - Replayer.Restart(); -} - -void ACarlaRecorder::IncrTimeFactor(const float Amnt_s) -{ - Replayer.IncrTimeFactor(Amnt_s); } \ No newline at end of file diff --git a/Carla/Recorder/CarlaRecorder.h b/Carla/Recorder/CarlaRecorder.h index b471866..5545963 100644 --- a/Carla/Recorder/CarlaRecorder.h +++ b/Carla/Recorder/CarlaRecorder.h @@ -169,13 +169,6 @@ class CARLA_API ACarlaRecorder : public AActor void Ticking(float DeltaSeconds); - // DReyeVR replayer functions - void RecPlayPause(); - void RecFastForward(); - void RecRewind(); - void RecRestart(); - void IncrTimeFactor(const float Amnt); - private: bool Enabled; // enabled or not diff --git a/Carla/Recorder/CarlaReplayer.cpp b/Carla/Recorder/CarlaReplayer.cpp index 2d2cf2a..61a8568 100644 --- a/Carla/Recorder/CarlaReplayer.cpp +++ b/Carla/Recorder/CarlaReplayer.cpp @@ -827,7 +827,7 @@ void CarlaReplayer::ProcessFrameByFrame() // have the vehicle camera take a screenshot to record the replay ADReyeVRSensor::GetDReyeVRSensor()->TakeScreenshot(); else - UE_LOG(LogTemp, Error, TEXT("No DReyeVR sensor available!")); + DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); // progress to the next frame if (SyncCurrentFrameId < FrameStartTimes.size() - 1) @@ -836,12 +836,7 @@ void CarlaReplayer::ProcessFrameByFrame() Stop(); } -void CarlaReplayer::PlayPause() -{ - Paused = !Paused; -} - -void CarlaReplayer::Restart() +void CarlaReplayer::Restart() { // Use same params as they were initially ReplayFile(LastReplay.Filename, LastReplay.TimeStart, @@ -889,11 +884,4 @@ void CarlaReplayer::Advance(const float Amnt) Restart(); ProcessToTime(DesiredTime, true); } -} - -void CarlaReplayer::IncrTimeFactor(const float Amnt_s) -{ - double NewTimeFactor = FMath::Clamp(TimeFactor + Amnt_s, 0.0, 4.0); // min of paused, max of 4x - UE_LOG(LogTemp, Log, TEXT("Time factor: %.3fx -> %.3fx"), TimeFactor, NewTimeFactor); - SetTimeFactor(NewTimeFactor); } \ No newline at end of file diff --git a/Carla/Recorder/CarlaReplayer.h b/Carla/Recorder/CarlaReplayer.h index 628ff34..9002013 100644 --- a/Carla/Recorder/CarlaReplayer.h +++ b/Carla/Recorder/CarlaReplayer.h @@ -26,7 +26,7 @@ class UCarlaEpisode; -class CarlaReplayer +class CARLA_API CarlaReplayer { #pragma pack(push, 1) struct Header @@ -95,16 +95,18 @@ class CarlaReplayer void Tick(float Time); // DReyeVR replayer functions - void PlayPause(); - void Restart(); - void Advance(const float Amnt); - void IncrTimeFactor(const float Amnt_s); + void PlayPause() + { + Paused = !Paused; + } + + void Restart(); // calls ReplayFile which is implemented in .cpp + + void Advance(const float Amnt); // long function implemented in .cpp file void SetSyncMode(bool bSyncModeIn) { bReplaySync = bSyncModeIn; - if (bReplaySync) - UE_LOG(LogTemp, Warning, TEXT("Replay operating in frame-wise sync mode")); } private: diff --git a/Carla/Recorder/CarlaReplayerHelper.cpp b/Carla/Recorder/CarlaReplayerHelper.cpp index 210fc25..7311ec2 100644 --- a/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Carla/Recorder/CarlaReplayerHelper.cpp @@ -482,7 +482,7 @@ bool CarlaReplayerHelper::ProcessReplayerFinish(bool bApplyAutopilot, bool bIgno if (ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld())) ADReyeVRSensor::GetDReyeVRSensor()->StopReplaying(); else - UE_LOG(LogTemp, Error, TEXT("No DReyeVR sensor available!")); + DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); return true; } @@ -491,7 +491,7 @@ template void CarlaReplayerHelper::ProcessReplayerDReyeVRData(const if (ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld())) ADReyeVRSensor::GetDReyeVRSensor()->UpdateData(DReyeVRDataInstance.Data, Per); else - UE_LOG(LogTemp, Error, TEXT("No DReyeVR sensor available!")); + DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); } void CarlaReplayerHelper::SetActorVelocity(FCarlaActor *CarlaActor, FVector Velocity) diff --git a/Carla/Sensor/DReyeVRSensor.cpp b/Carla/Sensor/DReyeVRSensor.cpp index 13ad7cf..a93e6c5 100644 --- a/Carla/Sensor/DReyeVRSensor.cpp +++ b/Carla/Sensor/DReyeVRSensor.cpp @@ -25,9 +25,7 @@ ADReyeVRSensor::ADReyeVRSensor(const FObjectInitializer &ObjectInitializer) : Su FActorDefinition ADReyeVRSensor::GetSensorDefinition() { // What our sensor is going to be called: - auto Definition = UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition( - TEXT("DReyeVR"), // folder directory "dreyevr" - TEXT("DReyeVRSensor")); // sensor name "dreyevrsensor" + auto Definition = UActorBlueprintFunctionLibrary::MakeGenericSensorDefinition(TEXT("dreyevr"), TEXT("sensor_base")); /// NOTE: only has EActorAttributeType for bool, int, float, string, and RGBColor // see /Plugins/Carla/Source/Carla/Actor/ActorAttribute.h for the whole list @@ -45,11 +43,13 @@ void ADReyeVRSensor::Set(const FActorDescription &Description) void ADReyeVRSensor::SetOwner(AActor *Owner) { - check(Owner != nullptr); Super::SetOwner(Owner); - // Set Transform to the same as the Owner - SetActorLocation(Owner->GetActorLocation()); - SetActorRotation(Owner->GetActorRotation()); + if (Owner != nullptr) + { + // Set Transform to the same as the Owner + SetActorLocation(Owner->GetActorLocation()); + SetActorRotation(Owner->GetActorRotation()); + } } void ADReyeVRSensor::BeginPlay() @@ -232,7 +232,7 @@ class ADReyeVRSensor *ADReyeVRSensor::GetDReyeVRSensor(class UWorld *World) // s if (World != nullptr && World != ADReyeVRSensor::sWorld) { // check if the world has been reloaded and we need to refresh our internal pointers - UE_LOG(LogTemp, Warning, TEXT("Detected world change! Invalidating cached data")); + DReyeVR_LOG_WARN("Detected world change! Invalidating cached data"); ADReyeVRSensor::sWorld = World; ADReyeVRSensor::DReyeVRSensorPtr = nullptr; ADReyeVRCustomActor::ActiveCustomActors.clear(); @@ -254,14 +254,14 @@ class ADReyeVRSensor *ADReyeVRSensor::GetDReyeVRSensor(class UWorld *World) // s } if (FoundActors.Num() > 1) { - UE_LOG(LogTemp, Error, TEXT("Multiple DReyeVR sensors active in the world! Not supported.")); + DReyeVR_LOG_ERROR("Multiple DReyeVR sensors active in the world! Not supported."); } } // check if DReyeVR sensor was found if (ADReyeVRSensor::DReyeVRSensorPtr == nullptr) { - UE_LOG(LogTemp, Error, TEXT("No DReyeVRSensor found in the world!")); + DReyeVR_LOG_ERROR("No DReyeVRSensor found in the world!"); } return DReyeVRSensorPtr; diff --git a/Carla/Sensor/DReyeVRSensor.h b/Carla/Sensor/DReyeVRSensor.h index 482465b..55451bc 100644 --- a/Carla/Sensor/DReyeVRSensor.h +++ b/Carla/Sensor/DReyeVRSensor.h @@ -51,7 +51,7 @@ class CARLA_API ADReyeVRSensor : public ASensor virtual void TakeScreenshot() { /// TODO: make this a pure virtual function (abstract class) - UE_LOG(LogTemp, Warning, TEXT("Not implemented! Implement in EgoSensor!")); + DReyeVR_LOG_WARN("Not implemented! Implement in EgoSensor!"); }; static class ADReyeVRSensor *GetDReyeVRSensor(class UWorld *World = nullptr); diff --git a/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Carla/Vehicle/CarlaWheeledVehicle.cpp index 7da8c4c..3562246 100644 --- a/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -193,7 +193,7 @@ void ACarlaWheeledVehicle::ConstructSounds() // add all sounds here static ConstructorHelpers::FObjectFinder EngineCueObj( - TEXT("SoundCue'/Game/Carla/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'")); + TEXT("SoundCue'/Game/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'")); EngineRevSound = CreateDefaultSubobject(FName("EngineRevSound")); EngineRevSound->SetupAttachment(GetRootComponent()); // attach to self EngineRevSound->bAutoActivate = true; // start playing on begin @@ -204,7 +204,7 @@ void ACarlaWheeledVehicle::ConstructSounds() check(EngineRevSound != nullptr); static ConstructorHelpers::FObjectFinder CarCrashCue( - TEXT("SoundCue'/Game/Carla/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashCue.CrashCue'")); + TEXT("SoundCue'/Game/DReyeVR/Sounds/Crash/CrashCue.CrashCue'")); CrashSound = CreateDefaultSubobject(TEXT("CarCrash")); CrashSound->SetupAttachment(GetRootComponent()); CrashSound->bAutoActivate = false; diff --git a/CarlaUE4/CarlaUE4.Build.cs b/CarlaUE4/CarlaUE4.Build.cs new file mode 100644 index 0000000..a42e7fb --- /dev/null +++ b/CarlaUE4/CarlaUE4.Build.cs @@ -0,0 +1,84 @@ +// Fill out your copyright notice in the Description page of Project Settings. + +using System; +using System.IO; +using UnrealBuildTool; + +public class CarlaUE4 : ModuleRules +{ + private bool IsWindows(ReadOnlyTargetRules Target) + { + return (Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32); + } + public CarlaUE4(ReadOnlyTargetRules Target) : base(Target) + { + PrivatePCHHeaderFile = "CarlaUE4.h"; + ShadowVariableWarningLevel = WarningLevel.Off; // -Wno-shadow + + // include LibCarla so we can #include headers + string LibCarlaIncludePath = + Path.GetFullPath(Path.Combine(ModuleDirectory, "..", "..", "..", "..", "LibCarla", "source")); + PublicIncludePaths.Add(LibCarlaIncludePath); + PrivateIncludePaths.Add(LibCarlaIncludePath); + + PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "UMG" }); + + if (Target.Type == TargetType.Editor) + { + PublicDependencyModuleNames.AddRange(new string[] { "UnrealEd" }); + } + else + { + // only build this carla exception in package mode + PublicDefinitions.Add("NO_DREYEVR_EXCEPTIONS"); + } + + // Add module for SteamVR support with UE4 + PublicDependencyModuleNames.AddRange(new string[] { "HeadMountedDisplay" }); + + if (IsWindows(Target)) + { + bEnableExceptions = true; // enable unwind semantics for C++-style exceptions + } + + //////////////////////////////////////////////////////////////////////////////////// + // Edit these variables to enable/disable features of DReyeVR + bool UseSRanipalPlugin = true; + bool UseLogitechPlugin = true; + bool UseFoveatedRender = false; // currently only supported in editor + //////////////////////////////////////////////////////////////////////////////////// + + if (!IsWindows(Target)) + { + // adjust definitions so they are OS-compatible + UseSRanipalPlugin = false; // SRanipal only works on Windows + UseLogitechPlugin = false; // LogitechWheelPlugin also only works on Windows + UseFoveatedRender = false; // Vive VRS plugin requires engine fork + } + + // Add these preprocessor definitions to code + PublicDefinitions.Add("USE_SRANIPAL_PLUGIN=" + (UseSRanipalPlugin ? "true" : "false")); + PublicDefinitions.Add("USE_LOGITECH_PLUGIN=" + (UseLogitechPlugin ? "true" : "false")); + PublicDefinitions.Add("USE_FOVEATED_RENDER=" + (UseFoveatedRender ? "true" : "false")); + + // Add plugin dependencies + if (UseSRanipalPlugin) + { + PrivateDependencyModuleNames.AddRange(new string[] { "SRanipal", "SRanipalEye" }); + PrivateIncludePathModuleNames.AddRange(new string[] { "SRanipal", "SRanipalEye" }); + } + + if (UseLogitechPlugin) + { + PrivateDependencyModuleNames.AddRange(new string[] { "LogitechWheelPlugin" }); + } + + if (UseFoveatedRender) + { + // Add VRS plugin and and EyeTracker dependencies + PublicDependencyModuleNames.AddRange(new string[] { "EyeTracker", "VRSPlugin" }); + } + + PrivateDependencyModuleNames.AddRange(new string[] { "ImageWriteQueue" }); + } +} diff --git a/CarlaUE4/CarlaUE4.cpp b/CarlaUE4/CarlaUE4.cpp new file mode 100644 index 0000000..f4af712 --- /dev/null +++ b/CarlaUE4/CarlaUE4.cpp @@ -0,0 +1,7 @@ +// Fill out your copyright notice in the Description page of Project Settings. + +#include "CarlaUE4.h" + +IMPLEMENT_PRIMARY_GAME_MODULE(FDefaultGameModuleImpl, CarlaUE4, "CarlaUE4"); + +DEFINE_LOG_CATEGORY(LogDReyeVR); diff --git a/CarlaUE4/CarlaUE4.h b/CarlaUE4/CarlaUE4.h new file mode 100644 index 0000000..cdb9a4b --- /dev/null +++ b/CarlaUE4/CarlaUE4.h @@ -0,0 +1,36 @@ +// Fill out your copyright notice in the Description page of Project Settings. + +#pragma once + +#include "Engine.h" + +#include "Util/NonCopyable.h" + +DECLARE_LOG_CATEGORY_EXTERN(LogDReyeVR, Log, All); + +constexpr inline const char *file_name_only(const char *path) +{ + // note since this is a constexpr function, it gets evaluated at compile time rather + // than runtime so there is no runtime performance overhead! +#ifdef _WIN32 + constexpr char os_sep = '\\'; +#else + constexpr char os_sep = '/'; +#endif + const char *filename_start = path; + while (*path) + { + if (*path++ == os_sep) // keep searching until found last os sep + filename_start = path; + } + return filename_start; // includes extension +} + +// fancy logging that includes [filename::function:line] prefix +#define __DReyeVR_LOG(msg, verbosity, ...) \ + UE_LOG(LogDReyeVR, verbosity, TEXT("[%s::%s:%d] %s"), UTF8_TO_TCHAR(file_name_only(__FILE__)), \ + UTF8_TO_TCHAR(__func__), __LINE__, *FString::Printf(TEXT(msg), ##__VA_ARGS__)); + +#define LOG(msg, ...) __DReyeVR_LOG(msg, Log, ##__VA_ARGS__); +#define LOG_WARN(msg, ...) __DReyeVR_LOG(msg, Warning, ##__VA_ARGS__); +#define LOG_ERROR(msg, ...) __DReyeVR_LOG(msg, Error, ##__VA_ARGS__); diff --git a/Configs/CarlaUE4.uproject b/Config/CarlaUE4.uproject similarity index 100% rename from Configs/CarlaUE4.uproject rename to Config/CarlaUE4.uproject diff --git a/Config/DReyeVRConfig.ini b/Config/DReyeVRConfig.ini new file mode 100644 index 0000000..d23a593 --- /dev/null +++ b/Config/DReyeVRConfig.ini @@ -0,0 +1,130 @@ +# NOTE: this is a weird config file bc it is custom written for DReyeVR +# - use hashtags '#' for comments (supports inline) + +# some serialization formats: +# FVector: (X=..., Y=..., Z=...) (along XYZ-axes) +# FRotator: (R=..., P=..., Y=...) (for roll, pitch, yaw) +# FTransform: (FVector | FRotator | FVector) = (X=..., Y=..., Z=... | R=..., P=..., Y=... | X=..., Y=..., Z=...) +# bool: True or False + +[EgoVehicle] +DashLocation=(X=110.0, Y=0.0, Z=105.0) # position offset of dash in vehicle +SpeedometerInMPH=True # set to False to use KPH +EnableTurnSignalAction=True # True to enable turn signal animation (& sound), else false +TurnSignalDuration=3.0 # time (in s) that the turn signals stay on for +DrawDebugEditor=False # draw debug lines/sphere for eye gaze in the editor + +[CameraPose] +# location & rotation of camera relative to vehicle (location units in cm, rotation in degrees) +StartingPose="DriversSeat" # starting position of camera in vehicle (on begin play) +# NOTE: we assume the location is suffix'd with "Loc" and rotation is suffixed with "Rot" +DriversSeatLoc=(X=20.0, Y=-40.0, Z=120.0) # location of first-person camera +DriversSeatRot=(R=0.0, P=0.0, Y=0.0) # rotation of first-person camera +FrontLoc=(X=250.0, Y=0.0, Z=90.0) # location of camera in front of vehicle +FrontRot=(R=0.0, P=0.0, Y=0.0) # rotation of camera in front of vehicle +BirdsEyeViewLoc=(X=0.0, Y=0.0, Z=820.0) # location of camera from top-down bird's eye view +BirdsEyeViewRot=(R=0.0, P=270.0, Y=0.0) # rotation of camera from top-down bird's eye view +ThirdPersonLoc=(X=-500.0, Y=0.0, Z=380.0) # location of camera in third-person view +ThirdPersonRot=(R=0.0, P=330.0, Y=0.0) # rotation of camera in third-person view + +[CameraParams] +FieldOfView=90.0 # horizontal field of view (only in stereo camera => NOT VR) +ScreenPercentage=100 # 100% is native resolution, increase for supersampling, decrease for subsampling +# all the intensities range from [0 (off) to 1 (maximum)] +MotionBlurIntensity=0 # how much motion blur in the camera +VignetteIntensity=0 # how intense the vignetting is (darkened corners) +BloomIntensity=0 # how intense the bloom is +SceneFringeIntensity=0 # how intense the SceneFringe is +LensFlareIntensity=0 # how intense the lens flares are +GrainIntensity=0 # how intense the grain is + +[Mirrors] +# NOTE: mirrors are HIGHLY performance intensive in DReyeVR. If you care more about smooth FPS +# you'll want to set the "XMirrorEnabled" flag to False for each of the 3 mirrors below!! + +# rear view mirror +RearMirrorEnabled=True +RearMirrorChassisTransform=(X=48.0, Y=0.0, Z=123.0 | R=0.0, P=0.0, Y=25.06 | X=1.0, Y=1.0, Z=1.0) +RearMirrorTransform=(X=-0.5, Y=0.0, Z=0.0 | R=0.0, P=1.0, Y=0.0 | X=0.9, Y=0.98, Z=0.9) +RearReflectionTransform=(X=-7, Y=0.0, Z=0.0 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.007, Z=1.0) +RearScreenPercentage=85 # used very frequently (85% quality) +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=62.0, Y=-98.0, Z=105.5 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) +LeftReflectionTransform=(X=0, Y=0, Z=-3.0 | R=43.2, P=81, Y=22.5 | X=0.003, Y=0.005, Z=1.0) +LeftScreenPercentage=65 # used quite a bit (65% quality) +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=62, Y=98, Z=100.5 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) +RightReflectionTransform=(X=0.0, Y=0.0, Z=2.22 | R=-1, P=90.0, Y=21.6 | X=0.003, Y=0.005, Z=1.0) +RightScreenPercentage=50 # used very rarely if ever (50% quality) + +[SteeringWheel] +InitLocation=(X=85.0, Y=-40.0, Z=85.0) # position of the steering wheel in the vehicle +InitRotation=(R=0.0, P=-10.0, Y=0.0) # tilt of the steering wheel at rest +MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) +MaxSteerVelocity=90 # maximum velocity (degrees per second) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) + +[EgoSensor] +StreamSensorData=True # Set to False to skip streaming sensor data (for PythonAPI) on every tick +MaxTraceLenM=1000.0 # maximum trace length (in meters) to use for world-hit point calculation +DrawDebugFocusTrace=True # draw the debug focus trace & hit point in editor + +[VehicleInputs] +ScaleSteeringDamping=0.6 +ScaleThrottleInput=1.0 +ScaleBrakeInput=1.0 +InvertMouseY=False +ScaleMouseY=1.0 +ScaleMouseX=1.0 + +[EgoVehicleHUD] +HUDScaleVR=6 # scale all HUD elements in VR mode only +DrawFPSCounter=True # draw's FPS (frames per second) in top right corner of flat screen +DrawFlatReticle=True # reticle in flat-screen mode +DrawGaze=False # draw debug gaze lines on flat-screen hud +DrawSpectatorReticle=True # reticle in spectator mode during vr (VR spectator HUD only) +ReticleSize=100 # (percent) diameter of reticle (thickness also scales) +EnableSpectatorScreen=True # whether or not to enable the flat-screen spectator when in VR + +[Game] +AutomaticallySpawnEgo=True # use to spawn EgoVehicle, o/w defaults to spectator & Ego can be spawned via PythonAPI +DoSpawnEgoVehicleTransform=False # True uses the SpawnEgoVehicleTransform below, False uses Carla's own spawn points +SpawnEgoVehicleTransform=(X=3010, Y=390, Z=0.0 | R=0, P=0.0, Y=0 | X=1.0, Y=1.0, Z=1.0) # !! This is only for Town03 !! +EgoVolumePercent=100 +NonEgoVolumePercent=100 +AmbientVolumePercent=20 + +[Replayer] +CameraFollowHMD=True # Whether or not to have the camera pose follow the recorded HMD pose + +# Enable or disable replay interpolation with *ReplayInterpolation* +# True is the default CARLA behavior, this may cause replay timesteps in between ground truth data +# False ensures that every frame will match exactly with the recorded data at the exact timesteps (no interpolation) +ReplayInterpolation=False # see above + +# for taking per-frame screen capture during replay (for post-hoc analysis) +RecordFrames=True # additionally capture camera screenshots on replay tick (requires no replay interpolation!) +RecordAllShaders=False # Enable or disable rendering the scene with additional (beyond RGB) shaders such as depth +RecordAllPoses=False # Enable or disable rendering the scene with all camera poses (beyond driver's seat) +FileFormatJPG=True # either JPG or PNG +LinearGamma=True # force linear gamme for frame capture render (recommended) +FrameWidth=1280 # resolution x for screenshot +FrameHeight=720 # resolution y for screenshot +FrameDir="FrameCap" # directory name for screenshot +FrameName="tick" # title of screenshot (differentiated via tick-suffix) + +# for Logitech hardware of the racing sim +[Hardware] +DeviceIdx=0 # Device index of the hardware (Logitech has 2, can be 0 or 1) +LogUpdates=False # whether or not to print debug messages + +# VariableRateShading is an experimental attempt to squeeze more performance out of DReyeVR +# by reducing rendering quality of the scene in the periphery, which we should know from the real-time +# gaze tracking. Unfortunately the development to port HTC Vive's VariableRateShading is still WIP and +# currently only works in the Editor, not in a shipping/package game where it'd be most useful. We are +# actively working on this feature and will enable VRS once it is fully supported. +[VariableRateShading] # disabled by default (would need to enable via CarlaUE4.Build.cs flag) +Enabled=True # currently only works in Editor mode (but enabled in Build.cs settings) +UsingEyeTracking=True # use eye tracking for foveated rendering if available diff --git a/Content/Default.Package.json b/Config/Default.Package.json similarity index 96% rename from Content/Default.Package.json rename to Config/Default.Package.json index ed9b9ca..3dfa4d9 100644 --- a/Content/Default.Package.json +++ b/Config/Default.Package.json @@ -447,23 +447,23 @@ }, { "name": "DReyeVR_sign_left", - "path": "/Game/DReyeVR/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_left.SM_DReyeVR_sign_left", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_left.SM_DReyeVR_sign_left", "size": "Big" }, { "name": "DReyeVR_sign_straight", - "path": "/Game/DReyeVR/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_straight.SM_DReyeVR_sign_straight", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_straight.SM_DReyeVR_sign_straight", "size": "Big" }, { "name": "DReyeVR_sign_right", - "path": "/Game/DReyeVR/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_right.SM_DReyeVR_sign_right", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_right.SM_DReyeVR_sign_right", "size": "Big" }, { "name": "DReyeVR_sign_goal", - "path": "/Game/DReyeVR/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_goal.SM_DReyeVR_sign_goal", + "path": "/Game/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_goal.SM_DReyeVR_sign_goal", "size": "Big" } ] -} +} \ No newline at end of file diff --git a/Configs/DefaultEngine.ini b/Config/DefaultEngine.ini similarity index 95% rename from Configs/DefaultEngine.ini rename to Config/DefaultEngine.ini index ba9b1de..ca91e98 100644 --- a/Configs/DefaultEngine.ini +++ b/Config/DefaultEngine.ini @@ -10,12 +10,18 @@ AppliedDefaultGraphicsPerformance=Maximum [/Script/EngineSettings.GameMapsSettings] EditorStartupMap=/Game/Carla/Maps/Town03.Town03 +LocalMapOptions= +TransitionMap=/Game/Carla/Maps/Town03.Town03 +bUseSplitscreen=True +TwoPlayerSplitscreenLayout=Horizontal +ThreePlayerSplitscreenLayout=FavorTop +FourPlayerSplitscreenLayout=Grid +bOffsetPlayerGamepadIds=False +GameInstanceClass=/Script/Carla.CarlaGameInstance GameDefaultMap=/Game/Carla/Maps/Town03.Town03 ServerDefaultMap=/Game/Carla/Maps/Town03.Town03 -GlobalDefaultGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C -GameInstanceClass=/Script/Carla.CarlaGameInstance -TransitionMap=/Game/Carla/Maps/Town03.Town03 -GlobalDefaultServerGameMode=/Game/Carla/Blueprints/Game/CarlaGameMode.CarlaGameMode_C +GlobalDefaultGameMode=/Script/CarlaUE4.DReyeVRGameMode +GlobalDefaultServerGameMode=/Script/CarlaUE4.DReyeVRGameMode [/Script/Engine.RendererSettings] r.DefaultFeature.MotionBlur=True @@ -61,6 +67,27 @@ OcclusionPlugin= +TargetedRHIs=SF_VULKAN_SM5 +TargetedRHIs=GLSL_430 +[/Script/IOSRuntimeSettings.IOSRuntimeSettings] +bSupportsPortraitOrientation=False +bSupportsUpsideDownOrientation=False +bSupportsLandscapeLeftOrientation=True +PreferredLandscapeOrientation=LandscapeLeft + +[/Script/MacTargetPlatform.MacTargetSettings] +-TargetedRHIs=SF_METAL_SM5 ++TargetedRHIs=SF_METAL_SM5 +MaxShaderLanguageVersion=3 +UseFastIntrinsics=False +EnableMathOptimisations=True +AudioSampleRate=0 +AudioCallbackBufferFrameSize=0 +AudioNumBuffersToEnqueue=0 +AudioMaxChannels=0 +AudioNumSourceWorkers=0 +SpatializationPlugin= +ReverbPlugin= +OcclusionPlugin= + [/Script/Engine.PhysicsSettings] DefaultGravityZ=-980.000000 DefaultTerminalVelocity=4000.000000 @@ -129,6 +156,24 @@ DefaultGraphicsRHI=DefaultGraphicsRHI_DX11 +Profiles=(Name="NoCollision",CollisionEnabled=NoCollision,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="Visibility",Response=ECR_Ignore),(Channel="Camera",Response=ECR_Ignore)),HelpMessage="No collision") +Profiles=(Name="BlockAll",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=,HelpMessage="WorldStatic object that blocks all actors by default. All new custom channels will use its own default response. ") +Profiles=(Name="OverlapAll",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldStatic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldStatic object that overlaps all actors by default. All new custom channels will use its own default response. ") +-ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") +-ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") +-ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") +-ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") +-ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") ++ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") ++ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") ++ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") ++ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") ++ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") +-CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") +-CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") +-CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") +-CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") ++CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") ++CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") ++CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") ++CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") +Profiles=(Name="BlockAllDynamic",CollisionEnabled=QueryAndPhysics,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=,HelpMessage="WorldDynamic object that blocks all actors by default. All new custom channels will use its own default response. ") +Profiles=(Name="OverlapAllDynamic",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="WorldStatic",Response=ECR_Overlap),(Channel="Pawn",Response=ECR_Overlap),(Channel="Visibility",Response=ECR_Overlap),(Channel="WorldDynamic",Response=ECR_Overlap),(Channel="Camera",Response=ECR_Overlap),(Channel="PhysicsBody",Response=ECR_Overlap),(Channel="Vehicle",Response=ECR_Overlap),(Channel="Destructible",Response=ECR_Overlap)),HelpMessage="WorldDynamic object that overlaps all actors by default. All new custom channels will use its own default response. ") +Profiles=(Name="IgnoreOnlyPawn",CollisionEnabled=QueryOnly,bCanModify=False,ObjectTypeName="WorldDynamic",CustomResponses=((Channel="Pawn",Response=ECR_Ignore),(Channel="Vehicle",Response=ECR_Ignore)),HelpMessage="WorldDynamic object that ignores Pawn and Vehicle. All other channels will be set to default.") @@ -151,21 +196,4 @@ DefaultGraphicsRHI=DefaultGraphicsRHI_DX11 +DefaultChannelResponses=(Channel=ECC_GameTraceChannel4,DefaultResponse=ECR_Block,bTraceType=True,bStaticObject=False,Name="DReyeVRSensorTrace") +EditProfiles=(Name="BlockAll",CustomResponses=((Channel="SensorObject"),(Channel="SensorTrace"))) +EditProfiles=(Name="OverlapAll",CustomResponses=((Channel="SensorObject",Response=ECR_Overlap),(Channel="SensorTrace",Response=ECR_Overlap))) --ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") --ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") --ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") --ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") --ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") -+ProfileRedirects=(OldName="BlockingVolume",NewName="InvisibleWall") -+ProfileRedirects=(OldName="InterpActor",NewName="IgnoreOnlyPawn") -+ProfileRedirects=(OldName="StaticMeshComponent",NewName="BlockAllDynamic") -+ProfileRedirects=(OldName="SkeletalMeshActor",NewName="PhysicsActor") -+ProfileRedirects=(OldName="InvisibleActor",NewName="InvisibleWallDynamic") --CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") --CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") --CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") --CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") -+CollisionChannelRedirects=(OldName="Static",NewName="WorldStatic") -+CollisionChannelRedirects=(OldName="Dynamic",NewName="WorldDynamic") -+CollisionChannelRedirects=(OldName="VehicleMovement",NewName="Vehicle") -+CollisionChannelRedirects=(OldName="PawnMovement",NewName="Pawn") + diff --git a/Configs/DefaultGame.ini b/Config/DefaultGame.ini similarity index 83% rename from Configs/DefaultGame.ini rename to Config/DefaultGame.ini index 53e65b7..00c38f8 100644 --- a/Configs/DefaultGame.ini +++ b/Config/DefaultGame.ini @@ -59,16 +59,31 @@ bSkipEditorContent=False +MapsToCook=(FilePath="/Game/Carla/Maps/Town04_Opt") +MapsToCook=(FilePath="/Game/Carla/Maps/Town05") +MapsToCook=(FilePath="/Game/Carla/Maps/Town05_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town06") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town06_Opt") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town07") ++MapsToCook=(FilePath="/Game/Carla/Maps/Town07_Opt") +MapsToCook=(FilePath="/Game/Carla/Maps/Town10HD") +MapsToCook=(FilePath="/Game/Carla/Maps/Town10HD_Opt") +MapsToCook=(FilePath="/Game/Carla/Maps/OpenDriveMap") +MapsToCook=(FilePath="/Game/Carla/Maps/TestMaps/EmptyMap") +DirectoriesToAlwaysCook=(Path="Carla/Static/GenericMaterials/Licenseplates/Textures") -+DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/DReyeVR_Signs") -+DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/Custom") ++DirectoriesToAlwaysCook=(Path="/Game/DReyeVR") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/OpenDrive") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/Nav") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/TM") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Config") bNativizeBlueprintAssets=False bNativizeOnlySelectedBlueprints=False + +[/Script/VRSSettingsEditor.VRSSettings] +vrs.EnableVRS=True +vrs.EnableEyeTracking=True +vrs.VRSRenderType=0 +FoveationPatternPreset=NARROW +FoveationPatternDetail=(FoveatedHorizontalRadius=0.000000,FoveatedVerticalRadius=0.000000,MiddleHorizontalRadius=0.000000,MiddleVerticalRadius=0.000000,PeripheralHorizontalRadius=0.000000,PeripheralVerticalRadius=0.000000) +CustomFoveationPatternSettings=(FoveatedHorizontalRadius=0.250000,FoveatedVerticalRadius=0.250000,MiddleHorizontalRadius=0.330000,MiddleVerticalRadius=0.330000,PeripheralHorizontalRadius=1.500000,PeripheralVerticalRadius=1.500000) +ShadingRatePreset=HIGHEST_PERFORMANCE +ShadingRateDetail=(FoveatedShadingRate=X1_PER_PIXEL,MiddleShadingRate=X1_PER_2X2PIXEL,PeripheralShadingRate=X1_PER_4X4PIXEL) +CustomShadingRateSettings=(FoveatedShadingRate=X16_PER_PIXEL,MiddleShadingRate=X16_PER_PIXEL,PeripheralShadingRate=X16_PER_PIXEL) + diff --git a/Configs/DefaultInput.ini b/Config/DefaultInput.ini similarity index 100% rename from Configs/DefaultInput.ini rename to Config/DefaultInput.ini diff --git a/Configs/CarlaUE4.Build.cs b/Configs/CarlaUE4.Build.cs deleted file mode 100644 index a73bd84..0000000 --- a/Configs/CarlaUE4.Build.cs +++ /dev/null @@ -1,84 +0,0 @@ -// Fill out your copyright notice in the Description page of Project Settings. - -using System; -using System.IO; -using UnrealBuildTool; - -public class CarlaUE4 : ModuleRules -{ - private bool IsWindows(ReadOnlyTargetRules Target) - { - return (Target.Platform == UnrealTargetPlatform.Win64) || (Target.Platform == UnrealTargetPlatform.Win32); - } - public CarlaUE4(ReadOnlyTargetRules Target) : base(Target) - { - PrivatePCHHeaderFile = "CarlaUE4.h"; - ShadowVariableWarningLevel = WarningLevel.Off; // -Wno-shadow - - // include LibCarla so we can #include headers - string LibCarlaIncludePath = Path.GetFullPath(Path.Combine(ModuleDirectory, "..", "..", "..", "..", "LibCarla", "source")); - PublicIncludePaths.Add(LibCarlaIncludePath); - PrivateIncludePaths.Add(LibCarlaIncludePath); - - PublicDependencyModuleNames.AddRange(new string[] { "Core", "CoreUObject", "Engine", "InputCore", "UMG" }); - - if (Target.Type == TargetType.Editor) - { - PublicDependencyModuleNames.AddRange(new string[] { "UnrealEd" }); - } - else - { - // only build this carla exception in package mode - PublicDefinitions.Add("NO_DREYEVR_EXCEPTIONS"); - } - - // Add module for SteamVR support with UE4 - PublicDependencyModuleNames.AddRange(new string[] { "HeadMountedDisplay" }); - - if (IsWindows(Target)) - { - bEnableExceptions = true; // enable unwind semantics for C++-style exceptions - } - - //////////////////////////////////////////////////////////////////////////////////// - // Edit these variables to enable/disable features of DReyeVR - bool UseSRanipalPlugin = true; - bool UseLogitechPlugin = true; - bool UseFoveatedRender = false; // not ready for production yet! - //////////////////////////////////////////////////////////////////////////////////// - - if (!IsWindows(Target)) - { - // adjust definitions so they are OS-compatible - UseSRanipalPlugin = false; // SRanipal only works on Windows - UseLogitechPlugin = false; // LogitechWheelPlugin also only works on Windows - UseFoveatedRender = false; // Vive VRS plugin requires engine fork - } - - // Add these preprocessor definitions to code - PublicDefinitions.Add("USE_SRANIPAL_PLUGIN=" + (UseSRanipalPlugin ? "true" : "false")); - PublicDefinitions.Add("USE_LOGITECH_PLUGIN=" + (UseLogitechPlugin ? "true" : "false")); - PublicDefinitions.Add("USE_FOVEATED_RENDER=" + (UseFoveatedRender ? "true" : "false")); - - // Add plugin dependencies - if (UseSRanipalPlugin) - { - PrivateDependencyModuleNames.AddRange(new string[] { "SRanipalEye" }); - PrivateIncludePathModuleNames.AddRange(new string[] { "SRanipalEye" }); - } - - if (UseLogitechPlugin) - { - PrivateDependencyModuleNames.AddRange(new string[] { "LogitechWheelPlugin" }); - } - - if (UseFoveatedRender) - { - // Add VRS plugin and and EyeTracker dependencies - PublicDependencyModuleNames.AddRange(new string[] { "EyeTracker", "VRSPlugin" }); - } - - - PrivateDependencyModuleNames.AddRange( new string[] {"ImageWriteQueue"}); - } -} diff --git a/Configs/DReyeVRConfig.ini b/Configs/DReyeVRConfig.ini deleted file mode 100644 index fc028d7..0000000 --- a/Configs/DReyeVRConfig.ini +++ /dev/null @@ -1,123 +0,0 @@ -; NOTE: this is a weird config file bc it is custom written for DReyeVR -; there needs to be no spaces between the '=' and the key/value pair -; also comments are permitted BUT need to be directly after the value (no spaces) -; [sections] also work as intended, see ReadConfigValue for more info - -[EgoVehicle] -DashLocation=(X=110.0, Y=0.0, Z=105.0); position offset of dash in vehicle -SpeedometerInMPH=True; set to False to use KPH -EnableTurnSignalAction=True; True to enable turn signal animation (& sound), else false -TurnSignalDuration=3.0; time (in s) that the turn signals stay on for -ActorRegistryID=501; desired (but not guaranteed) ID for the ActorRegistry (can be any nonzero number) -DrawDebugEditor=False; draw debug lines/sphere for eye gaze in the editor - -[CameraPose] -; location & rotation of camera relative to vehicle (location units in cm, rotation in degrees) -StartingPose=DriversSeat; starting position of camera in vehicle (on begin play) -; NOTE: we assume the location is suffix'd with "Loc" and rotation is suffixed with "Rot" -DriversSeatLoc=(X=20.0, Y=-40.0, Z=120.0); location of first-person camera -DriversSeatRot=(R=0.0, P=0.0, Y=0.0); rotation of first-person camera -FrontLoc=(X=250.0, Y=0.0, Z=90.0); location of camera in front of vehicle -FrontRot=(R=0.0, P=0.0, Y=0.0); rotation of camera in front of vehicle -BirdsEyeViewLoc=(X=0.0, Y=0.0, Z=820.0); location of camera from top-down bird's eye view -BirdsEyeViewRot=(R=0.0, P=270.0, Y=0.0); rotation of camera from top-down bird's eye view -ThirdPersonLoc=(X=-500.0, Y=0.0, Z=380.0); location of camera in third-person view -ThirdPersonRot=(R=0.0, P=330.0, Y=0.0); rotation of camera in third-person view - -[CameraParams] -FieldOfView=90.0; horizontal field of view -ScreenPercentage=100; 100% is native resolution, increase for supersampling, decrease for subsampling -; all the intensities range from [0 (off) to 1 (maximum)] -MotionBlurIntensity=0; how much motion blur in the camera -VignetteIntensity=0; how intense the vignetting is (darkened corners) -BloomIntensity=0; how intense the bloom is -SceneFringeIntensity=0; how intense the SceneFringe is -LensFlareIntensity=0; how intense the lens flares are -GrainIntensity=0; how intense the grain is - -[Mirrors] -; rear view mirror -RearMirrorEnabled=True -RearMirrorChassisPos=(X=48.0, Y=0.0, Z=123.0) -RearMirrorChassisRot=(R=0.0, P=0.0, Y=25.06) -RearMirrorChassisScale=(X=1.0, Y=1.0, Z=1.0) -RearMirrorPos=(X=-0.5, Y=0.0, Z=0.0) -RearMirrorRot=(R=0.0, P=1.0, Y=0.0) -RearMirrorScale=(X=0.9, Y=0.98, Z=0.9) -RearReflectionPos=(X=-7, Y=0.0, Z=0.0) -RearReflectionRot=(R=0.0, P=90.0, Y=0.0) -RearReflectionScale=(X=0.002, Y=0.007, Z=1.0) -RearScreenPercentage=85; used very frequently -; left view side mirror -LeftMirrorEnabled=True -LeftMirrorPos=(X=62.0, Y=-98.0, Z=105.5) -LeftMirrorRot=(R=0.0, P=0.0, Y=0.0) -LeftMirrorScale=(X=0.9, Y=0.9, Z=0.9) -LeftReflectionPos=(X=0, Y=0, Z=-3.0) -LeftReflectionRot=(R=43.2, P=81, Y=22.5) -LeftReflectionScale=(X=0.003, Y=0.005, Z=1.0) -LeftScreenPercentage=65; used quite a bit -; right view side mirror -RightMirrorEnabled=True -RightMirrorPos=(X=62, Y=98, Z=100.5) -RightMirrorRot=(R=0, P=-4, Y=2.79) -RightMirrorScale=(X=0.9, Y=0.9, Z=0.9) -RightReflectionPos=(X=0.0, Y=0.0, Z=2.22) -RightReflectionRot=(R=-1, P=90.0, Y=21.6) -RightReflectionScale=(X=0.003, Y=0.005, Z=1.0) -RightScreenPercentage=50; used very rarely if ever - -[SteeringWheel] -InitLocation=(X=85.0, Y=-40.0, Z=85.0); position of the steering wheel in the vehicle -InitRotation=(R=0.0, P=-10.0, Y=0.0); tilt of the steering wheel at rest -MaxSteerAngleDeg=900; max wheel rotation in degrees (pos and negative) -MaxSteerVelocity=90; maximum velocity (degrees per second) -SteeringScale=360; scale with which to rotate the wheel (normalized [-1, 1] -> degrees) - -[EgoSensor] -ActorRegistryID=502; desired (but not guaranteed) ID for the ActorRegistry (can be any nonzero number) -StreamSensorData=True; Set to False to skip streaming sensor data (for PythonAPI) on every tick -MaxTraceLenM=100.0; maximum trace length (in meters) to use for world-hit point calculation -DrawDebugFocusTrace=True; draw the debug focus trace & hit point in editor - -[VehicleInputs] -ScaleSteeringDamping=0.6 -ScaleThrottleInput=1.0 -ScaleBrakeInput=1.0 -InvertMouseY=False; use inverted-flight controls for moving camera with mouse inputs -ScaleMouseY=1.0 -ScaleMouseX=1.0 - -[EgoVehicleHUD] -HUDScaleVR=6; scale all HUD elements in VR mode only -DrawFPSCounter=True; draw's FPS (frames per second) in top right corner of flat screen -DrawFlatReticle=True; reticle in flat-screen mode -DrawGaze=False; draw debug gaze lines on flat-screen hud -DrawSpectatorReticle=True; reticle in spectator mode during vr (VR spectator HUD only) -ReticleSize=100; diameter of reticle (thickness also scales) -EnableSpectatorScreen=True; whether or not to enable the flat-screen spectator when in VR - -[Level] -EgoVolumePercent=100 -NonEgoVolumePercent=100 -AmbientVolumePercent=20 - -[Replayer] -CameraFollowHMD=True; Whether or not to have the camera pose follow the recorded HMD pose -RunSyncReplay=True; Whether or not to run the replayer exactly frame by frame (no interpolation) -RecordAllShaders=False; Enable or disable rendering the scene with additional (beyond RGB) shaders such as depth -RecordAllPoses=False; Enable or disable rendering the scene with all camera poses (beyond driver's seat) -RecordFrames=True; additionally capture camera screenshots on replay tick (requires RunSyncReplay=True) -FileFormatJPG=True; either JPG or PNG -LinearGamma=True; force linear gamme for frame capture render -FrameWidth=1280; resolution x for screenshot -FrameHeight=720; resolution y for screenshot -FrameDir=FrameCap; directory name for screenshot -FrameName=tick; title of screenshot (differentiated via tick-suffix) - -[Hardware] -DeviceIdx=0; Device index of the hardware (Logitech has 2, can be 0 or 1) -LogUpdates=False; whether or not to print debug messages - -[FoveatedRender] -Enabled=True diff --git a/Content/DReyeVR/Custom/MirrorMaterial.uasset b/Content/DReyeVR/Custom/MirrorMaterial.uasset new file mode 100644 index 0000000..5b7ece0 Binary files /dev/null and b/Content/DReyeVR/Custom/MirrorMaterial.uasset differ diff --git a/Content/Custom/OpaqueParamMaterial.uasset b/Content/DReyeVR/Custom/OpaqueParamMaterial.uasset similarity index 100% rename from Content/Custom/OpaqueParamMaterial.uasset rename to Content/DReyeVR/Custom/OpaqueParamMaterial.uasset diff --git a/Content/DReyeVR/Custom/Shapes/SM_Arrow.uasset b/Content/DReyeVR/Custom/Shapes/SM_Arrow.uasset new file mode 100644 index 0000000..9339e5b Binary files /dev/null and b/Content/DReyeVR/Custom/Shapes/SM_Arrow.uasset differ diff --git a/Content/DReyeVR/Custom/Shapes/SM_Cross.uasset b/Content/DReyeVR/Custom/Shapes/SM_Cross.uasset new file mode 100644 index 0000000..8371227 Binary files /dev/null and b/Content/DReyeVR/Custom/Shapes/SM_Cross.uasset differ diff --git a/Content/Custom/TranslucentParamMaterial.uasset b/Content/DReyeVR/Custom/TranslucentParamMaterial.uasset similarity index 100% rename from Content/Custom/TranslucentParamMaterial.uasset rename to Content/DReyeVR/Custom/TranslucentParamMaterial.uasset diff --git a/Content/DReyeVR/EgoVehicle/BP_model3.uasset b/Content/DReyeVR/EgoVehicle/BP_model3.uasset new file mode 100644 index 0000000..6c169fe Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/BP_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.uasset new file mode 100644 index 0000000..5980c0c Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.uasset new file mode 100644 index 0000000..2345b40 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleMesh_DReyeVR.uasset b/Content/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.uasset similarity index 78% rename from Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleMesh_DReyeVR.uasset rename to Content/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.uasset index 1c7d52f..beeeace 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleMesh_DReyeVR.uasset and b/Content/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleSkeleton_DReyeVR.uasset b/Content/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.uasset similarity index 57% rename from Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleSkeleton_DReyeVR.uasset rename to Content/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.uasset index 6bc82d5..8fdc8dc 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Mesh/SM_VehicleSkeleton_DReyeVR.uasset and b/Content/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.uasset new file mode 100644 index 0000000..b9aeecd Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.uasset new file mode 100644 index 0000000..c844223 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.uasset new file mode 100644 index 0000000..68c3d83 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.uasset new file mode 100644 index 0000000..db5dea0 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Physics_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Physics_model3.uasset new file mode 100644 index 0000000..2f193e2 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Physics_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_SkeletalMesh_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_SkeletalMesh_model3.uasset new file mode 100644 index 0000000..2a083a7 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_SkeletalMesh_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Skeleton_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Skeleton_model3.uasset new file mode 100644 index 0000000..383e73e Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Skeleton_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.uasset new file mode 100644 index 0000000..4f68a6c Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Front.uasset b/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Front.uasset new file mode 100644 index 0000000..dd3bf3a Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Front.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Tires/BP_DReyeVR_Rear.uasset b/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Rear.uasset similarity index 52% rename from Blueprints/Vehicles/DReyeVR/Tires/BP_DReyeVR_Rear.uasset rename to Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Rear.uasset index 870f79e..037f183 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Tires/BP_DReyeVR_Rear.uasset and b/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Rear.uasset differ diff --git a/Content/DReyeVR/Signs/BP_DReyeVR_Left.uasset b/Content/DReyeVR/Signs/BP_DReyeVR_Left.uasset new file mode 100644 index 0000000..4ab743b Binary files /dev/null and b/Content/DReyeVR/Signs/BP_DReyeVR_Left.uasset differ diff --git a/Content/DReyeVR/Signs/BP_DReyeVR_Right.uasset b/Content/DReyeVR/Signs/BP_DReyeVR_Right.uasset new file mode 100644 index 0000000..f6032d1 Binary files /dev/null and b/Content/DReyeVR/Signs/BP_DReyeVR_Right.uasset differ diff --git a/Content/DReyeVR/Signs/BP_DReyeVR_Straight.uasset b/Content/DReyeVR/Signs/BP_DReyeVR_Straight.uasset new file mode 100644 index 0000000..1c34447 Binary files /dev/null and b/Content/DReyeVR/Signs/BP_DReyeVR_Straight.uasset differ diff --git a/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_RoadSigns01.uasset b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_RoadSigns01.uasset new file mode 100644 index 0000000..2e2db64 Binary files /dev/null and b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_RoadSigns01.uasset differ diff --git a/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_goal.uasset b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_goal.uasset new file mode 100644 index 0000000..fd15fa6 Binary files /dev/null and b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_goal.uasset differ diff --git a/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_left.uasset b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_left.uasset new file mode 100644 index 0000000..e712f39 Binary files /dev/null and b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_left.uasset differ diff --git a/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_right.uasset b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_right.uasset new file mode 100644 index 0000000..eca67b2 Binary files /dev/null and b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_right.uasset differ diff --git a/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_straight.uasset b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_straight.uasset new file mode 100644 index 0000000..dbeccaa Binary files /dev/null and b/Content/DReyeVR/Signs/FullSign/SM_DReyeVR_sign_straight.uasset differ diff --git a/Content/DReyeVR/Signs/M_DReyeVR_Goal.uasset b/Content/DReyeVR/Signs/M_DReyeVR_Goal.uasset new file mode 100644 index 0000000..fdb5443 Binary files /dev/null and b/Content/DReyeVR/Signs/M_DReyeVR_Goal.uasset differ diff --git a/Content/DReyeVR/Signs/M_DReyeVR_Left.uasset b/Content/DReyeVR/Signs/M_DReyeVR_Left.uasset new file mode 100644 index 0000000..26d8fc3 Binary files /dev/null and b/Content/DReyeVR/Signs/M_DReyeVR_Left.uasset differ diff --git a/Content/DReyeVR/Signs/M_DReyeVR_Right.uasset b/Content/DReyeVR/Signs/M_DReyeVR_Right.uasset new file mode 100644 index 0000000..f157012 Binary files /dev/null and b/Content/DReyeVR/Signs/M_DReyeVR_Right.uasset differ diff --git a/Content/DReyeVR/Signs/M_DReyeVR_Straight.uasset b/Content/DReyeVR/Signs/M_DReyeVR_Straight.uasset new file mode 100644 index 0000000..64a28b0 Binary files /dev/null and b/Content/DReyeVR/Signs/M_DReyeVR_Straight.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Goal.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Goal.uasset new file mode 100644 index 0000000..f147cbc Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Goal.uasset differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Goal__0.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Goal__0.uasset similarity index 95% rename from Content/DReyeVR_Signs/SM_DReyeVR_Goal__0.uasset rename to Content/DReyeVR/Signs/SM_DReyeVR_Goal__0.uasset index 24e69f1..85f2bc5 100644 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Goal__0.uasset and b/Content/DReyeVR/Signs/SM_DReyeVR_Goal__0.uasset differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Goal_n.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Goal_n.uasset similarity index 96% rename from Content/DReyeVR_Signs/SM_DReyeVR_Goal_n.uasset rename to Content/DReyeVR/Signs/SM_DReyeVR_Goal_n.uasset index 3187731..8f17250 100644 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Goal_n.uasset and b/Content/DReyeVR/Signs/SM_DReyeVR_Goal_n.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Left_.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Left_.uasset new file mode 100644 index 0000000..76258bf Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Left_.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Left__0.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Left__0.uasset new file mode 100644 index 0000000..12fb588 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Left__0.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Left_n.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Left_n.uasset new file mode 100644 index 0000000..0507982 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Left_n.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Right_.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Right_.uasset new file mode 100644 index 0000000..16ad410 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Right_.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Right__0.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Right__0.uasset new file mode 100644 index 0000000..586df83 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Right__0.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Right_n.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Right_n.uasset new file mode 100644 index 0000000..e847235 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Right_n.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Straight.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Straight.uasset new file mode 100644 index 0000000..78fe860 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Straight.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Straight__0.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Straight__0.uasset new file mode 100644 index 0000000..66c315b Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Straight__0.uasset differ diff --git a/Content/DReyeVR/Signs/SM_DReyeVR_Straight_n.uasset b/Content/DReyeVR/Signs/SM_DReyeVR_Straight_n.uasset new file mode 100644 index 0000000..c0c1994 Binary files /dev/null and b/Content/DReyeVR/Signs/SM_DReyeVR_Straight_n.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Light01.uasset b/Content/DReyeVR/Sounds/Ambient/Light01.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Light01.uasset rename to Content/DReyeVR/Sounds/Ambient/Light01.uasset index fefa368..1a04c76 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Light01.uasset and b/Content/DReyeVR/Sounds/Ambient/Light01.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Light02.uasset b/Content/DReyeVR/Sounds/Ambient/Light02.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Light02.uasset rename to Content/DReyeVR/Sounds/Ambient/Light02.uasset index 34ba926..36353a0 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Light02.uasset and b/Content/DReyeVR/Sounds/Ambient/Light02.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Smoke01.uasset b/Content/DReyeVR/Sounds/Ambient/Smoke01.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Smoke01.uasset rename to Content/DReyeVR/Sounds/Ambient/Smoke01.uasset index f34963b..fe69509 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Smoke01.uasset and b/Content/DReyeVR/Sounds/Ambient/Smoke01.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Birds01.uasset b/Content/DReyeVR/Sounds/Ambient/Starter_Birds01.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Birds01.uasset rename to Content/DReyeVR/Sounds/Ambient/Starter_Birds01.uasset index 9c21303..558190c 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Birds01.uasset and b/Content/DReyeVR/Sounds/Ambient/Starter_Birds01.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Wind05.uasset b/Content/DReyeVR/Sounds/Ambient/Starter_Wind05.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Wind05.uasset rename to Content/DReyeVR/Sounds/Ambient/Starter_Wind05.uasset index 0df4882..fd71bfa 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Wind05.uasset and b/Content/DReyeVR/Sounds/Ambient/Starter_Wind05.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Wind06.uasset b/Content/DReyeVR/Sounds/Ambient/Starter_Wind06.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Wind06.uasset rename to Content/DReyeVR/Sounds/Ambient/Starter_Wind06.uasset index 3b5d55a..66f0fa1 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Starter_Wind06.uasset and b/Content/DReyeVR/Sounds/Ambient/Starter_Wind06.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Steam01.uasset b/Content/DReyeVR/Sounds/Ambient/Steam01.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Steam01.uasset rename to Content/DReyeVR/Sounds/Ambient/Steam01.uasset index ab1d2df..ee6d8c1 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Steam01.uasset and b/Content/DReyeVR/Sounds/Ambient/Steam01.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Water.uasset b/Content/DReyeVR/Sounds/Ambient/Water.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Water.uasset rename to Content/DReyeVR/Sounds/Ambient/Water.uasset index 9767899..e2b8d62 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Ambient/Water.uasset and b/Content/DReyeVR/Sounds/Ambient/Water.uasset differ diff --git a/Content/DReyeVR/Sounds/Crash/CrashAttenuation.uasset b/Content/DReyeVR/Sounds/Crash/CrashAttenuation.uasset new file mode 100644 index 0000000..e2eb1b7 Binary files /dev/null and b/Content/DReyeVR/Sounds/Crash/CrashAttenuation.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashCue.uasset b/Content/DReyeVR/Sounds/Crash/CrashCue.uasset similarity index 61% rename from Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashCue.uasset rename to Content/DReyeVR/Sounds/Crash/CrashCue.uasset index 93f4ab8..af4c8c3 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashCue.uasset and b/Content/DReyeVR/Sounds/Crash/CrashCue.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashWave.uasset b/Content/DReyeVR/Sounds/Crash/CrashWave.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashWave.uasset rename to Content/DReyeVR/Sounds/Crash/CrashWave.uasset index 8cfeace..97f094d 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/Crash/CrashWave.uasset and b/Content/DReyeVR/Sounds/Crash/CrashWave.uasset differ diff --git a/Content/DReyeVR/Sounds/EngineRev/EngineAttenuation.uasset b/Content/DReyeVR/Sounds/EngineRev/EngineAttenuation.uasset new file mode 100644 index 0000000..b18d81c Binary files /dev/null and b/Content/DReyeVR/Sounds/EngineRev/EngineAttenuation.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineRev.uasset b/Content/DReyeVR/Sounds/EngineRev/EngineRev.uasset similarity index 80% rename from Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineRev.uasset rename to Content/DReyeVR/Sounds/EngineRev/EngineRev.uasset index ba8c2ad..3c92c4a 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/EngineRev.uasset and b/Content/DReyeVR/Sounds/EngineRev/EngineRev.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive0.uasset b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive0.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive0.uasset rename to Content/DReyeVR/Sounds/EngineRev/Rev_Drive0.uasset index 75e0ac2..d82eaba 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive0.uasset and b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive0.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive1.uasset b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive1.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive1.uasset rename to Content/DReyeVR/Sounds/EngineRev/Rev_Drive1.uasset index 0f8c3df..17a38e8 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive1.uasset and b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive1.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive2.uasset b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive2.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive2.uasset rename to Content/DReyeVR/Sounds/EngineRev/Rev_Drive2.uasset index 00215b2..8e3f376 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive2.uasset and b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive2.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive3.uasset b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive3.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive3.uasset rename to Content/DReyeVR/Sounds/EngineRev/Rev_Drive3.uasset index 0695c1e..683772f 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/EngineRev/Rev_Drive3.uasset and b/Content/DReyeVR/Sounds/EngineRev/Rev_Drive3.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/GearShift.uasset b/Content/DReyeVR/Sounds/GearShift.uasset similarity index 98% rename from Blueprints/Vehicles/DReyeVR/Sounds/GearShift.uasset rename to Content/DReyeVR/Sounds/GearShift.uasset index 3bfcb56..ae22c5a 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/GearShift.uasset and b/Content/DReyeVR/Sounds/GearShift.uasset differ diff --git a/Blueprints/Vehicles/DReyeVR/Sounds/TurnSignal.uasset b/Content/DReyeVR/Sounds/TurnSignal.uasset similarity index 99% rename from Blueprints/Vehicles/DReyeVR/Sounds/TurnSignal.uasset rename to Content/DReyeVR/Sounds/TurnSignal.uasset index ff0f711..d21bb47 100644 Binary files a/Blueprints/Vehicles/DReyeVR/Sounds/TurnSignal.uasset and b/Content/DReyeVR/Sounds/TurnSignal.uasset differ diff --git a/Content/DReyeVR_Signs/BP_DReyeVR_Left.uasset b/Content/DReyeVR_Signs/BP_DReyeVR_Left.uasset deleted file mode 100644 index d4c52c5..0000000 Binary files a/Content/DReyeVR_Signs/BP_DReyeVR_Left.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/BP_DReyeVR_Right.uasset b/Content/DReyeVR_Signs/BP_DReyeVR_Right.uasset deleted file mode 100644 index e674aa1..0000000 Binary files a/Content/DReyeVR_Signs/BP_DReyeVR_Right.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/BP_DReyeVR_Straight.uasset b/Content/DReyeVR_Signs/BP_DReyeVR_Straight.uasset deleted file mode 100644 index 4a91c4a..0000000 Binary files a/Content/DReyeVR_Signs/BP_DReyeVR_Straight.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_RoadSigns01.uasset b/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_RoadSigns01.uasset deleted file mode 100644 index 08d4d67..0000000 Binary files a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_RoadSigns01.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_goal.uasset b/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_goal.uasset deleted file mode 100644 index ac995fc..0000000 Binary files a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_goal.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_left.uasset b/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_left.uasset deleted file mode 100644 index e123e12..0000000 Binary files a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_left.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_right.uasset b/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_right.uasset deleted file mode 100644 index 215d374..0000000 Binary files a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_right.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_straight.uasset b/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_straight.uasset deleted file mode 100644 index a3d0e49..0000000 Binary files a/Content/DReyeVR_Signs/FullSign/SM_DReyeVR_sign_straight.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/M_DReyeVR_Goal.uasset b/Content/DReyeVR_Signs/M_DReyeVR_Goal.uasset deleted file mode 100644 index 86a6fb1..0000000 Binary files a/Content/DReyeVR_Signs/M_DReyeVR_Goal.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/M_DReyeVR_Left.uasset b/Content/DReyeVR_Signs/M_DReyeVR_Left.uasset deleted file mode 100644 index 0d23678..0000000 Binary files a/Content/DReyeVR_Signs/M_DReyeVR_Left.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/M_DReyeVR_Right.uasset b/Content/DReyeVR_Signs/M_DReyeVR_Right.uasset deleted file mode 100644 index 5ca787d..0000000 Binary files a/Content/DReyeVR_Signs/M_DReyeVR_Right.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/M_DReyeVR_Straight.uasset b/Content/DReyeVR_Signs/M_DReyeVR_Straight.uasset deleted file mode 100644 index 801e685..0000000 Binary files a/Content/DReyeVR_Signs/M_DReyeVR_Straight.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Goal.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Goal.uasset deleted file mode 100644 index 08a55a5..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Goal.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Left_.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Left_.uasset deleted file mode 100644 index ea40ecc..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Left_.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Left__0.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Left__0.uasset deleted file mode 100644 index 74f0eb7..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Left__0.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Left_n.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Left_n.uasset deleted file mode 100644 index f2d73f1..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Left_n.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Right_.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Right_.uasset deleted file mode 100644 index 0be137d..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Right_.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Right__0.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Right__0.uasset deleted file mode 100644 index eed7c73..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Right__0.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Right_n.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Right_n.uasset deleted file mode 100644 index ad54134..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Right_n.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Straight.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Straight.uasset deleted file mode 100644 index f6018f1..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Straight.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Straight__0.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Straight__0.uasset deleted file mode 100644 index 6d4b489..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Straight__0.uasset and /dev/null differ diff --git a/Content/DReyeVR_Signs/SM_DReyeVR_Straight_n.uasset b/Content/DReyeVR_Signs/SM_DReyeVR_Straight_n.uasset deleted file mode 100644 index fb28586..0000000 Binary files a/Content/DReyeVR_Signs/SM_DReyeVR_Straight_n.uasset and /dev/null differ diff --git a/Content/Static/DefaultSign.png b/Content/Static/DefaultSign.png deleted file mode 100644 index 433bdc8..0000000 Binary files a/Content/Static/DefaultSign.png and /dev/null differ diff --git a/Content/Static/Goal.png b/Content/Static/Goal.png deleted file mode 100644 index e4e17de..0000000 Binary files a/Content/Static/Goal.png and /dev/null differ diff --git a/Content/Static/GoalLeft.png b/Content/Static/GoalLeft.png deleted file mode 100644 index ca971be..0000000 Binary files a/Content/Static/GoalLeft.png and /dev/null differ diff --git a/Content/Static/GoalLeft_n.png b/Content/Static/GoalLeft_n.png deleted file mode 100644 index 3d9935f..0000000 Binary files a/Content/Static/GoalLeft_n.png and /dev/null differ diff --git a/Content/Static/GoalRight.png b/Content/Static/GoalRight.png deleted file mode 100644 index dd142e4..0000000 Binary files a/Content/Static/GoalRight.png and /dev/null differ diff --git a/Content/Static/GoalRight_n.png b/Content/Static/GoalRight_n.png deleted file mode 100644 index 216d4f3..0000000 Binary files a/Content/Static/GoalRight_n.png and /dev/null differ diff --git a/Content/Static/GoalStraight.png b/Content/Static/GoalStraight.png deleted file mode 100644 index fa0fd77..0000000 Binary files a/Content/Static/GoalStraight.png and /dev/null differ diff --git a/Content/Static/GoalStraight_n.png b/Content/Static/GoalStraight_n.png deleted file mode 100644 index 1361427..0000000 Binary files a/Content/Static/GoalStraight_n.png and /dev/null differ diff --git a/Content/Static/Goal_n.png b/Content/Static/Goal_n.png deleted file mode 100644 index 02bfe4d..0000000 Binary files a/Content/Static/Goal_n.png and /dev/null differ diff --git a/DReyeVR/DReyeVRFactory.cpp b/DReyeVR/DReyeVRFactory.cpp new file mode 100644 index 0000000..0007dff --- /dev/null +++ b/DReyeVR/DReyeVRFactory.cpp @@ -0,0 +1,144 @@ +#include "DReyeVRFactory.h" +#include "Carla.h" // to avoid linker errors +#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // UActorBlueprintFunctionLibrary +#include "Carla/Actor/VehicleParameters.h" // FVehicleParameters +#include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode +#include "EgoSensor.h" // AEgoSensor +#include "EgoVehicle.h" // AEgoVehicle + +#define EgoVehicleBP_Str "/Game/DReyeVR/EgoVehicle/BP_model3.BP_model3_C" + +// instead of vehicle.dreyevr.model3 or sensor.dreyevr.ego_sensor, we use "harplab" for category +// => harplab.dreyevr_vehicle.model3 & harplab.dreyevr_sensor.ego_sensor +// in PythonAPI use world.get_actors().filter("harplab.dreyevr_vehicle.*") or +// world.get_blueprint_library().filter("harplab.dreyevr_sensor.*") and you won't accidentally get these actors when +// performing filter("vehicle.*") or filter("sensor.*") +#define CATEGORY TEXT("HARPLab") + +ADReyeVRFactory::ADReyeVRFactory(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +{ + // https://forums.unrealengine.com/t/cdo-constructor-failed-to-find-thirdperson-c-template-mannequin-animbp/99003 + // get ego vehicle bp (can use UTF8_TO_TCHAR if making EgoVehicleBP_Str a variable) + static ConstructorHelpers::FObjectFinder EgoVehicleBP(TEXT(EgoVehicleBP_Str)); + EgoVehicleBPClass = EgoVehicleBP.Object; + ensure(EgoVehicleBPClass != nullptr); +} + +TArray ADReyeVRFactory::GetDefinitions() +{ + FActorDefinition EgoVehicleDef; + { + FVehicleParameters Parameters; + Parameters.Model = "Model3"; + Parameters.ObjectType = EgoVehicleBP_Str; + Parameters.Class = AEgoVehicle::StaticClass(); + Parameters.NumberOfWheels = 4; + + ADReyeVRFactory::MakeVehicleDefinition(Parameters, EgoVehicleDef); + } + + FActorDefinition EgoSensorDef; + { + const FString Id = "Ego_Sensor"; + ADReyeVRFactory::MakeSensorDefinition(Id, EgoSensorDef); + } + + return {EgoVehicleDef, EgoSensorDef}; +} + +// copied and modified from UActorBlueprintFunctionLibrary +FActorDefinition MakeGenericDefinition(const FString &Category, const FString &Type, const FString &Id) +{ + FActorDefinition Definition; + + TArray Tags = {Category.ToLower(), Type.ToLower(), Id.ToLower()}; + Definition.Id = FString::Join(Tags, TEXT(".")); + Definition.Tags = FString::Join(Tags, TEXT(",")); + return Definition; +} + +void ADReyeVRFactory::MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition) +{ + // assign the ID/Tags with category (ex. "vehicle.tesla.model3" => "harplab.dreyevr.model3") + Definition = MakeGenericDefinition(CATEGORY, TEXT("DReyeVR_Vehicle"), Parameters.Model); + Definition.Class = Parameters.Class; + + FActorVariation ActorRole; + { + ActorRole.Id = TEXT("role_name"); + ActorRole.Type = EActorAttributeType::String; + ActorRole.RecommendedValues = {TEXT("ego_vehicle")}; // assume this is the CARLA "hero" + ActorRole.bRestrictToRecommended = false; + } + Definition.Variations.Emplace(ActorRole); + + FActorVariation StickyControl; + { + StickyControl.Id = TEXT("sticky_control"); + StickyControl.Type = EActorAttributeType::Bool; + StickyControl.bRestrictToRecommended = false; + StickyControl.RecommendedValues.Emplace(TEXT("false")); + } + Definition.Variations.Emplace(StickyControl); + + FActorAttribute ObjectType; + { + ObjectType.Id = TEXT("object_type"); + ObjectType.Type = EActorAttributeType::String; + ObjectType.Value = Parameters.ObjectType; + } + Definition.Attributes.Emplace(ObjectType); + + FActorAttribute NumberOfWheels; + { + NumberOfWheels.Id = TEXT("number_of_wheels"); + NumberOfWheels.Type = EActorAttributeType::Int; + NumberOfWheels.Value = FString::FromInt(Parameters.NumberOfWheels); + } + Definition.Attributes.Emplace(NumberOfWheels); + + FActorAttribute Generation; + { + Generation.Id = TEXT("generation"); + Generation.Type = EActorAttributeType::Int; + Generation.Value = FString::FromInt(Parameters.Generation); + } + Definition.Attributes.Emplace(Generation); +} + +void ADReyeVRFactory::MakeSensorDefinition(const FString &Id, FActorDefinition &Definition) +{ + Definition = MakeGenericDefinition(CATEGORY, TEXT("DReyeVR_Sensor"), Id); + Definition.Class = AEgoSensor::StaticClass(); +} + +FActorSpawnResult ADReyeVRFactory::SpawnActor(const FTransform &SpawnAtTransform, + const FActorDescription &ActorDescription) +{ + auto *World = GetWorld(); + if (World == nullptr) + { + LOG_ERROR("cannot spawn \"%s\" into an empty world.", *ActorDescription.Id); + return {}; + } + + AActor *SpawnedActor = nullptr; + + FActorSpawnParameters SpawnParameters; + SpawnParameters.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + if (ActorDescription.Class == AEgoVehicle::StaticClass()) + { + LOG("Spawning EgoVehicle (\"%s\") at: %s", *ActorDescription.Id, *SpawnAtTransform.ToString()); + SpawnedActor = World->SpawnActor(EgoVehicleBPClass, SpawnAtTransform, SpawnParameters); + } + else if (ActorDescription.Class == AEgoSensor::StaticClass()) + { + LOG("Spawning EgoSensor (\"%s\") at: %s", *ActorDescription.Id, *SpawnAtTransform.ToString()); + SpawnedActor = World->SpawnActor(ActorDescription.Class, SpawnAtTransform, SpawnParameters); + } + else + { + LOG_ERROR("Unknown actor class in DReyeVR factory!"); + } + return FActorSpawnResult(SpawnedActor); +} diff --git a/DReyeVR/DReyeVRFactory.h b/DReyeVR/DReyeVRFactory.h new file mode 100644 index 0000000..c881686 --- /dev/null +++ b/DReyeVR/DReyeVRFactory.h @@ -0,0 +1,26 @@ +#pragma once + +#include "Carla/Actor/ActorSpawnResult.h" +#include "Carla/Actor/CarlaActorFactory.h" +#include "Carla/Actor/VehicleParameters.h" + +#include "DReyeVRFactory.generated.h" + +/// Factory in charge of spawning DReyeVR actors. +UCLASS() +class ADReyeVRFactory : public ACarlaActorFactory +{ + GENERATED_BODY() + public: + ADReyeVRFactory(const FObjectInitializer &ObjectInitializer); + + TArray GetDefinitions() final; + + FActorSpawnResult SpawnActor(const FTransform &SpawnAtTransform, const FActorDescription &ActorDescription) final; + + private: + void MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition); + void MakeSensorDefinition(const FString &Id, FActorDefinition &Definition); + + class UClass *EgoVehicleBPClass = nullptr; +}; diff --git a/DReyeVR/DReyeVRGameMode.cpp b/DReyeVR/DReyeVRGameMode.cpp new file mode 100644 index 0000000..99b3e33 --- /dev/null +++ b/DReyeVR/DReyeVRGameMode.cpp @@ -0,0 +1,587 @@ +#include "DReyeVRGameMode.h" +#include "Carla/AI/AIControllerFactory.h" // AAIControllerFactory +#include "Carla/Actor/StaticMeshFactory.h" // AStaticMeshFactory +#include "Carla/Game/CarlaStatics.h" // GetReplayer, GetEpisode +#include "Carla/Recorder/CarlaReplayer.h" // ACarlaReplayer +#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor +#include "Carla/Sensor/SensorFactory.h" // ASensorFactory +#include "Carla/Trigger/TriggerFactory.h" // TriggerFactory +#include "Carla/Vehicle/CarlaWheeledVehicle.h" // ACarlaWheeledVehicle +#include "Carla/Weather/Weather.h" // AWeather +#include "Components/AudioComponent.h" // UAudioComponent +#include "DReyeVRFactory.h" // ADReyeVRFactory +#include "DReyeVRPawn.h" // ADReyeVRPawn +#include "DReyeVRUtils.h" // FindDefnInRegistry +#include "EgoVehicle.h" // AEgoVehicle +#include "FlatHUD.h" // ADReyeVRHUD +#include "HeadMountedDisplayFunctionLibrary.h" // IsHeadMountedDisplayAvailable +#include "Kismet/GameplayStatics.h" // GetPlayerController +#include "UObject/UObjectIterator.h" // TObjectInterator + +ADReyeVRGameMode::ADReyeVRGameMode(FObjectInitializer const &FO) : Super(FO) +{ + // initialize stuff here + PrimaryActorTick.bCanEverTick = false; + PrimaryActorTick.bStartWithTickEnabled = false; + + // initialize default classes + this->HUDClass = ADReyeVRHUD::StaticClass(); + // find object UClass rather than UBlueprint + // https://forums.unrealengine.com/t/cdo-constructor-failed-to-find-thirdperson-c-template-mannequin-animbp/99003 + static ConstructorHelpers::FObjectFinder WeatherBP( + TEXT("/Game/Carla/Blueprints/Weather/BP_Weather.BP_Weather_C")); + this->WeatherClass = WeatherBP.Object; + + // initialize actor factories + // https://forums.unrealengine.com/t/what-is-the-right-syntax-of-fclassfinder-and-how-could-i-generaly-use-it-to-find-a-specific-blueprint/363884 + static ConstructorHelpers::FClassFinder VehicleFactoryBP( + TEXT("Blueprint'/Game/Carla/Blueprints/Vehicles/VehicleFactory'")); + static ConstructorHelpers::FClassFinder WalkerFactoryBP( + TEXT("Blueprint'/Game/Carla/Blueprints/Walkers/WalkerFactory'")); + static ConstructorHelpers::FClassFinder PropFactoryBP( + TEXT("Blueprint'/Game/Carla/Blueprints/Props/PropFactory'")); + + this->ActorFactories = TSet>{ + VehicleFactoryBP.Class, + ASensorFactory::StaticClass(), + WalkerFactoryBP.Class, + PropFactoryBP.Class, + ATriggerFactory::StaticClass(), + AAIControllerFactory::StaticClass(), + AStaticMeshFactory::StaticClass(), + ADReyeVRFactory::StaticClass(), // this is what registers the DReyeVR actors + }; + + // read config variables + ReadConfigValue("Game", "AutomaticallySpawnEgo", bDoSpawnEgoVehicle); + ReadConfigValue("Game", "EgoVolumePercent", EgoVolumePercent); + ReadConfigValue("Game", "NonEgoVolumePercent", NonEgoVolumePercent); + ReadConfigValue("Game", "AmbientVolumePercent", AmbientVolumePercent); + ReadConfigValue("Game", "DoSpawnEgoVehicleTransform", bDoSpawnEgoVehicleTransform); + ReadConfigValue("Game", "SpawnEgoVehicleTransform", SpawnEgoVehicleTransform); + + // Recorder/replayer + bool bEnableReplayInterpolation = false; + ReadConfigValue("Replayer", "ReplayInterpolation", bEnableReplayInterpolation); + bReplaySync = !bEnableReplayInterpolation; // synchronous => no interpolation! +} + +void ADReyeVRGameMode::BeginPlay() +{ + Super::BeginPlay(); + + // Initialize player + Player = UGameplayStatics::GetPlayerController(GetWorld(), 0); + + // Can we tick? + SetActorTickEnabled(false); // make sure we do not tick ourselves + + // set all the volumes (ego, non-ego, ambient/world) + SetVolume(); + + // start input mapping + SetupPlayerInputComponent(); + + // spawn the DReyeVR pawn and possess it + SetupDReyeVRPawn(); + + // Initialize DReyeVR spectator + SetupSpectator(); + + // Initialize the DReyeVR EgoVehicle (and Sensor) + SetupEgoVehicle(); +} + +void ADReyeVRGameMode::SetupDReyeVRPawn() +{ + FActorSpawnParameters SpawnParams; + SpawnParams.Owner = this; + SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + DReyeVR_Pawn = GetWorld()->SpawnActor(FVector::ZeroVector, FRotator::ZeroRotator, SpawnParams); + /// NOTE: the pawn is automatically possessed by player0 + // as the constructor has the AutoPossessPlayer != disabled + // if you want to manually possess then you can do Player->Possess(DReyeVR_Pawn); + if (DReyeVR_Pawn == nullptr) + { + LOG_ERROR("Unable to spawn DReyeVR pawn!") + } + else + { + DReyeVR_Pawn->BeginPlayer(Player); + LOG("Successfully spawned DReyeVR pawn"); + } +} + +bool ADReyeVRGameMode::SetupEgoVehicle() +{ + if (EgoVehiclePtr != nullptr || bDoSpawnEgoVehicle == false) + { + LOG("Not spawning new EgoVehicle"); + if (EgoVehiclePtr == nullptr) + { + LOG("EgoVehicle unavailable, possessing spectator by default") + PossessSpectator(); // NOTE: need to call SetupSpectator before this! + } + return true; + } + ensure(DReyeVR_Pawn); + + TArray FoundActors; + UGameplayStatics::GetAllActorsOfClass(GetWorld(), AEgoVehicle::StaticClass(), FoundActors); + if (FoundActors.Num() > 0) + { + for (AActor *Vehicle : FoundActors) + { + LOG("Found EgoVehicle in world: %s", *(Vehicle->GetName())); + EgoVehiclePtr = CastChecked(Vehicle); + /// TODO: handle multiple ego-vehcles? (we should only ever have one!) + break; + } + } + else + { + LOG("Did not find EgoVehicle in map... spawning..."); + // use the provided transform if requested, else generate a spawn point + FTransform SpawnPt = bDoSpawnEgoVehicleTransform ? SpawnEgoVehicleTransform : GetSpawnPoint(); + SpawnEgoVehicle(SpawnPt); // constructs and assigns EgoVehiclePtr + } + + // finalize the EgoVehicle by installing the DReyeVR_Pawn to control it + check(EgoVehiclePtr != nullptr); + return (EgoVehiclePtr != nullptr); +} + +void ADReyeVRGameMode::SetupSpectator() +{ + { // look for existing spectator in world + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + if (Episode != nullptr) + SpectatorPtr = Episode->GetSpectatorPawn(); + else if (Player != nullptr) + { + SpectatorPtr = Player->GetPawn(); + } + } + + // spawn if necessary + if (SpectatorPtr != nullptr) + { + LOG("Found available spectator in world"); + } + else + { + LOG_WARN("No available spectator actor in world... spawning one"); + FVector SpawnLocn; + FRotator SpawnRotn; + if (EgoVehiclePtr != nullptr) + { + SpawnLocn = EgoVehiclePtr->GetCameraPosn(); + SpawnRotn = EgoVehiclePtr->GetCameraRot(); + } + // create new spectator pawn + FActorSpawnParameters SpawnParams; + SpawnParams.Owner = this; + SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; + SpawnParams.ObjectFlags |= RF_Transient; + SpectatorPtr = GetWorld()->SpawnActor(ASpectatorPawn::StaticClass(), // spectator + SpawnLocn, SpawnRotn, SpawnParams); + } + + if (SpectatorPtr) + { + SpectatorPtr->SetActorHiddenInGame(true); // make spectator invisible + SpectatorPtr->GetRootComponent()->DestroyPhysicsState(); // no physics (just no-clip) + SpectatorPtr->SetActorEnableCollision(false); // no collisions + LOG("Successfully initiated spectator actor"); + } +} + +void ADReyeVRGameMode::BeginDestroy() +{ + Super::BeginDestroy(); + LOG("Finished Game"); +} + +void ADReyeVRGameMode::Tick(float DeltaSeconds) +{ + Super::Tick(DeltaSeconds); + /// TODO: clean up replay init + if (!bRecorderInitiated) // can't do this in constructor + { + // Initialize recorder/replayer + SetupReplayer(); // once this is successfully run, it no longer gets executed + } + + DrawBBoxes(); +} + +void ADReyeVRGameMode::SetupPlayerInputComponent() +{ + InputComponent = NewObject(this); + InputComponent->RegisterComponent(); + // set up gameplay key bindings + check(InputComponent); + Player->PushInputComponent(InputComponent); // enable this InputComponent with the PlayerController + // InputComponent->BindAction("ToggleCamera", IE_Pressed, this, &ADReyeVRGameMode::ToggleSpectator); + InputComponent->BindAction("PlayPause_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayPlayPause); + InputComponent->BindAction("FastForward_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayFastForward); + InputComponent->BindAction("Rewind_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayRewind); + InputComponent->BindAction("Restart_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplayRestart); + InputComponent->BindAction("Incr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplaySpeedUp); + InputComponent->BindAction("Decr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::ReplaySlowDown); + // Driver Handoff examples + InputComponent->BindAction("EgoVehicle_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::PossessEgoVehicle); + InputComponent->BindAction("Spectator_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::PossessSpectator); + InputComponent->BindAction("AI_DReyeVR", IE_Pressed, this, &ADReyeVRGameMode::HandoffDriverToAI); +} + +void ADReyeVRGameMode::PossessEgoVehicle() +{ + if (EgoVehiclePtr == nullptr) + { + LOG_WARN("No EgoVehicle to possess! Attempting to remedy..."); + SetupEgoVehicle(); + if (EgoVehiclePtr == nullptr) + { + LOG_ERROR("Remedy failed, unable to possess EgoVehicle"); + return; + } + } + EgoVehiclePtr->SetAutopilot(false); + + if (DReyeVR_Pawn == nullptr) + { + LOG_WARN("No DReyeVR pawn to possess EgoVehicle! Attempting to remedy..."); + SetupDReyeVRPawn(); + if (DReyeVR_Pawn == nullptr) + { + LOG_ERROR("Remedy failed, unable to possess EgoVehicle"); + return; + } + return; + } + + { // check if already possessing EgoVehicle (DReyeVRPawn) + ensure(Player != nullptr); + if (Player->GetPawn() == DReyeVR_Pawn) + { + LOG("Currently possessing EgoVehicle"); + return; + } + } + + LOG("Possessing DReyeVR EgoVehicle"); + Player->Possess(DReyeVR_Pawn); +} + +void ADReyeVRGameMode::PossessSpectator() +{ + if (SpectatorPtr == nullptr) + { + LOG_WARN("No spectator to possess! Attempting to remedy..."); + SetupSpectator(); + if (SpectatorPtr == nullptr) + { + LOG_ERROR("Remedy failed, unable to possess spectator"); + return; + } + } + + { // check if already possessing spectator + ensure(Player != nullptr); + if (Player->GetPawn() == SpectatorPtr) + { + LOG("Already possessing Spectator"); + return; + } + } + + if (EgoVehiclePtr) + { + // spawn from EgoVehicle head position + const FVector &EgoLocn = EgoVehiclePtr->GetCameraPosn(); + const FRotator &EgoRotn = EgoVehiclePtr->GetCameraRot(); + SpectatorPtr->SetActorLocationAndRotation(EgoLocn, EgoRotn); + } + // repossess the ego vehicle + Player->Possess(SpectatorPtr); + LOG("Possessing spectator player"); +} + +void ADReyeVRGameMode::HandoffDriverToAI() +{ + if (EgoVehiclePtr == nullptr) + { + LOG_WARN("No EgoVehicle to handoff AI control! Attempting to remedy..."); + SetupEgoVehicle(); + if (EgoVehiclePtr == nullptr) + { + LOG_ERROR("Remedy failed, unable to access EgoVehicle"); + return; + } + } + + { // check if autopilot already enabled + if (EgoVehiclePtr->GetAutopilotStatus() == true) + { + LOG("EgoVehicle autopilot already on"); + return; + } + } + EgoVehiclePtr->SetAutopilot(true); + LOG("Enabling EgoVehicle Autopilot"); +} + +void ADReyeVRGameMode::ReplayPlayPause() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Toggle Replayer Play-Pause"); + Replayer->PlayPause(); + } +} + +void ADReyeVRGameMode::ReplayFastForward() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Advance replay by +1.0s"); + Replayer->Advance(1.0); + } +} + +void ADReyeVRGameMode::ReplayRewind() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Advance replay by -1.0s"); + Replayer->Advance(-1.0); + } +} + +void ADReyeVRGameMode::ReplayRestart() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + LOG("Restarting recording replay..."); + Replayer->Restart(); + } +} + +void ADReyeVRGameMode::ChangeTimestep(UWorld *World, double AmntChangeSeconds) +{ + if (bReplaySync) + { + LOG("Changing timestep of replay during a synchronous replay is not supported. Enable ReplayInterpolation to " + "achieve this.") + return; + } + ensure(World != nullptr); + auto *Replayer = UCarlaStatics::GetReplayer(World); + if (Replayer != nullptr && Replayer->IsEnabled()) + { + double NewFactor = ReplayTimeFactor + AmntChangeSeconds; + if (AmntChangeSeconds > 0) + { + if (NewFactor < ReplayTimeFactorMax) + { + LOG("Increase replay time factor: %.3fx -> %.3fx", ReplayTimeFactor, NewFactor); + Replayer->SetTimeFactor(NewFactor); + } + else + { + LOG("Unable to increase replay time factor (%.3f) beyond %.3fx", ReplayTimeFactor, ReplayTimeFactorMax); + Replayer->SetTimeFactor(ReplayTimeFactorMax); + } + } + else + { + if (NewFactor > ReplayTimeFactorMin) + { + LOG("Decrease replay time factor: %.3fx -> %.3fx", ReplayTimeFactor, NewFactor); + Replayer->SetTimeFactor(NewFactor); + } + else + { + LOG("Unable to decrease replay time factor (%.3f) below %.3fx", ReplayTimeFactor, ReplayTimeFactorMin); + Replayer->SetTimeFactor(ReplayTimeFactorMin); + } + } + ReplayTimeFactor = FMath::Clamp(NewFactor, ReplayTimeFactorMin, ReplayTimeFactorMax); + } +} + +void ADReyeVRGameMode::ReplaySpeedUp() +{ + ChangeTimestep(GetWorld(), AmntPlaybackIncr); +} + +void ADReyeVRGameMode::ReplaySlowDown() +{ + ChangeTimestep(GetWorld(), -AmntPlaybackIncr); +} + +void ADReyeVRGameMode::SetupReplayer() +{ + auto *Replayer = UCarlaStatics::GetReplayer(GetWorld()); + if (Replayer != nullptr) + { + Replayer->SetSyncMode(bReplaySync); + if (bReplaySync) + { + LOG_WARN("Replay operating in frame-wise (1:1) synchronous mode (no replay interpolation)"); + } + bRecorderInitiated = true; + } +} + +void ADReyeVRGameMode::DrawBBoxes() +{ +#if 0 + TArray FoundActors; + if (GetWorld() != nullptr) + { + UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); + } + for (AActor *A : FoundActors) + { + std::string name = TCHAR_TO_UTF8(*A->GetName()); + if (A->GetName().Contains("DReyeVR")) + continue; // skip drawing a bbox over the EgoVehicle + if (BBoxes.find(name) == BBoxes.end()) + { + BBoxes[name] = ADReyeVRCustomActor::CreateNew(SM_CUBE, MAT_TRANSLUCENT, GetWorld(), "BBox" + A->GetName()); + } + const float DistThresh = 20.f; // meters before nearby bounding boxes become red + ADReyeVRCustomActor *BBox = BBoxes[name]; + ensure(BBox != nullptr); + if (BBox != nullptr) + { + BBox->Activate(); + BBox->MaterialParams.Opacity = 0.1f; + FLinearColor Col = FLinearColor::Green; + if (FVector::Distance(EgoVehiclePtr->GetActorLocation(), A->GetActorLocation()) < DistThresh * 100.f) + { + Col = FLinearColor::Red; + } + BBox->MaterialParams.BaseColor = Col; + BBox->MaterialParams.Emissive = 0.1 * Col; + + FVector Origin; + FVector BoxExtent; + A->GetActorBounds(true, Origin, BoxExtent, false); + // LOG("Origin: %s Extent %s"), *Origin.ToString(), *BoxExtent.ToString()); + // divide by 100 to get from m to cm, multiply by 2 bc the cube is scaled in both X and Y + BBox->SetActorScale3D(2 * BoxExtent / 100.f); + BBox->SetActorLocation(Origin); + // extent already covers the rotation aspect since the bbox is dynamic and axis aligned + // BBox->SetActorRotation(A->GetActorRotation()); + } + } +#endif +} + +void ADReyeVRGameMode::ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per) +{ + // first spawn the actor if not currently active + const std::string ActorName = TCHAR_TO_UTF8(*RecorderData.Name); + ADReyeVRCustomActor *A = nullptr; + if (ADReyeVRCustomActor::ActiveCustomActors.find(ActorName) == ADReyeVRCustomActor::ActiveCustomActors.end()) + { + /// TODO: also track KnownNumMaterials? + A = ADReyeVRCustomActor::CreateNew(RecorderData.MeshPath, RecorderData.MaterialParams.MaterialPath, GetWorld(), + RecorderData.Name); + } + else + { + A = ADReyeVRCustomActor::ActiveCustomActors[ActorName]; + } + // ensure the actor is currently active (spawned) + // now that we know this actor exists, update its internals + if (A != nullptr) + { + A->SetInternals(RecorderData); + A->Activate(); + A->Tick(Per); // update locations immediately + } +} + +void ADReyeVRGameMode::SetVolume() +{ + // update the non-ego volume percent + ACarlaWheeledVehicle::Volume = NonEgoVolumePercent / 100.f; + + // for all in-world audio components such as ambient birdsong, fountain splashing, smoke, etc. + for (TObjectIterator Itr; Itr; ++Itr) + { + if (Itr->GetWorld() != GetWorld()) // World Check + { + continue; + } + Itr->SetVolumeMultiplier(AmbientVolumePercent / 100.f); + } + + // for all in-world vehicles (including the EgoVehicle) manually set their volumes + TArray FoundActors; + UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); + for (AActor *A : FoundActors) + { + ACarlaWheeledVehicle *Vehicle = Cast(A); + if (Vehicle != nullptr) + { + float NewVolume = ACarlaWheeledVehicle::Volume; // Non ego volume + if (Vehicle->IsA(AEgoVehicle::StaticClass())) // dynamic cast, requires -frrti + NewVolume = EgoVolumePercent / 100.f; + Vehicle->SetVolume(NewVolume); + } + } +} + +void ADReyeVRGameMode::SpawnEgoVehicle(const FTransform &SpawnPt) +{ + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + check(Episode != nullptr); + FActorDefinition EgoVehicleDefn = FindDefnInRegistry(Episode, AEgoVehicle::StaticClass()); + FActorDescription DReyeVRDescr; + { // create a Description from the Definition to spawn the actor + DReyeVRDescr.UId = EgoVehicleDefn.UId; + DReyeVRDescr.Id = EgoVehicleDefn.Id; + DReyeVRDescr.Class = EgoVehicleDefn.Class; + // ensure this vehicle is denoted by the 'hero' attribute + FActorAttribute HeroRole; + HeroRole.Id = "role_name"; + HeroRole.Type = EActorAttributeType::String; + HeroRole.Value = "hero"; + DReyeVRDescr.Variations.Add(HeroRole.Id, std::move(HeroRole)); + } + + if (Episode == nullptr) + { + LOG_ERROR("Null Episode in world!"); + } + // calls Episode::SpawnActor => SpawnActorWithInfo => ActorDispatcher->SpawnActor => SpawnFunctions[UId] + EgoVehiclePtr = static_cast(Episode->SpawnActor(SpawnPt, DReyeVRDescr)); +} + +FTransform ADReyeVRGameMode::GetSpawnPoint(int SpawnPointIndex) const +{ + ACarlaGameModeBase *GM = UCarlaStatics::GetGameMode(GetWorld()); + if (GM != nullptr) + { + TArray SpawnPoints = GM->GetSpawnPointsTransforms(); + size_t WhichPoint = 0; // default to first one + if (SpawnPointIndex < 0) + WhichPoint = FMath::RandRange(0, SpawnPoints.Num()); + else + WhichPoint = FMath::Clamp(SpawnPointIndex, 0, SpawnPoints.Num()); + + if (WhichPoint < SpawnPoints.Num()) // SpawnPoints could be empty + return SpawnPoints[WhichPoint]; + } + /// TODO: return a safe bet (position of the player start maybe?) + return FTransform(FRotator::ZeroRotator, FVector::ZeroVector, FVector::OneVector); +} \ No newline at end of file diff --git a/DReyeVR/DReyeVRGameMode.h b/DReyeVR/DReyeVRGameMode.h new file mode 100644 index 0000000..cc0c9ac --- /dev/null +++ b/DReyeVR/DReyeVRGameMode.h @@ -0,0 +1,97 @@ +#pragma once + +#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor +#include "Carla/Game/CarlaGameModeBase.h" // ACarlaGameModeBase +#include "Carla/Sensor/DReyeVRData.h" // DReyeVR:: +#include // std::unordered_map + +#include "DReyeVRGameMode.generated.h" + +class AEgoVehicle; +class ADReyeVRPawn; + +UCLASS() +class ADReyeVRGameMode : public ACarlaGameModeBase +{ + GENERATED_UCLASS_BODY() + + public: + ADReyeVRGameMode(); + + virtual void BeginPlay() override; + + virtual void BeginDestroy() override; + + virtual void Tick(float DeltaSeconds) override; + + ADReyeVRPawn *GetPawn() + { + return DReyeVR_Pawn; + } + + void SetEgoVehicle(AEgoVehicle *Vehicle) + { + EgoVehiclePtr = Vehicle; + } + + // input handling + void SetupPlayerInputComponent(); + + // EgoVehicle functions + void PossessEgoVehicle(); + void PossessSpectator(); + void HandoffDriverToAI(); + + // Replay media functions + void ChangeTimestep(UWorld *World, double AmntChangeSeconds); + void ReplayPlayPause(); + void ReplayFastForward(); + void ReplayRewind(); + void ReplayRestart(); + void ReplaySpeedUp(); + void ReplaySlowDown(); + + // Replayer + void SetupReplayer(); + + // Meta world functions + void SetVolume(); + FTransform GetSpawnPoint(int SpawnPointIndex = 0) const; + + // Custom actors + void ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per); + void DrawBBoxes(); + std::unordered_map BBoxes; + + private: + bool bDoSpawnEgoVehicle = true; // spawn Ego on BeginPlay or not + + // for handling inputs and possessions + void SetupDReyeVRPawn(); + void SetupSpectator(); + bool SetupEgoVehicle(); + void SpawnEgoVehicle(const FTransform &SpawnPt); + class APlayerController *Player = nullptr; + class ADReyeVRPawn *DReyeVR_Pawn = nullptr; + + // for toggling bw spectator mode + bool bIsSpectating = true; + class APawn *SpectatorPtr = nullptr; + class AEgoVehicle *EgoVehiclePtr = nullptr; + + // for audio control + float EgoVolumePercent; + float NonEgoVolumePercent; + float AmbientVolumePercent; + + bool bDoSpawnEgoVehicleTransform = false; // whether or not to use provided SpawnEgoVehicleTransform + FTransform SpawnEgoVehicleTransform; + + // for recorder/replayer params + const double AmntPlaybackIncr = 0.25; // how much the playback speed changes (multiplicative, ex: 1x + 0.1 = 1.1x) + double ReplayTimeFactor = 1.0; // same as CarlaReplayer.h::TimeFactor (but local) + double ReplayTimeFactorMin = 0.0; // minimum playback of 0 (paused) + double ReplayTimeFactorMax = 4.0; // maximum of 4.0x playback + bool bReplaySync = false; // false allows for interpolation + bool bRecorderInitiated = false; // allows tick-wise checking for replayer/recorder +}; \ No newline at end of file diff --git a/DReyeVR/DReyeVRPawn.cpp b/DReyeVR/DReyeVRPawn.cpp index 0d4cf53..d60669a 100644 --- a/DReyeVR/DReyeVRPawn.cpp +++ b/DReyeVR/DReyeVRPawn.cpp @@ -1,5 +1,5 @@ #include "DReyeVRPawn.h" -#include "DReyeVRUtils.h" // ProjectGazeToScreen, CreatePostProcessingEffect +#include "DReyeVRUtils.h" // CreatePostProcessingEffect #include "HeadMountedDisplayFunctionLibrary.h" // SetTrackingOrigin, GetWorldToMetersScale #include "HeadMountedDisplayTypes.h" // ESpectatorScreenMode #include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic @@ -22,6 +22,9 @@ ADReyeVRPawn::ADReyeVRPawn(const FObjectInitializer &ObjectInitializer) : Super( // spawn and construct the first person camera ConstructCamera(); + + // log + LOG("Spawning DReyeVR pawn for player0"); } void ADReyeVRPawn::ReadConfigVariables() @@ -70,7 +73,16 @@ void ADReyeVRPawn::BeginPlay() ensure(World != nullptr); } -void ADReyeVRPawn::BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World, APlayerController *PlayerIn) +void ADReyeVRPawn::BeginPlayer(APlayerController *PlayerIn) +{ + Player = PlayerIn; + ensure(Player != nullptr); + + // Setup the HUD + InitFlatHUD(); +} + +void ADReyeVRPawn::BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World) { /// NOTE: this should be run very early! // before anything that needs the EgoVehicle pointer (since this initializes it!) @@ -79,17 +91,12 @@ void ADReyeVRPawn::BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World, APlayerC ensure(EgoVehicle != nullptr); EgoVehicle->SetPawn(this); - Player = PlayerIn; - ensure(Player != nullptr); - // register inputs that require EgoVehicle ensure(InputComponent != nullptr); SetupEgoVehicleInputComponent(InputComponent, EgoVehicle); + check(World != nullptr); FirstPersonCam->RegisterComponentWithWorld(World); - - // Setup the HUD - InitFlatHUD(Player); } void ADReyeVRPawn::BeginDestroy() @@ -109,6 +116,9 @@ void ADReyeVRPawn::Tick(float DeltaTime) // Tick the logitech wheel TickLogiWheel(); + + // Tick spectator screen + TickSpectatorScreen(DeltaTime); } /// ========================================== /// @@ -122,7 +132,7 @@ void ADReyeVRPawn::InitSteamVR() { FString HMD_Name = UHeadMountedDisplayFunctionLibrary::GetHMDDeviceName().ToString(); FString HMD_Version = UHeadMountedDisplayFunctionLibrary::GetVersionString(); - UE_LOG(LogTemp, Log, TEXT("HMD enabled: %s, version %s"), *HMD_Name, *HMD_Version); + LOG("SteamVR HMD enabled: %s, version %s", *HMD_Name, *HMD_Version); // Now we'll begin with setting up the VR Origin logic // this tracking origin is what moves the HMD camera to the right position UHeadMountedDisplayFunctionLibrary::SetTrackingOrigin(EHMDTrackingOrigin::Eye); // Also have Floor & Stage Level @@ -130,7 +140,7 @@ void ADReyeVRPawn::InitSteamVR() } else { - UE_LOG(LogTemp, Warning, TEXT("No head mounted device enabled!")); + LOG_WARN("No SteamVR head mounted device enabled!"); } } @@ -186,15 +196,25 @@ void ADReyeVRPawn::InitSpectator() } } -void ADReyeVRPawn::DrawSpectatorScreen(const FVector &GazeOrigin, const FVector &GazeDir) +void ADReyeVRPawn::TickSpectatorScreen(float DeltaSeconds) { - if (!bEnableSpectatorScreen || Player == nullptr || !bIsHMDConnected) - return; - - FVector2D ReticlePos = ProjectGazeToScreen(Player, GetCamera(), GazeOrigin, GazeDir); + // first draw the UE4 spectator screen (the flat-screen window during VR-play) + if (bIsHMDConnected) + { + // Draw the spectator vr screen and overlay elements + DrawSpectatorScreen(); + } + else // or overlay the HUD on the render window (flat-screen) if not playing in VR + { + // draws flat screen HUD if not in VR + DrawFlatHUD(DeltaSeconds); + } +} - /// NOTE: we like using this constant offset for visualization - ReticlePos += FVector2D(0.f, -0.5f * ReticleSize); // move reticle up by size/2 (texture in quadrant 4) +void ADReyeVRPawn::DrawSpectatorScreen() +{ + if (!bEnableSpectatorScreen || !Player || !EgoVehicle || !bIsHMDConnected) + return; // calculate View size (of open window). Note this is not the same as resolution FIntPoint ViewSize; @@ -203,10 +223,22 @@ void ADReyeVRPawn::DrawSpectatorScreen(const FVector &GazeOrigin, const FVector /// TODO: draw other things on the spectator screen? if (bDrawSpectatorReticle) { + // project the 3D world point to 2D using the player's viewport + FVector2D ReticlePos; + { + // get where in the world the intersection occurs + const FVector HitPoint = EgoVehicle->GetSensor()->GetData()->GetFocusActorPoint(); + bool bPlayerViewportRelative = true; + UGameplayStatics::ProjectWorldToScreen(Player, HitPoint, ReticlePos, bPlayerViewportRelative); + } + + /// HACK: correct for offset likely due to using left eye for camera projection + ReticlePos.X += 0.3f * ReticleSize; + /// NOTE: the SetSpectatorScreenModeTexturePlusEyeLayout expects normalized positions on the screen // define min and max bounds (where the texture is actually drawn on screen) - const FVector2D TextureRectMin = ReticlePos / ViewSize; // top left - const FVector2D TextureRectMax = (ReticlePos + ReticleSize) / ViewSize; // bottom right + const FVector2D TextureRectMin = (ReticlePos - 0.5f * ReticleSize) / ViewSize; // top left + const FVector2D TextureRectMax = (ReticlePos + 0.5f * ReticleSize) / ViewSize; // bottom right auto Within01 = [](const float Num) { return 0.f <= Num && Num <= 1.f; }; bool RectMinValid = Within01(TextureRectMin.X) && Within01(TextureRectMin.Y); bool RectMaxValid = Within01(TextureRectMax.X) && Within01(TextureRectMax.Y); @@ -232,15 +264,16 @@ void ADReyeVRPawn::DrawSpectatorScreen(const FVector &GazeOrigin, const FVector /// ----------------:FLATHUD:----------------- /// /// ========================================== /// -void ADReyeVRPawn::InitFlatHUD(APlayerController *P) +void ADReyeVRPawn::InitFlatHUD() { - check(P); - AHUD *Raw_HUD = P->GetHUD(); + check(Player); + class AHUD *Raw_HUD = Player->GetHUD(); + ensure(Raw_HUD); FlatHUD = Cast(Raw_HUD); if (FlatHUD) - FlatHUD->SetPlayer(P); + FlatHUD->SetPlayer(Player); else - UE_LOG(LogTemp, Warning, TEXT("Unable to initialize DReyeVR HUD!")); + LOG_WARN("Unable to initialize DReyeVR HUD!"); // make sure to disable the flat hud when in VR (not supported, only displays on half of one eye screen) if (bIsHMDConnected) { @@ -248,39 +281,46 @@ void ADReyeVRPawn::InitFlatHUD(APlayerController *P) } } -void ADReyeVRPawn::DrawFlatHUD(float DeltaSeconds, const FVector &GazeOrigin, const FVector &GazeDir) +void ADReyeVRPawn::DrawFlatHUD(float DeltaSeconds) { - if (FlatHUD == nullptr || Player == nullptr || bDrawFlatHud == false || bIsHMDConnected == true) + if (!FlatHUD || !Player || !EgoVehicle || !bDrawFlatHud || bIsHMDConnected) return; - const FVector &WorldPos = GetCamera()->GetComponentLocation(); - const FRotator &WorldRot = GetCamera()->GetComponentRotation(); - const float RayLengthScale = 10.f * 100.f; // 10m ray length - const FVector TargetStart = WorldPos + WorldRot.RotateVector(GazeOrigin); - const FVector TargetEnd = TargetStart + RayLengthScale * WorldRot.RotateVector(GazeDir); - // calculate View size (of open window). Note this is not the same as resolution FIntPoint ViewSize; Player->GetViewportSize(ViewSize.X, ViewSize.Y); - // Get eye tracker variables + + const auto *SensorData = EgoVehicle->GetSensor()->GetData(); + check(SensorData != nullptr); // Draw elements of the HUD if (bDrawFlatReticle) // Draw reticle on flat-screen HUD { + // get where in the world the intersection occurs + const FVector HitPoint = SensorData->GetFocusActorPoint(); + const float Diameter = ReticleSize; const float Thickness = (ReticleSize / 2.f) / 10.f; // 10 % of radius // FlatHUD->DrawDynamicSquare(GazeEnd, Diameter, FColor(255, 0, 0, 255), Thickness); - FlatHUD->DrawDynamicCrosshair(TargetEnd, Diameter, FColor(255, 0, 0, 255), true, Thickness); + FlatHUD->DrawDynamicCrosshair(HitPoint, Diameter, FColor(255, 0, 0, 255), true, Thickness); } + if (bDrawFPSCounter) { FlatHUD->DrawDynamicText(FString::FromInt(int(1.f / DeltaSeconds)), FVector2D(ViewSize.X - 100, 50), FColor(0, 255, 0, 213), 2); } + if (bDrawGaze) { + const FVector &WorldPos = GetCamera()->GetComponentLocation(); + const FRotator &WorldRot = GetCamera()->GetComponentRotation(); + const FVector &GazeOrigin = SensorData->GetGazeOrigin(); + const FVector RayStart = WorldPos + WorldRot.RotateVector(GazeOrigin); + const FVector RayEnd = SensorData->GetFocusActorPoint(); + // Draw line components in FlatHUD - FlatHUD->DrawDynamicLine(TargetStart, TargetEnd, FColor::Red, 3.0f); + FlatHUD->DrawDynamicLine(RayStart, RayEnd, FColor::Red, 3.0f); } } @@ -299,13 +339,13 @@ void ADReyeVRPawn::InitLogiWheel() wchar_t *NameBuffer = (wchar_t *)malloc(n * sizeof(wchar_t)); if (LogiGetFriendlyProductName(WheelDeviceIdx, NameBuffer, n) == false) { - UE_LOG(LogTemp, Warning, TEXT("Unable to get Logi friendly name!")); + LOG_WARN("Unable to get Logi friendly name!"); NameBuffer = L"Unknown"; } std::wstring wNameStr(NameBuffer, n); std::string NameStr(wNameStr.begin(), wNameStr.end()); FString LogiName(NameStr.c_str()); - UE_LOG(LogTemp, Log, TEXT("Found a Logitech device (%s) connected on input %d"), *LogiName, WheelDeviceIdx); + LOG("Found a Logitech device (%s) connected on input %d", *LogiName, WheelDeviceIdx); free(NameBuffer); // no longer needed } else @@ -317,7 +357,7 @@ void ADReyeVRPawn::InitLogiWheel() const FLinearColor MsgColour = FLinearColor(1, 0, 0, 1); // RED UKismetSystemLibrary::PrintString(World, LogiError, PrintToScreen, PrintToLog, MsgColour, ScreenDurationSec); if (PrintToLog) - UE_LOG(LogTemp, Warning, TEXT("%s"), *LogiError); // Error is RED + LOG_ERROR("%s", *LogiError); // Error is RED } #endif } @@ -408,10 +448,10 @@ void ADReyeVRPawn::LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now) { if (!isDiff) // only gets triggered at MOST once { - UE_LOG(LogTemp, Log, TEXT("Logging joystick at t=%.3f"), UGameplayStatics::GetRealTimeSeconds(World)); + LOG("Logging joystick at t=%.3f", UGameplayStatics::GetRealTimeSeconds(World)); isDiff = true; } - UE_LOG(LogTemp, Log, TEXT("Triggered \"%s\" from %d to %d"), *(VarNames[i]), OldVals[i], NowVals[i]); + LOG("Triggered \"%s\" from %d to %d", *(VarNames[i]), OldVals[i], NowVals[i]); } } @@ -422,11 +462,10 @@ void ADReyeVRPawn::LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now) { if (!isDiff) // only gets triggered at MOST once { - UE_LOG(LogTemp, Log, TEXT("Logging joystick at t=%.3f"), UGameplayStatics::GetRealTimeSeconds(World)); + LOG("Logging joystick at t=%.3f", UGameplayStatics::GetRealTimeSeconds(World)); isDiff = true; } - UE_LOG(LogTemp, Log, TEXT("Triggered \"rgbButtons[%d]\" from %d to %d"), int(i), int(OldVals[i]), - int(NowVals[i])); + LOG("Triggered \"rgbButtons[%d]\" from %d to %d", int(i), int(OldVals[i]), int(NowVals[i])); } } @@ -441,7 +480,7 @@ void ADReyeVRPawn::LogitechWheelUpdate() // only execute this in Windows, the Logitech plugin is incompatible with Linux if (LogiUpdate() == false) // update the logitech wheel - UE_LOG(LogTemp, Warning, TEXT("Logitech wheel %d failed to update!"), WheelDeviceIdx); + LOG_WARN("Logitech wheel %d failed to update!", WheelDeviceIdx); DIJOYSTATE2 *WheelState = LogiGetState(WheelDeviceIdx); if (bLogLogitechWheel) LogLogitechPluginStruct(WheelState); @@ -588,7 +627,7 @@ void ADReyeVRPawn::SetupPlayerInputComponent(UInputComponent *PlayerInputCompone void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputComponent, AEgoVehicle *EV) { - UE_LOG(LogTemp, Log, TEXT("Initializing EgoVehicle relay mechanisms")); + LOG("Initializing EgoVehicle relay mechanisms"); // this function sets up the direct relay mechanisms to call EgoVehicle input functions check(PlayerInputComponent != nullptr); check(EV != nullptr); @@ -622,7 +661,7 @@ void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputCom if (EgoVehicle) \ FUNCTION; \ else \ - UE_LOG(LogTemp, Error, TEXT("EgoVehicle is NULL!")); + LOG_ERROR("EgoVehicle is NULL!"); void ADReyeVRPawn::SetThrottleKbd(const float ThrottleInput) { @@ -652,8 +691,8 @@ void ADReyeVRPawn::SetSteeringKbd(const float SteeringInput) else { // so the steering wheel does go to 0 when letting go - ensure(EgoVehicle != nullptr); - EgoVehicle->VehicleInputs.Steering = 0; + if (EgoVehicle != nullptr) + EgoVehicle->VehicleInputs.Steering = 0; } } diff --git a/DReyeVR/DReyeVRPawn.h b/DReyeVR/DReyeVRPawn.h index 2196894..0ab0dc2 100644 --- a/DReyeVR/DReyeVRPawn.h +++ b/DReyeVR/DReyeVRPawn.h @@ -28,7 +28,8 @@ class ADReyeVRPawn : public APawn virtual void SetupPlayerInputComponent(UInputComponent *PlayerInputComponent) override; virtual void Tick(float DeltaSeconds) override; - void BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World, APlayerController *PlayerIn); + void BeginPlayer(APlayerController *PlayerIn); + void BeginEgoVehicle(AEgoVehicle *Vehicle, UWorld *World); APlayerController *GetPlayer() { @@ -50,9 +51,6 @@ class ADReyeVRPawn : public APawn return bIsLogiConnected; } - void DrawSpectatorScreen(const FVector &GazeOrigin, const FVector &GazeDir); - void DrawFlatHUD(float DeltaSeconds, const FVector &GazeOrigin, const FVector &GazeDir); - protected: virtual void BeginPlay() override; virtual void BeginDestroy() override; @@ -71,6 +69,10 @@ class ADReyeVRPawn : public APawn void PrevShader(); size_t CurrentShaderIdx = 0; // 0th shader is rgb (camera) + void TickSpectatorScreen(float DeltaSeconds); // to render the spectator screen (VR) or flat-screen hud (non-VR) + void DrawSpectatorScreen(); + void DrawFlatHUD(float DeltaSeconds); + ////////////////:STEAMVR://////////////// void InitSteamVR(); // Initialize the Head Mounted Display void InitSpectator(); // Initialize the VR spectator @@ -81,7 +83,7 @@ class ADReyeVRPawn : public APawn ////////////////:FLATHUD://////////////// // (Flat) HUD (NOTE: ONLY FOR NON VR) - void InitFlatHUD(APlayerController *P); + void InitFlatHUD(); UPROPERTY(Category = HUD, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class ADReyeVRHUD *FlatHUD; FVector2D ReticlePos; // 2D reticle position from eye gaze diff --git a/DReyeVR/DReyeVRUtils.h b/DReyeVR/DReyeVRUtils.h index 2f65734..ba7181b 100644 --- a/DReyeVR/DReyeVRUtils.h +++ b/DReyeVR/DReyeVRUtils.h @@ -17,7 +17,52 @@ static const FString ConfigFilePath = FPaths::Combine(FPaths::ConvertRelativePathToFull(FPaths::ProjectDir()), TEXT("Config"), TEXT("DReyeVRConfig.ini")); -static std::unordered_map Params = {}; +struct ParamString +{ + ParamString() = default; + + FString DataStr = ""; // string representation of the data to parse into primitives + bool bIsDirty = true; // whether or not the data has been read (clean) or not (dirty) + + template inline T DecipherToType() const + { + // supports FVector, FVector2D, FLinearColor, FQuat, and FRotator, + // basically any UE4 type that has a ::InitFromString method + T Ret; + if (Ret.InitFromString(DataStr) == false) + { + LOG_ERROR("Unable to decipher \"%s\" to a type", *DataStr); + } + return Ret; + } + + template <> inline bool DecipherToType() const + { + return DataStr.ToBool(); + } + + template <> inline int DecipherToType() const + { + return FCString::Atoi(*DataStr); + } + + template <> inline float DecipherToType() const + { + return FCString::Atof(*DataStr); + } + + template <> inline FString DecipherToType() const + { + return DataStr; + } + + template <> inline FName DecipherToType() const + { + return FName(*DataStr); + } +}; + +static std::unordered_map Params = {}; static std::string CreateVariableName(const std::string &Section, const std::string &Variable) { @@ -31,7 +76,7 @@ static std::string CreateVariableName(const FString &Section, const FString &Var static void ReadDReyeVRConfig() { /// TODO: add feature to "hot-reload" new params during runtime - UE_LOG(LogTemp, Warning, TEXT("Reading config from %s"), *ConfigFilePath); + LOG_WARN("Reading config from %s", *ConfigFilePath); /// performs a single pass over the config file to collect all variables into Params std::ifstream ConfigFile(TCHAR_TO_ANSI(*ConfigFilePath)); if (ConfigFile) @@ -41,7 +86,7 @@ static void ReadDReyeVRConfig() while (std::getline(ConfigFile, Line)) { // std::string stdKey = std::string(TCHAR_TO_UTF8(*Key)); - if (Line[0] == ';') // ignore comments + if (Line[0] == '#' || Line[0] == ';') // ignore comments continue; std::istringstream iss_Line(Line); if (Line[0] == '[') // test section @@ -54,21 +99,21 @@ static void ReadDReyeVRConfig() if (std::getline(iss_Line, Key, '=')) // gets left side of '=' into FileKey { std::string Value; - if (std::getline(iss_Line, Value, ';')) // gets left side of ';' for comments + if (std::getline(iss_Line, Value, '#')) // gets left side of '#' for comments { std::string VariableName = CreateVariableName(Section, Key); - FString VariableValue = FString(Value.c_str()); - Params[VariableName] = VariableValue; + bool bHasQuotes = false; + Params[VariableName].DataStr = FString(Value.c_str()).TrimStartAndEnd().TrimQuotes(&bHasQuotes); } } } } else { - UE_LOG(LogTemp, Error, TEXT("Unable to open the config file %s"), *ConfigFilePath); + LOG_ERROR("Unable to open the config file %s", *ConfigFilePath); } // for (auto &e : Params){ - // UE_LOG(LogTemp, Warning, TEXT("%s: %s"), *FString(e.first.c_str()), *e.second); + // LOG_WARN("%s: %s", *FString(e.first.c_str()), *e.second); // } } @@ -79,108 +124,47 @@ static void EnsureConfigsUpdated() ReadDReyeVRConfig(); } -static void ReadConfigValue(const FString &Section, const FString &Variable, bool &Value) -{ - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) - Value = Params[VariableName].ToBool(); - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} -static void ReadConfigValue(const FString &Section, const FString &Variable, int &Value) -{ - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) - Value = FCString::Atoi(*Params[VariableName]); - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} -static void ReadConfigValue(const FString &Section, const FString &Variable, float &Value) -{ - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) - Value = FCString::Atof(*Params[VariableName]); - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} -static void ReadConfigValue(const FString &Section, const FString &Variable, FVector &Value) +template static void ReadConfigValue(const FString &Section, const FString &Variable, T &Value) { EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) + const std::string VariableName = CreateVariableName(Section, Variable); + if (Params.find(VariableName) == Params.end()) { - if (Value.InitFromString(Params[VariableName]) == false) - { - UE_LOG(LogTemp, Error, TEXT("Unable to construct FVector for %s from %s"), *FString(VariableName.c_str()), - *(Params[VariableName])); - } + LOG_ERROR("No variable matching \"%s\" found for type", *FString(VariableName.c_str())); + return; } - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} -static void ReadConfigValue(const FString &Section, const FString &Variable, FVector2D &Value) -{ - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) + auto &Param = Params[VariableName]; + Value = Param.DecipherToType(); + + if (Param.bIsDirty) { - if (Value.InitFromString(Params[VariableName]) == false) - { - UE_LOG(LogTemp, Error, TEXT("Unable to construct FVector2D for %s from %s"), *FString(VariableName.c_str()), - *(Params[VariableName])); - } + LOG("Read \"%s\" => %s", *FString(VariableName.c_str()), *Param.DataStr); } - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); + Param.bIsDirty = false; // has just been read } -static void ReadConfigValue(const FString &Section, const FString &Variable, FLinearColor &Value) + +static FActorDefinition FindDefnInRegistry(const UCarlaEpisode *Episode, const UClass *ClassType) { - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) + // searches through the registers actors (definitions) to find one with the matching class type + check(Episode != nullptr); + + FActorDefinition FoundDefinition; + bool bFoundDef = false; + for (const auto &Defn : Episode->GetActorDefinitions()) { - if (Value.InitFromString(Params[VariableName]) == false) + if (Defn.Class == ClassType) { - UE_LOG(LogTemp, Error, TEXT("Unable to construct FLinearColor for %s from %s"), *FString(VariableName.c_str()), - *(Params[VariableName])); + LOG("Found appropriate definition registered at UId: %d as \"%s\"", Defn.UId, *Defn.Id); + FoundDefinition = Defn; + bFoundDef = true; + break; // assumes the first is the ONLY one matching this class (Ex. EgoVehicle, EgoSensor) } } - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} -static void ReadConfigValue(const FString &Section, const FString &Variable, FRotator &Value) -{ - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) + if (!bFoundDef) { - if (Value.InitFromString(Params[VariableName]) == false) - { - UE_LOG(LogTemp, Error, TEXT("Unable to construct FRotator for %s from %s"), *FString(VariableName.c_str()), - *(Params[VariableName])); - } + LOG_ERROR("Unable to find appropriate definition in registry!"); } - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} -static void ReadConfigValue(const FString &Section, const FString &Variable, FString &Value) -{ - EnsureConfigsUpdated(); - std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) != Params.end()) - Value = Params[VariableName]; - else - UE_LOG(LogTemp, Error, TEXT("No variable matching %s found"), *FString(VariableName.c_str())); -} - -static void ReadConfigValue(const FString &Section, const FString &Variable, FName &Value) -{ - FString TmpValueString; - ReadConfigValue(Section, Variable, TmpValueString); - Value = FName(*TmpValueString); + return FoundDefinition; } static FVector ComputeClosestToRayIntersection(const FVector &L0, const FVector &LDir, const FVector &R0, @@ -283,26 +267,6 @@ static void GenerateCrosshairImage(TArray &Src, const float Size, const } } -static FVector2D ProjectGazeToScreen(const APlayerController *Player, const UCameraComponent *Camera, - const FVector &InOrigin, const FVector &InDir, bool bPlayerViewportRelative = true) -{ - if (Player == nullptr) - return FVector2D::ZeroVector; - - // compute the 3D world point of the InOrigin + InDir - const FVector &WorldPos = Camera->GetComponentLocation(); - const FRotator &WorldRot = Camera->GetComponentRotation(); - const FVector Origin = WorldPos + WorldRot.RotateVector(InOrigin); - const FVector GazeDir = 100.f * WorldRot.RotateVector(InDir); - const FVector WorldPoint = Origin + GazeDir; - - FVector2D ProjectedCoords; - // first project the 3D point to 2D using the player's viewport - UGameplayStatics::ProjectWorldToScreen(Player, WorldPoint, ProjectedCoords, bPlayerViewportRelative); - - return ProjectedCoords; -} - static float CmPerSecondToXPerHour(const bool MilesPerHour) { // convert cm/s to X/h @@ -330,18 +294,18 @@ static void SaveFrameToDisk(UTextureRenderTarget2D &RenderTarget, const FString ReadPixelFlags.SetLinearToGamma(true); if (RTResource == nullptr) { - UE_LOG(LogTemp, Error, TEXT("Missing render target!")); + LOG_ERROR("Missing render target!"); return; } if (!RTResource->ReadPixels(Pixels, ReadPixelFlags)) - UE_LOG(LogTemp, Error, TEXT("Unable to read pixels!")); + LOG_ERROR("Unable to read pixels!"); // dump pixel array to disk PixelData.Pixels = Pixels; TUniquePtr ImageTask = MakeUnique(); ImageTask->PixelData = MakeUnique>(PixelData); ImageTask->Filename = FilePath; - UE_LOG(LogTemp, Log, TEXT("Saving screenshot to %s"), *FilePath); + // LOG("Saving screenshot to %s", *FilePath); ImageTask->Format = FileFormatJPG ? EImageFormat::JPEG : EImageFormat::PNG; // lower quality, less storage ImageTask->CompressionQuality = (int32)EImageCompressionQuality::Default; ImageTask->bOverwriteFile = true; diff --git a/DReyeVR/EgoInputs.cpp b/DReyeVR/EgoInputs.cpp index e052abc..215d569 100644 --- a/DReyeVR/EgoInputs.cpp +++ b/DReyeVR/EgoInputs.cpp @@ -87,8 +87,7 @@ void AEgoVehicle::ReleasePrevCameraView() void AEgoVehicle::NextCameraView() { CurrentCameraTransformIdx = (CurrentCameraTransformIdx + 1) % (CameraTransforms.size()); - UE_LOG(LogTemp, Log, TEXT("Switching to next camera view: \"%s\""), - *CameraTransforms[CurrentCameraTransformIdx].first); + LOG("Switching to next camera view: \"%s\"", *CameraTransforms[CurrentCameraTransformIdx].first); SetCameraRootPose(CurrentCameraTransformIdx); } @@ -97,8 +96,7 @@ void AEgoVehicle::PrevCameraView() if (CurrentCameraTransformIdx == 0) CurrentCameraTransformIdx = CameraTransforms.size(); CurrentCameraTransformIdx--; - UE_LOG(LogTemp, Log, TEXT("Switching to prev camera view: \"%s\""), - *CameraTransforms[CurrentCameraTransformIdx].first); + LOG("Switching to prev camera view: \"%s\"", *CameraTransforms[CurrentCameraTransformIdx].first); SetCameraRootPose(CurrentCameraTransformIdx); } @@ -145,11 +143,15 @@ void AEgoVehicle::PressReverse() if (!bCanPressReverse) return; bCanPressReverse = false; // don't press again until release + bReverse = !bReverse; // negate to toggle bw + (forwards) and - (backwards) const int CurrentGear = this->GetVehicleMovementComponent()->GetTargetGear(); - const int NewGear = CurrentGear != 0 ? -1 * CurrentGear : -1; // set to -1 if parked, else -gear - this->bReverse = !this->bReverse; + int NewGear = -1; // for when parked + if (CurrentGear != 0) + { + NewGear = bReverse ? -1 * std::abs(CurrentGear) : std::abs(CurrentGear); // negative => backwards + } this->GetVehicleMovementComponent()->SetTargetGear(NewGear, true); // UE4 control // apply new light state @@ -157,7 +159,7 @@ void AEgoVehicle::PressReverse() Lights.Reverse = this->bReverse; this->SetVehicleLightState(Lights); - UE_LOG(LogTemp, Log, TEXT("Toggle Reverse")); + LOG("Toggle Reverse"); // assign to input struct VehicleInputs.ToggledReverse = true; @@ -197,7 +199,7 @@ void AEgoVehicle::ReleaseTurnSignalR() if (bCanPressTurnSignalR) return; VehicleInputs.TurnSignalRight = false; - RightSignalTimeToDie = FPlatformTime::Seconds() + this->TurnSignalDuration; // reset counter + RightSignalTimeToDie = GetWorld()->GetTimeSeconds() + this->TurnSignalDuration; // reset counter bCanPressTurnSignalR = true; } @@ -228,7 +230,7 @@ void AEgoVehicle::ReleaseTurnSignalL() if (bCanPressTurnSignalL) return; VehicleInputs.TurnSignalLeft = false; - LeftSignalTimeToDie = FPlatformTime::Seconds() + this->TurnSignalDuration; // reset counter + LeftSignalTimeToDie = GetWorld()->GetTimeSeconds() + this->TurnSignalDuration; // reset counter bCanPressTurnSignalL = true; } diff --git a/DReyeVR/EgoSensor.cpp b/DReyeVR/EgoSensor.cpp index 3162a6d..1fb497f 100644 --- a/DReyeVR/EgoSensor.cpp +++ b/DReyeVR/EgoSensor.cpp @@ -8,15 +8,15 @@ #include "Misc/DateTime.h" // FDateTime #include "UObject/UObjectBaseUtility.h" // GetName +#if USE_SRANIPAL_PLUGIN +#include "SRanipal_API.h" // SRanipal_GetVersion +#endif + #if USE_FOVEATED_RENDER #include "EyeTrackerTypes.h" // FEyeTrackerStereoGazeData #include "VRSBlueprintFunctionLibrary.h" // VRS #endif -#ifdef _WIN32 -#include // required for file IO in Windows -#endif - #include #ifndef NO_DREYEVR_EXCEPTIONS @@ -43,7 +43,6 @@ AEgoSensor::AEgoSensor(const FObjectInitializer &ObjectInitializer) : Super(Obje void AEgoSensor::ReadConfigVariables() { - ReadConfigValue("EgoSensor", "ActorRegistryID", EgoSensorID); ReadConfigValue("EgoSensor", "StreamSensorData", bStreamData); ReadConfigValue("EgoSensor", "MaxTraceLenM", MaxTraceLenM); ReadConfigValue("EgoSensor", "DrawDebugFocusTrace", bDrawDebugFocusTrace); @@ -59,8 +58,11 @@ void AEgoSensor::ReadConfigVariables() ReadConfigValue("Replayer", "FrameDir", FrameCapLocation); ReadConfigValue("Replayer", "FrameName", FrameCapFilename); +#if USE_FOVEATED_RENDER // foveated rendering variables - ReadConfigValue("FoveatedRender", "Enabled", bEnableFovRender); + ReadConfigValue("VariableRateShading", "Enabled", bEnableFovRender); + ReadConfigValue("VariableRateShading", "UsingEyeTracking", bUseEyeTrackingVRS); +#endif } void AEgoSensor::BeginPlay() @@ -73,16 +75,14 @@ void AEgoSensor::BeginPlay() // Initialize the eye tracker hardware InitEyeTracker(); - // Register EgoSensor with the CarlaActorRegistry - Register(); - #if USE_FOVEATED_RENDER // Initialize VRS plugin (using our VRS fork!) UVariableRateShadingFunctionLibrary::EnableVRS(bEnableFovRender); - UVariableRateShadingFunctionLibrary::EnableEyeTracking(bEnableFovRender); + UVariableRateShadingFunctionLibrary::EnableEyeTracking(bUseEyeTrackingVRS); + LOG("Initialized Variable Rate Shading (VRS) plugin"); #endif - UE_LOG(LogTemp, Log, TEXT("Initialized DReyeVR EgoSensor")); + LOG("Initialized DReyeVR EgoSensor"); } void AEgoSensor::BeginDestroy() @@ -121,27 +121,50 @@ void AEgoSensor::InitEyeTracker() { #if USE_SRANIPAL_PLUGIN bSRanipalEnabled = false; - // initialize SRanipal framework for eye tracking - UE_LOG(LogTemp, Warning, TEXT("Attempting to use SRanipal eye tracking")); + + char *SR_Version_chars = new char[128](); + ViveSR::anipal::SRanipal_GetVersion(SR_Version_chars); + const FString SR_Version(SR_Version_chars); + { + // we found that these versions work great, other versions may cause random crashes + const std::vector SupportedVers = {"1.3.1.1", "1.3.2.0", "1.3.3.0"}; + auto FoundVersion = std::find(SupportedVers.begin(), SupportedVers.end(), std::string(SR_Version_chars)); + bool bIsCompatible = (FoundVersion != SupportedVers.end()); + if (!bIsCompatible) + { + std::string SupportedVersStr = ""; + for (const auto &Ver : SupportedVers) + SupportedVersStr += Ver + ", "; + LOG_ERROR("Detected incompatible SRanipal version: %s", *SR_Version); + LOG_WARN("Please use a compatible SRanipal version such as: {%s}", *FString(SupportedVersStr.c_str())); + LOG_WARN("Check out the DReyeVR documentation to download a supported version."); + LOG_WARN("Disabling SRanipal for now..."); + bSRanipalEnabled = false; + return; + } + + // initialize SRanipal framework for eye tracking + LOG("Attempting to use SRanipal (%s) for eye tracking", *SR_Version); + } // Initialize the SRanipal eye tracker (WINDOWS ONLY) SRanipalFramework = SRanipalEye_Framework::Instance(); SRanipal = SRanipalEye_Core::Instance(); // no easily discernible difference between v1 and v2 /// TODO: use the status output from StartFramework to determine if SRanipal loaded successfully int Status = SRanipalFramework->StartFramework(SupportedEyeVersion::version1); - if (Status == SRanipalEye_Framework::FrameworkStatus::ERROR_SRANIPAL || // matches the patch_sranipal.sh script + if (Status == SRanipalEye_Framework::FrameworkStatus::ERROR || Status == SRanipalEye_Framework::FrameworkStatus::NOT_SUPPORT) { - UE_LOG(LogTemp, Error, TEXT("Unable to start SRanipal framework!")); + LOG_ERROR("Unable to start SRanipal framework (%d)!", Status); return; } // SRanipal->SetEyeParameter_() // can set the eye gaze jitter parameter // see SRanipal_Eyes_Enums.h // Get the reference timing to synchronize the SRanipal timer with Carla - UE_LOG(LogTemp, Log, TEXT("Successfully started SRanipal framework")); + LOG("Successfully started SRanipal (%s) framework", *SR_Version); bSRanipalEnabled = true; #else - UE_LOG(LogTemp, Warning, TEXT("Not using SRanipal eye tracking")); + LOG("Not using SRanipal eye tracking"); #endif } @@ -173,17 +196,14 @@ void AEgoSensor::TickEyeTracker() // Assigns EyeOrigin and Gaze direction (normalized) of combined gaze Combined->GazeValid = SRanipal->GetGazeRay(GazeIndex::COMBINE, Combined->GazeOrigin, Combined->GazeDir); // Assign Left/Right Gaze direction + Left->GazeValid = SRanipal->GetGazeRay(GazeIndex::LEFT, Left->GazeOrigin, Left->GazeDir); + Right->GazeValid = SRanipal->GetGazeRay(GazeIndex::RIGHT, Right->GazeOrigin, Right->GazeDir); /// NOTE: the eye gazes are reversed bc SRanipal has a bug in their closed libraries // see: https://forum.vive.com/topic/9306-possible-bug-in-unreal-sdk-for-leftright-eye-gazes - if (SRANIPAL_EYE_SWAP_FIXED) // if the latest SRanipal does not have this bug + const bool SRANIPAL_EYE_SWAP_BUG = true; + if (SRANIPAL_EYE_SWAP_BUG) // if the latest SRanipal does not have this bug { - Left->GazeValid = SRanipal->GetGazeRay(GazeIndex::LEFT, Left->GazeOrigin, Left->GazeDir); - Right->GazeValid = SRanipal->GetGazeRay(GazeIndex::RIGHT, Right->GazeOrigin, Right->GazeDir); - } - else // this is the default case which we were dealing with during development - { - Left->GazeValid = SRanipal->GetGazeRay(GazeIndex::LEFT, Left->GazeOrigin, Right->GazeDir); - Right->GazeValid = SRanipal->GetGazeRay(GazeIndex::RIGHT, Right->GazeOrigin, Left->GazeDir); + std::swap(Left->GazeDir, Right->GazeDir); // need to swap the gaze directions } // Assign Eye openness Left->EyeOpennessValid = SRanipal->GetEyeOpenness(EyeIndex::LEFT, Left->EyeOpenness); @@ -261,7 +281,7 @@ bool AEgoSensor::ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel Trace const FRotator &WorldRot = GetData()->GetCameraRotationAbs(); const FVector &WorldPos = GetData()->GetCameraLocationAbs(); const FVector GazeOrigin = WorldPos + WorldRot.RotateVector(GetData()->GetGazeOrigin()); - const FVector GazeRay = TraceLen * WorldRot.RotateVector(GetData()->GetGazeDir()); + const FVector GazeRay = TraceLen * WorldRot.RotateVector(GetData()->GetGazeDir()).GetSafeNormal(); // Create collision information container. FCollisionQueryParams TraceParam; TraceParam = FCollisionQueryParams(FName("TraceParam"), true); @@ -286,6 +306,15 @@ bool AEgoSensor::ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel Trace bDidHit = World->SweepSingleByChannel(Hit, GazeOrigin, GazeOrigin + GazeRay, FQuat(0.f, 0.f, 0.f, 0.f), TraceChannel, Sphear, TraceParam); } + + if (!bDidHit) + { + // focus point is just straight ahead to the maximum trace length + Hit.Actor = nullptr; + Hit.Location = GazeOrigin + GazeRay; + Hit.Distance = TraceLen; + } + if (bDrawDebugFocusTrace) { DrawDebugSphere(World, Hit.Location, 8.0f, 30, FColor::Blue); @@ -344,10 +373,10 @@ void AEgoSensor::SetEgoVehicle(class AEgoVehicle *NewEgoVehicle) check(Vehicle); } -void AEgoSensor::SetLevel(class ADReyeVRLevel *LevelIn) +void AEgoSensor::SetGame(class ADReyeVRGameMode *GameIn) { - DReyeVRLevel = LevelIn; - check(DReyeVRLevel); + DReyeVRGame = GameIn; + check(DReyeVRGame); } void AEgoSensor::ComputeEgoVars() @@ -419,7 +448,7 @@ void AEgoSensor::InitFrameCapture() FrameCapLocation = FPaths::Combine(FrameCapLocation, DirName); // create directory if not present - UE_LOG(LogTemp, Log, TEXT("Outputting frame capture data to %s"), *FrameCapLocation); + LOG("Outputting frame capture data to %s", *FrameCapLocation); IPlatformFile &PlatformFile = FPlatformFileManager::Get().GetPlatformFile(); if (!PlatformFile.DirectoryExists(*FrameCapLocation)) { @@ -510,8 +539,8 @@ void AEgoSensor::TickFoveatedRender() F.LeftEyeDirection = GetData()->GetGazeDir(DReyeVR::Gaze::LEFT); ConvertToEyeTrackerSpace(F.LeftEyeDirection); F.RightEyeOrigin = GetData()->GetGazeOrigin(DReyeVR::Gaze::RIGHT); - ConvertToEyeTrackerSpace(F.RightEyeDirection); F.RightEyeDirection = GetData()->GetGazeDir(DReyeVR::Gaze::RIGHT); + ConvertToEyeTrackerSpace(F.RightEyeDirection); F.FixationPoint = GetData()->GetFocusActorPoint(); F.ConfidenceValue = 0.99f; UVariableRateShadingFunctionLibrary::UpdateStereoGazeDataToFoveatedRendering(F); @@ -530,20 +559,6 @@ void AEgoSensor::UpdateData(const DReyeVR::AggregateData &RecorderData, const do void AEgoSensor::UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) { - if (DReyeVRLevel) - DReyeVRLevel->ReplayCustomActor(RecorderData, Per); -} - -/// ========================================== /// -/// -----------------:OTHER:------------------ /// -/// ========================================== /// - -void AEgoSensor::Register() -{ - // Register EgoSensor with ActorRegistry - FCarlaActor::IdType ID = EgoSensorID; - FActorDescription SensorDescr; - SensorDescr.Id = "sensor.dreyevr.dreyevrsensor"; - FString RegistryTags = "EgoSensor,DReyeVR"; - UCarlaStatics::GetCurrentEpisode(World)->RegisterActor(*this, SensorDescr, RegistryTags, ID); + if (DReyeVRGame) + DReyeVRGame->ReplayCustomActor(RecorderData, Per); } \ No newline at end of file diff --git a/DReyeVR/EgoSensor.h b/DReyeVR/EgoSensor.h index 685b53f..31efebf 100644 --- a/DReyeVR/EgoSensor.h +++ b/DReyeVR/EgoSensor.h @@ -6,16 +6,13 @@ #include // timing threads #include -// #define USE_SRANIPAL_PLUGIN true // handled in .Build.cs file -#define SRANIPAL_EYE_SWAP_FIXED false // as of v1.3.1.1 this bug is unfortunately still present +#if USE_SRANIPAL_PLUGIN -#ifndef _WIN32 -// unset the #define if on anything other than Windows bc the SRanipal libraries only work on Windows :( -#undef USE_SRANIPAL_PLUGIN -#define USE_SRANIPAL_PLUGIN false +// avoid macro conflict since SRanipal uses "ERROR" often +#ifdef ERROR +#undef ERROR #endif -#if USE_SRANIPAL_PLUGIN /// NOTE: Can only use SRanipal on Windows machines #include "SRanipalEye.h" // SRanipal Module Framework #include "SRanipalEye_Core.h" // SRanipal Eye Tracker @@ -27,7 +24,7 @@ #include "EgoSensor.generated.h" class AEgoVehicle; -class ADReyeVRLevel; +class ADReyeVRGameMode; UCLASS() class CARLAUE4_API AEgoSensor : public ADReyeVRSensor @@ -40,7 +37,7 @@ class CARLAUE4_API AEgoSensor : public ADReyeVRSensor void ManualTick(float DeltaSeconds); // Tick called explicitly from DReyeVR EgoVehicle void SetEgoVehicle(class AEgoVehicle *EgoVehicle); // provide access to EgoVehicle (and by extension its camera) - void SetLevel(class ADReyeVRLevel *Level); // provides access to ADReyeVRLevel + void SetGame(class ADReyeVRGameMode *Game); // provides access to ADReyeVRGameMode void UpdateData(const DReyeVR::AggregateData &RecorderData, const double Per) override; void UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) override; @@ -106,11 +103,8 @@ class CARLAUE4_API AEgoSensor : public ADReyeVRSensor void TickFoveatedRender(); void ConvertToEyeTrackerSpace(FVector &inVec) const; bool bEnableFovRender = false; + bool bUseEyeTrackingVRS = true; ////////////////:REPLAY://////////////// - class ADReyeVRLevel *DReyeVRLevel = nullptr; - - ////////////////:OTHER://////////////// - int EgoSensorID; - void Register(); + class ADReyeVRGameMode *DReyeVRGame = nullptr; }; \ No newline at end of file diff --git a/DReyeVR/EgoVehicle.cpp b/DReyeVR/EgoVehicle.cpp index a0d003e..b8a6618 100644 --- a/DReyeVR/EgoVehicle.cpp +++ b/DReyeVR/EgoVehicle.cpp @@ -17,6 +17,8 @@ // Sets default values AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) { + LOG("Constructing Ego Vehicle: %s", *FString(this->GetName())); + ReadConfigVariables(); // this actor ticks AFTER the physics simulation is done @@ -26,6 +28,9 @@ AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(Ob // Set up the root position to be the this mesh SetRootComponent(GetMesh()); + // Initialize the rigid body static mesh + ConstructRigidBody(); + // Initialize the camera components ConstructCameraRoot(); @@ -40,6 +45,8 @@ AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(Ob // Initialize the steering wheel ConstructSteeringWheel(); + + LOG("Finished constructing %s", *FString(this->GetName())); } void AEgoVehicle::ReadConfigVariables() @@ -52,21 +59,15 @@ void AEgoVehicle::ReadConfigVariables() auto InitMirrorParams = [](const FString &Name, struct MirrorParams &Params) { Params.Name = Name; ReadConfigValue("Mirrors", Params.Name + "MirrorEnabled", Params.Enabled); - ReadConfigValue("Mirrors", Params.Name + "MirrorPos", Params.MirrorPos); - ReadConfigValue("Mirrors", Params.Name + "MirrorRot", Params.MirrorRot); - ReadConfigValue("Mirrors", Params.Name + "MirrorScale", Params.MirrorScale); - ReadConfigValue("Mirrors", Params.Name + "ReflectionPos", Params.ReflectionPos); - ReadConfigValue("Mirrors", Params.Name + "ReflectionRot", Params.ReflectionRot); - ReadConfigValue("Mirrors", Params.Name + "ReflectionScale", Params.ReflectionScale); + ReadConfigValue("Mirrors", Params.Name + "MirrorTransform", Params.MirrorTransform); + ReadConfigValue("Mirrors", Params.Name + "ReflectionTransform", Params.ReflectionTransform); ReadConfigValue("Mirrors", Params.Name + "ScreenPercentage", Params.ScreenPercentage); }; InitMirrorParams("Rear", RearMirrorParams); InitMirrorParams("Left", LeftMirrorParams); InitMirrorParams("Right", RightMirrorParams); // rear mirror chassis - ReadConfigValue("Mirrors", "RearMirrorChassisPos", RearMirrorChassisPos); - ReadConfigValue("Mirrors", "RearMirrorChassisRot", RearMirrorChassisRot); - ReadConfigValue("Mirrors", "RearMirrorChassisScale", RearMirrorChassisScale); + ReadConfigValue("Mirrors", "RearMirrorChassisTransform", RearMirrorChassisTransform); // steering wheel ReadConfigValue("SteeringWheel", "InitLocation", InitWheelLocation); ReadConfigValue("SteeringWheel", "InitRotation", InitWheelRotation); @@ -74,7 +75,6 @@ void AEgoVehicle::ReadConfigVariables() ReadConfigValue("SteeringWheel", "MaxSteerVelocity", MaxSteerVelocity); ReadConfigValue("SteeringWheel", "SteeringScale", SteeringAnimScale); // other/cosmetic - ReadConfigValue("EgoVehicle", "ActorRegistryID", EgoVehicleID); ReadConfigValue("EgoVehicle", "DrawDebugEditor", bDrawDebugEditor); // inputs ReadConfigValue("VehicleInputs", "ScaleSteeringDamping", ScaleSteeringInput); @@ -91,7 +91,7 @@ void AEgoVehicle::BeginPlay() // Get information about the world World = GetWorld(); - Episode = UCarlaStatics::GetCurrentEpisode(World); + ensure(World != nullptr); // initialize InitAIPlayer(); @@ -99,10 +99,10 @@ void AEgoVehicle::BeginPlay() // Bug-workaround for initial delay on throttle; see https://github.com/carla-simulator/carla/issues/1640 this->GetVehicleMovementComponent()->SetTargetGear(1, true); - // Register Ego Vehicle with ActorRegistry - Register(); + // get the GameMode script + SetGame(Cast(UGameplayStatics::GetGameMode(World))); - UE_LOG(LogTemp, Log, TEXT("Initialized DReyeVR EgoVehicle")); + LOG("Initialized DReyeVR EgoVehicle"); } void AEgoVehicle::BeginDestroy() @@ -137,21 +137,85 @@ void AEgoVehicle::Tick(float DeltaSeconds) // Ensure appropriate autopilot functionality is accessible from EgoVehicle TickAutopilot(); - if (Pawn) + // Update the world level + TickGame(DeltaSeconds); + + // Play sound that requires constant ticking + TickSounds(); +} + +void AEgoVehicle::ConstructRigidBody() +{ +#if 0 + /// TODO: re-enable this code once spawning from DReyeVR needs to be done without a hardcoded blueprint asset + /// to see this effect remove the reference to EgoVehicleBPClass in DReyeVRFactory.cpp once implemented + + // https://forums.unrealengine.com/t/cannot-create-vehicle-updatedcomponent-has-not-initialized-its-rigid-body-actor/461662 + /// NOTE: this must be run in the constructors! + + // load skeletal mesh (static mesh) + static ConstructorHelpers::FObjectFinder CarMesh(TEXT( + "SkeletalMesh'/Game/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.SkeletalMesh_model3'")); + // original: "SkeletalMesh'/Game/Carla/Static/Car/4Wheeled/Tesla/SM_TeslaM3_v2.SM_TeslaM3_v2'" + USkeletalMesh *SkeletalMesh = CarMesh.Object; + if (SkeletalMesh == nullptr) + { + LOG_ERROR("Unable to load skeletal mesh!"); + return; + } + + // load skeleton (for animations) + static ConstructorHelpers::FObjectFinder CarSkeleton( + TEXT("Skeleton'/Game/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.Skeleton_model3'")); + // original: + // "Skeleton'/Game/Carla/Static/Car/4Wheeled/Tesla/SM_TeslaM3_lights_body_Skeleton.SM_TeslaM3_lights_body_Skeleton'" + USkeleton *Skeleton = CarSkeleton.Object; + if (Skeleton == nullptr) { - // Draw the spectator vr screen and overlay elements - Pawn->DrawSpectatorScreen(EgoSensor->GetData()->GetGazeOrigin(DReyeVR::Gaze::LEFT), - EgoSensor->GetData()->GetGazeDir(DReyeVR::Gaze::LEFT)); + LOG_ERROR("Unable to load skeleton!"); + return; + } - // draws combined reticle - Pawn->DrawFlatHUD(DeltaSeconds, EgoSensor->GetData()->GetGazeOrigin(), EgoSensor->GetData()->GetGazeDir()); + // load animations bp + static ConstructorHelpers::FClassFinder AnimBPClass( + TEXT("/Game/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.Animation_model3_C")); + // original: "/Game/Carla/Static/Car/4Wheeled/Tesla/Tesla_Animation.Tesla_Animation_C" + auto AnimInstance = AnimBPClass.Class; + if (!AnimBPClass.Succeeded()) + { + LOG_ERROR("Unable to load Animation!"); + return; } - // Update the world level - TickLevel(DeltaSeconds); + // load physics asset + static ConstructorHelpers::FObjectFinder CarPhysics(TEXT( + "PhysicsAsset'/Game/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.Physics_model3'")); + // original: "PhysicsAsset'/Game/Carla/Static/Car/4Wheeled/Tesla/SM_TeslaM3_PhysicsAsset.SM_TeslaM3_PhysicsAsset'" + UPhysicsAsset *PhysicsAsset = CarPhysics.Object; + if (PhysicsAsset == nullptr) + { + LOG_ERROR("Unable to load PhysicsAsset!"); + return; + } - // Play sound that requires constant ticking - TickSounds(); + // contrary to https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/USkeletalMesh/SetSkeleton/ + SkeletalMesh->Skeleton = Skeleton; + SkeletalMesh->PhysicsAsset = PhysicsAsset; + SkeletalMesh->Build(); + + USkeletalMeshComponent *Mesh = GetMesh(); + check(Mesh != nullptr); + Mesh->SetSkeletalMesh(SkeletalMesh, true); + Mesh->SetAnimInstanceClass(AnimInstance); + Mesh->SetPhysicsAsset(PhysicsAsset); + Mesh->RecreatePhysicsState(); + this->GetVehicleMovementComponent()->RecreatePhysicsState(); + + // sanity checks + ensure(Mesh->GetPhysicsAsset() != nullptr); + + LOG("Successfully created EgoVehicle rigid body"); +#endif } /// ========================================== /// @@ -224,7 +288,7 @@ void AEgoVehicle::SetCameraRootPose(const FTransform &CameraPoseTransform) { // sets the base posision of the Camera root (where the camera is at "rest") this->CameraPose = CameraPoseTransform; - UE_LOG(LogTemp, Log, TEXT("Setting camera pose to: %s"), *(CameraPose + CameraPoseOffset).ToString()); + // LOG("Setting camera pose to: %s", *(CameraPose + CameraPoseOffset).ToString()); // First, set the root of the camera to the driver's seat head pos VRCameraRoot->SetRelativeLocation(CameraPose.GetLocation() + CameraPoseOffset.GetLocation()); @@ -248,10 +312,12 @@ void AEgoVehicle::SetPawn(ADReyeVRPawn *PawnIn) const UCameraComponent *AEgoVehicle::GetCamera() const { + ensure(FirstPersonCam != nullptr); return FirstPersonCam; } UCameraComponent *AEgoVehicle::GetCamera() { + ensure(FirstPersonCam != nullptr); return FirstPersonCam; } FVector AEgoVehicle::GetCameraOffset() const @@ -282,7 +348,10 @@ const class AEgoSensor *AEgoVehicle::GetSensor() const void AEgoVehicle::InitAIPlayer() { - AI_Player = Cast(this->GetController()); + this->SpawnDefaultController(); // spawns default (AI) controller and gets possessed by it + auto PlayerController = this->GetController(); + ensure(PlayerController != nullptr); + AI_Player = Cast(PlayerController); ensure(AI_Player != nullptr); } @@ -317,16 +386,32 @@ void AEgoVehicle::InitSensor() World = GetWorld(); check(World != nullptr); // Spawn the EyeTracker Carla sensor and attach to Ego-Vehicle: - FActorSpawnParameters EyeTrackerSpawnInfo; - EyeTrackerSpawnInfo.Owner = this; - EyeTrackerSpawnInfo.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - EgoSensor = World->SpawnActor(GetCameraPosn(), FRotator::ZeroRotator, EyeTrackerSpawnInfo); + { + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(World); + check(Episode != nullptr); + FActorDefinition EgoSensorDef = FindDefnInRegistry(Episode, AEgoSensor::StaticClass()); + FActorDescription Description; + { // create a Description from the Definition to spawn the actor + Description.UId = EgoSensorDef.UId; + Description.Id = EgoSensorDef.Id; + Description.Class = EgoSensorDef.Class; + } + + if (Episode == nullptr) + { + LOG_ERROR("Null Episode in world!"); + } + // calls Episode::SpawnActor => SpawnActorWithInfo => ActorDispatcher->SpawnActor => SpawnFunctions[UId] + FTransform SpawnPt = FTransform(FRotator::ZeroRotator, GetCameraPosn(), FVector::OneVector); + EgoSensor = static_cast(Episode->SpawnActor(SpawnPt, Description)); + } check(EgoSensor != nullptr); // Attach the EgoSensor as a child to the EgoVehicle + EgoSensor->SetOwner(this); EgoSensor->AttachToActor(this, FAttachmentTransformRules::KeepRelativeTransform); EgoSensor->SetEgoVehicle(this); - if (DReyeVRLevel) - EgoSensor->SetLevel(DReyeVRLevel); + if (DReyeVRGame) + EgoSensor->SetGame(DReyeVRGame); } void AEgoVehicle::ReplayTick() @@ -385,34 +470,12 @@ void AEgoVehicle::UpdateSensor(const float DeltaSeconds) ensure(EgoSensor != nullptr); if (EgoSensor == nullptr) { - UE_LOG(LogTemp, Warning, TEXT("EgoSensor initialization failed!")); + LOG_WARN("EgoSensor initialization failed!"); return; } // Explicitly update the EgoSensor here, synchronized with EgoVehicle tick EgoSensor->ManualTick(DeltaSeconds); // Ensures we always get the latest data - - // Calculate gaze data (in world space) using eye tracker data - const DReyeVR::AggregateData *Data = EgoSensor->GetData(); - // Compute World positions and orientations - const FRotator WorldRot = FirstPersonCam->GetComponentRotation(); - const FVector WorldPos = FirstPersonCam->GetComponentLocation(); - - // First get the gaze origin and direction and vergence from the EyeTracker Sensor - const float RayLength = FMath::Max(1.f, Data->GetGazeVergence() / 100.f); // vergence to m (from cm) - const float VRMeterScale = 100.f; - - // Both eyes - CombinedGaze = RayLength * VRMeterScale * Data->GetGazeDir(); - CombinedOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin()); - - // Left eye - LeftGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::LEFT); - LeftOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::LEFT)); - - // Right eye - RightGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::RIGHT); - RightOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::RIGHT)); } /// ========================================== /// @@ -423,22 +486,22 @@ void AEgoVehicle::MirrorParams::Initialize(class UStaticMeshComponent *MirrorSM, class UPlanarReflectionComponent *Reflection, class USkeletalMeshComponent *VehicleMesh) { - UE_LOG(LogTemp, Log, TEXT("Initializing %s mirror"), *Name) + LOG("Initializing %s mirror", *Name) check(MirrorSM != nullptr); MirrorSM->SetupAttachment(VehicleMesh); - MirrorSM->SetRelativeLocation(MirrorPos); - MirrorSM->SetRelativeRotation(MirrorRot); - MirrorSM->SetRelativeScale3D(MirrorScale); + MirrorSM->SetRelativeLocation(MirrorTransform.GetLocation()); + MirrorSM->SetRelativeRotation(MirrorTransform.Rotator()); + MirrorSM->SetRelativeScale3D(MirrorTransform.GetScale3D()); MirrorSM->SetGenerateOverlapEvents(false); // don't collide with itself MirrorSM->SetCollisionEnabled(ECollisionEnabled::NoCollision); MirrorSM->SetVisibility(true); check(Reflection != nullptr); Reflection->SetupAttachment(MirrorSM); - Reflection->SetRelativeLocation(ReflectionPos); - Reflection->SetRelativeRotation(ReflectionRot); - Reflection->SetRelativeScale3D(ReflectionScale); + Reflection->SetRelativeLocation(ReflectionTransform.GetLocation()); + Reflection->SetRelativeRotation(ReflectionTransform.Rotator()); + Reflection->SetRelativeScale3D(ReflectionTransform.GetScale3D()); Reflection->NormalDistortionStrength = 0.0f; Reflection->PrefilterRoughness = 0.0f; Reflection->DistanceFromPlaneFadeoutStart = 1500.f; @@ -462,22 +525,21 @@ void AEgoVehicle::ConstructMirrors() if (RearMirrorParams.Enabled) { static ConstructorHelpers::FObjectFinder RearSM( - TEXT("StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/Mirrors/" - "RearMirror_DReyeVR_Glass_SM.RearMirror_DReyeVR_Glass_SM'")); + TEXT("StaticMesh'/Game/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.RearMirror_model3'")); RearMirrorSM = CreateDefaultSubobject(FName(*(RearMirrorParams.Name + "MirrorSM"))); RearMirrorSM->SetStaticMesh(RearSM.Object); RearReflection = CreateDefaultSubobject(FName(*(RearMirrorParams.Name + "Refl"))); RearMirrorParams.Initialize(RearMirrorSM, RearReflection, VehicleMesh); // also add the chassis for this mirror - static ConstructorHelpers::FObjectFinder RearChassisSM(TEXT( - "StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/Mirrors/RearMirror_DReyeVR_SM.RearMirror_DReyeVR_SM'")); + static ConstructorHelpers::FObjectFinder RearChassisSM( + TEXT("StaticMesh'/Game/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.RearMirror_Mesh_model3'")); RearMirrorChassisSM = CreateDefaultSubobject(FName(*(RearMirrorParams.Name + "MirrorChassisSM"))); RearMirrorChassisSM->SetStaticMesh(RearChassisSM.Object); RearMirrorChassisSM->SetupAttachment(VehicleMesh); - RearMirrorChassisSM->SetRelativeLocation(RearMirrorChassisPos); - RearMirrorChassisSM->SetRelativeRotation(RearMirrorChassisRot); - RearMirrorChassisSM->SetRelativeScale3D(RearMirrorChassisScale); + RearMirrorChassisSM->SetRelativeLocation(RearMirrorChassisTransform.GetLocation()); + RearMirrorChassisSM->SetRelativeRotation(RearMirrorChassisTransform.Rotator()); + RearMirrorChassisSM->SetRelativeScale3D(RearMirrorChassisTransform.GetScale3D()); RearMirrorChassisSM->SetGenerateOverlapEvents(false); // don't collide with itself RearMirrorChassisSM->SetCollisionEnabled(ECollisionEnabled::NoCollision); RearMirrorChassisSM->SetVisibility(true); @@ -487,8 +549,8 @@ void AEgoVehicle::ConstructMirrors() /// Left mirror if (LeftMirrorParams.Enabled) { - static ConstructorHelpers::FObjectFinder LeftSM(TEXT( - "StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/Mirrors/LeftMirror_DReyeVR_SM.LeftMirror_DReyeVR_SM'")); + static ConstructorHelpers::FObjectFinder LeftSM( + TEXT("StaticMesh'/Game/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.LeftMirror_model3'")); LeftMirrorSM = CreateDefaultSubobject(FName(*(LeftMirrorParams.Name + "MirrorSM"))); LeftMirrorSM->SetStaticMesh(LeftSM.Object); LeftReflection = CreateDefaultSubobject(FName(*(LeftMirrorParams.Name + "Refl"))); @@ -498,8 +560,7 @@ void AEgoVehicle::ConstructMirrors() if (RightMirrorParams.Enabled) { static ConstructorHelpers::FObjectFinder RightSM( - TEXT("StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/Mirrors/" - "RightMirror_DReyeVR_SM.RightMirror_DReyeVR_SM'")); + TEXT("StaticMesh'/Game/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.RightMirror_model3'")); RightMirrorSM = CreateDefaultSubobject(FName(*(RightMirrorParams.Name + "MirrorSM"))); RightMirrorSM->SetStaticMesh(RightSM.Object); RightReflection = CreateDefaultSubobject(FName(*(RightMirrorParams.Name + "Refl"))); @@ -519,14 +580,14 @@ void AEgoVehicle::ConstructEgoSounds() ensureMsgf(CrashSound != nullptr, TEXT("Vehicle crash sound should be initialized!")); static ConstructorHelpers::FObjectFinder GearSound( - TEXT("SoundWave'/Game/Carla/Blueprints/Vehicles/DReyeVR/Sounds/GearShift.GearShift'")); + TEXT("SoundWave'/Game/DReyeVR/Sounds/GearShift.GearShift'")); GearShiftSound = CreateDefaultSubobject(TEXT("GearShift")); GearShiftSound->SetupAttachment(GetRootComponent()); GearShiftSound->bAutoActivate = false; GearShiftSound->SetSound(GearSound.Object); static ConstructorHelpers::FObjectFinder TurnSignalSoundWave( - TEXT("SoundWave'/Game/Carla/Blueprints/Vehicles/DReyeVR/Sounds/TurnSignal.TurnSignal'")); + TEXT("SoundWave'/Game/DReyeVR/Sounds/TurnSignal.TurnSignal'")); TurnSignalSound = CreateDefaultSubobject(TEXT("TurnSignal")); TurnSignalSound->SetupAttachment(GetRootComponent()); TurnSignalSound->bAutoActivate = false; @@ -609,25 +670,23 @@ void AEgoVehicle::UpdateDash() { const DReyeVR::AggregateData *Replay = EgoSensor->GetData(); XPH = Replay->GetVehicleVelocity() * SpeedometerScale; // FwdSpeed is in cm/s - if (Replay->GetUserInputs().ToggledReverse) - { - bReverse = !bReverse; - PlayGearShiftSound(); - } + const auto &ReplayInputs = Replay->GetUserInputs(); + if (ReplayInputs.ToggledReverse) + PressReverse(); + else + ReleaseReverse(); + if (bEnableTurnSignalAction) { - if (Replay->GetUserInputs().TurnSignalLeft) - { - LeftSignalTimeToDie = FPlatformTime::Seconds() + TurnSignalDuration; - RightSignalTimeToDie = 0.f; - PlayTurnSignalSound(); - } - if (Replay->GetUserInputs().TurnSignalRight) - { - RightSignalTimeToDie = FPlatformTime::Seconds() + TurnSignalDuration; - LeftSignalTimeToDie = 0.f; - PlayTurnSignalSound(); - } + if (ReplayInputs.TurnSignalLeft) + PressTurnSignalL(); + else + ReleaseTurnSignalL(); + + if (ReplayInputs.TurnSignalRight) + PressTurnSignalR(); + else + ReleaseTurnSignalR(); } } else @@ -641,17 +700,22 @@ void AEgoVehicle::UpdateDash() if (bEnableTurnSignalAction) { // Draw the signals - float Now = FPlatformTime::Seconds(); - if (Now < RightSignalTimeToDie) - TurnSignals->SetText(FText::FromString(">>>")); - else if (Now < LeftSignalTimeToDie) - TurnSignals->SetText(FText::FromString("<<<")); - else - TurnSignals->SetText(FText::FromString("")); // nothing + float Now = GetWorld()->GetTimeSeconds(); + const float StartTime = std::max(RightSignalTimeToDie, LeftSignalTimeToDie) - TurnSignalDuration; + FString TurnSignalStr = ""; + constexpr static float TurnSignalBlinkRate = 0.4f; // rate of blinking + if (std::fmodf(Now - StartTime, TurnSignalBlinkRate * 2) < TurnSignalBlinkRate) + { + if (Now < RightSignalTimeToDie) + TurnSignalStr = ">>>"; + else if (Now < LeftSignalTimeToDie) + TurnSignalStr = "<<<"; + } + TurnSignals->SetText(FText::FromString(TurnSignalStr)); } // Draw the gear shifter - if (bReverse) + if (bReverse) // backwards GearShifter->SetText(FText::FromString("R")); else GearShifter->SetText(FText::FromString("D")); @@ -663,9 +727,8 @@ void AEgoVehicle::UpdateDash() void AEgoVehicle::ConstructSteeringWheel() { - static ConstructorHelpers::FObjectFinder SteeringWheelSM( - TEXT("StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/SteeringWheel/" - "SM_SteeringWheel_DReyeVR.SM_SteeringWheel_DReyeVR'")); + static ConstructorHelpers::FObjectFinder SteeringWheelSM(TEXT( + "StaticMesh'/Game/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.Wheel_StaticMeshl_model3'")); SteeringWheel = CreateDefaultSubobject(FName("SteeringWheel")); SteeringWheel->SetStaticMesh(SteeringWheelSM.Object); SteeringWheel->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself @@ -706,43 +769,25 @@ void AEgoVehicle::TickSteeringWheel(const float DeltaTime) /// -----------------:LEVEL:------------------ /// /// ========================================== /// -void AEgoVehicle::SetLevel(ADReyeVRLevel *Level) +void AEgoVehicle::SetGame(ADReyeVRGameMode *Game) { - this->DReyeVRLevel = Level; - check(DReyeVRLevel != nullptr); + DReyeVRGame = Game; + check(DReyeVRGame != nullptr); + DReyeVRGame->SetEgoVehicle(this); + + DReyeVRGame->GetPawn()->BeginEgoVehicle(this, World); + LOG("Successfully assigned GameMode & controller pawn"); } -void AEgoVehicle::TickLevel(float DeltaSeconds) +ADReyeVRGameMode *AEgoVehicle::GetGame() { - if (this->DReyeVRLevel != nullptr) - DReyeVRLevel->Tick(DeltaSeconds); + return DReyeVRGame; } -/// ========================================== /// -/// -----------------:OTHER:------------------ /// -/// ========================================== /// - -void AEgoVehicle::Register() -{ - FCarlaActor::IdType ID = EgoVehicleID; - FActorDescription Description; - Description.Class = ACarlaWheeledVehicle::StaticClass(); - Description.Id = "vehicle.dreyevr.egovehicle"; - Description.UId = ID; - // ensure this vehicle is denoted by the 'hero' attribute - FActorAttribute HeroRole; - HeroRole.Id = "role_name"; - HeroRole.Type = EActorAttributeType::String; - HeroRole.Value = "hero"; - Description.Variations.Add(HeroRole.Id, std::move(HeroRole)); - // ensure the vehicle has attributes denoting number of wheels - FActorAttribute NumWheels; - NumWheels.Id = "number_of_wheels"; - NumWheels.Type = EActorAttributeType::Int; - NumWheels.Value = "4"; - Description.Variations.Add(NumWheels.Id, std::move(NumWheels)); - FString RegistryTags = "EgoVehicle,DReyeVR"; - Episode->RegisterActor(*this, Description, RegistryTags, ID); +void AEgoVehicle::TickGame(float DeltaSeconds) +{ + if (this->DReyeVRGame != nullptr) + DReyeVRGame->Tick(DeltaSeconds); } /// ========================================== /// @@ -752,15 +797,34 @@ void AEgoVehicle::Register() void AEgoVehicle::DebugLines() const { #if WITH_EDITOR - // Compute World positions and orientations - const FRotator WorldRot = FirstPersonCam->GetComponentRotation(); - // Rotate and add the gaze ray to the origin - FVector CombinedGazePosn = CombinedOrigin + WorldRot.RotateVector(CombinedGaze); - // Use Absolute Ray Position to draw debug information if (bDrawDebugEditor) { - DrawDebugSphere(World, CombinedGazePosn, 4.0f, 12, FColor::Blue); + // Calculate gaze data (in world space) using eye tracker data + const DReyeVR::AggregateData *Data = EgoSensor->GetData(); + // Compute World positions and orientations + const FRotator &WorldRot = FirstPersonCam->GetComponentRotation(); + const FVector &WorldPos = FirstPersonCam->GetComponentLocation(); + + // First get the gaze origin and direction and vergence from the EyeTracker Sensor + const float RayLength = FMath::Max(1.f, Data->GetGazeVergence() / 100.f); // vergence to m (from cm) + const float VRMeterScale = 100.f; + + // Both eyes + const FVector CombinedGaze = RayLength * VRMeterScale * Data->GetGazeDir(); + const FVector CombinedOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin()); + + // Left eye + const FVector LeftGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::LEFT); + const FVector LeftOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::LEFT)); + + // Right eye + const FVector RightGaze = RayLength * VRMeterScale * Data->GetGazeDir(DReyeVR::Gaze::RIGHT); + const FVector RightOrigin = WorldPos + WorldRot.RotateVector(Data->GetGazeOrigin(DReyeVR::Gaze::RIGHT)); + + // Use Absolute Ray Position to draw debug information + // Rotate and add the gaze ray to the origin + DrawDebugSphere(World, CombinedOrigin + WorldRot.RotateVector(CombinedGaze), 4.0f, 12, FColor::Blue); // Draw individual rays for left and right eye DrawDebugLine(World, diff --git a/DReyeVR/EgoVehicle.h b/DReyeVR/EgoVehicle.h index 315ded9..a62db05 100644 --- a/DReyeVR/EgoVehicle.h +++ b/DReyeVR/EgoVehicle.h @@ -11,18 +11,18 @@ #include "Components/PlanarReflectionComponent.h" // Planar Reflection #include "Components/SceneComponent.h" // USceneComponent #include "CoreMinimal.h" // Unreal functions +#include "DReyeVRGameMode.h" // ADReyeVRGameMode #include "DReyeVRUtils.h" // ReadConfigValue #include "EgoSensor.h" // AEgoSensor #include "FlatHUD.h" // ADReyeVRHUD #include "ImageUtils.h" // CreateTexture2D -#include "LevelScript.h" // ADReyeVRLevel #include "WheeledVehicle.h" // VehicleMovementComponent #include #include #include "EgoVehicle.generated.h" -class ADReyeVRLevel; +class ADReyeVRGameMode; class ADReyeVRPawn; UCLASS() @@ -41,7 +41,8 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle virtual void Tick(float DeltaTime) override; // called automatically // Setters from external classes - void SetLevel(ADReyeVRLevel *Level); + void SetGame(ADReyeVRGameMode *Game); + ADReyeVRGameMode *GetGame(); void SetPawn(ADReyeVRPawn *Pawn); void SetVolume(const float VolumeIn); @@ -82,7 +83,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle class UWorld *World; private: - void Register(); // function to register the AEgoVehicle with Carla's ActorRegistry + void ConstructRigidBody(); ////////////////:CAMERA://////////////// void ConstructCameraRoot(); // needs to be called in the constructor @@ -100,9 +101,6 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle void InitSensor(); class AEgoSensor *EgoSensor; // custom sensor helper that holds logic for extracting useful data void UpdateSensor(const float DeltaTime); - FVector CombinedGaze, CombinedOrigin; - FVector LeftGaze, LeftOrigin; - FVector RightGaze, RightOrigin; ///////////////:DREYEVRPAWN:///////////// class ADReyeVRPawn *Pawn = nullptr; @@ -112,8 +110,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle struct MirrorParams { bool Enabled; - FVector MirrorPos, MirrorScale, ReflectionPos, ReflectionScale; - FRotator MirrorRot, ReflectionRot; + FTransform MirrorTransform, ReflectionTransform; float ScreenPercentage; FString Name; void Initialize(class UStaticMeshComponent *SM, class UPlanarReflectionComponent *Reflection, @@ -135,8 +132,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle // rear mirror chassis (dynamic) UPROPERTY(Category = Mirrors, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UStaticMeshComponent *RearMirrorChassisSM; - FVector RearMirrorChassisPos, RearMirrorChassisScale; - FRotator RearMirrorChassisRot; + FTransform RearMirrorChassisTransform; ////////////////:AICONTROLLER://////////////// class AWheeledVehicleAIController *AI_Player = nullptr; @@ -207,8 +203,8 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle class UAudioComponent *TurnSignalSound; // good for turn signals ////////////////:LEVEL://////////////// - void TickLevel(float DeltaSeconds); - class ADReyeVRLevel *DReyeVRLevel; + void TickGame(float DeltaSeconds); + class ADReyeVRGameMode *DReyeVRGame; ////////////////:DASH://////////////// // Text Render components (Like the HUD but part of the mesh and works in VR) @@ -237,12 +233,6 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle float SteeringAnimScale; ////////////////:OTHER://////////////// - - // Actor registry - int EgoVehicleID; - UCarlaEpisode *Episode = nullptr; - - // Other void DebugLines() const; bool bDrawDebugEditor = false; }; diff --git a/DReyeVR/FlatHUD.cpp b/DReyeVR/FlatHUD.cpp index 76dc8a7..9eebf7e 100644 --- a/DReyeVR/FlatHUD.cpp +++ b/DReyeVR/FlatHUD.cpp @@ -1,12 +1,19 @@ #include "FlatHUD.h" +#include "DReyeVRUtils.h" // GetTimeSeconds + +// fixing issue described in CarlaHUD.h regarding DrawText on Windows +#ifdef DrawText +#undef DrawText +#endif + void ADReyeVRHUD::SetPlayer(APlayerController *P) { Player = P; // Player = GetOwningPlayerController(); if (Player == nullptr) { - UE_LOG(LogTemp, Error, TEXT("Can't find player controller!")); + LOG_ERROR("Can't find player controller!"); } check(Player != nullptr); } diff --git a/DReyeVR/FlatHUD.h b/DReyeVR/FlatHUD.h index 335aa91..a74706d 100644 --- a/DReyeVR/FlatHUD.h +++ b/DReyeVR/FlatHUD.h @@ -61,6 +61,7 @@ UCLASS() class ADReyeVRHUD : public ACarlaHUD public: ADReyeVRHUD(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) { + LOG("Initializing DReyeVR HUD"); } virtual void DrawHUD() override; diff --git a/DReyeVR/LevelScript.cpp b/DReyeVR/LevelScript.cpp deleted file mode 100644 index 4d9ec57..0000000 --- a/DReyeVR/LevelScript.cpp +++ /dev/null @@ -1,388 +0,0 @@ -#include "LevelScript.h" -#include "Carla/Game/CarlaStatics.h" // GetRecorder, GetEpisode -#include "Carla/Sensor/DReyeVRSensor.h" // ADReyeVRSensor -#include "Carla/Vehicle/CarlaWheeledVehicle.h" // ACarlaWheeledVehicle -#include "Components/AudioComponent.h" // UAudioComponent -#include "DReyeVRPawn.h" // ADReyeVRPawn -#include "EgoVehicle.h" // AEgoVehicle -#include "HeadMountedDisplayFunctionLibrary.h" // IsHeadMountedDisplayAvailable -#include "Kismet/GameplayStatics.h" // GetPlayerController -#include "UObject/UObjectIterator.h" // TObjectInterator - -ADReyeVRLevel::ADReyeVRLevel(FObjectInitializer const &FO) : Super(FO) -{ - // initialize stuff here - PrimaryActorTick.bCanEverTick = false; - PrimaryActorTick.bStartWithTickEnabled = false; - - ReadConfigValue("Level", "EgoVolumePercent", EgoVolumePercent); - ReadConfigValue("Level", "NonEgoVolumePercent", NonEgoVolumePercent); - ReadConfigValue("Level", "AmbientVolumePercent", AmbientVolumePercent); - - // Recorder/replayer - ReadConfigValue("Replayer", "RunSyncReplay", bReplaySync); -} - -void ADReyeVRLevel::BeginPlay() -{ - Super::ReceiveBeginPlay(); - - // Initialize player - Player = UGameplayStatics::GetPlayerController(GetWorld(), 0); - - // Can we tick? - SetActorTickEnabled(false); // make sure we do not tick ourselves - - // enable input tracking - InputEnabled(); - - // set all the volumes (ego, non-ego, ambient/world) - SetVolume(); - - // start input mapping - SetupPlayerInputComponent(); - - // spawn the DReyeVR pawn and possess it - StartDReyeVRPawn(); - - // Find the ego vehicle in the world - /// TODO: optionally, spawn ego-vehicle here with parametrized inputs - FindEgoVehicle(); - - // Initialize DReyeVR spectator - SetupSpectator(); - - // Initialize control mode - ControlMode = DRIVER::HUMAN; -} - -void ADReyeVRLevel::StartDReyeVRPawn() -{ - FActorSpawnParameters S; - DReyeVR_Pawn = GetWorld()->SpawnActor(FVector::ZeroVector, FRotator::ZeroRotator, S); - /// NOTE: the pawn is automatically possessed by player0 - // as the constructor has the AutoPossessPlayer != disabled - // if you want to manually possess then you can do Player->Possess(DReyeVR_Pawn); - ensure(DReyeVR_Pawn != nullptr); -} - -bool ADReyeVRLevel::FindEgoVehicle() -{ - if (EgoVehiclePtr != nullptr) - return true; - ensure(DReyeVR_Pawn); - TArray FoundEgoVehicles; - UGameplayStatics::GetAllActorsOfClass(GetWorld(), AEgoVehicle::StaticClass(), FoundEgoVehicles); - for (AActor *Vehicle : FoundEgoVehicles) - { - UE_LOG(LogTemp, Log, TEXT("Found EgoVehicle in world: %s"), *(Vehicle->GetName())); - EgoVehiclePtr = CastChecked(Vehicle); - EgoVehiclePtr->SetLevel(this); - if (DReyeVR_Pawn) - { - // need to assign ego vehicle before possess! - DReyeVR_Pawn->BeginEgoVehicle(EgoVehiclePtr, GetWorld(), Player); - UE_LOG(LogTemp, Log, TEXT("Created DReyeVR controller pawn")); - } - /// TODO: handle multiple ego-vehcles? (we should only ever have one!) - return true; - } - UE_LOG(LogTemp, Error, TEXT("Did not find EgoVehicle")); - return (EgoVehiclePtr != nullptr); -} - -void ADReyeVRLevel::SetupSpectator() -{ - /// TODO: fix bug where HMD is not detected on package BeginPlay() - // if (UHeadMountedDisplayFunctionLibrary::IsHeadMountedDisplayEnabled()) - const bool bEnableVRSpectator = true; - if (bEnableVRSpectator) - { - FVector SpawnLocn; - FRotator SpawnRotn; - if (EgoVehiclePtr != nullptr) - { - SpawnLocn = EgoVehiclePtr->GetCameraPosn(); - SpawnRotn = EgoVehiclePtr->GetCameraRot(); - } - // create new spectator pawn - FActorSpawnParameters SpawnParams; - SpawnParams.Owner = this; - SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; - SpawnParams.ObjectFlags |= RF_Transient; - SpectatorPtr = GetWorld()->SpawnActor(ASpectatorPawn::StaticClass(), // spectator - SpawnLocn, SpawnRotn, SpawnParams); - } - else - { - UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); - if (Episode != nullptr) - SpectatorPtr = Episode->GetSpectatorPawn(); - else - { - if (Player != nullptr) - { - SpectatorPtr = Player->GetPawn(); - } - } - } -} - -void ADReyeVRLevel::BeginDestroy() -{ - Super::BeginDestroy(); - UE_LOG(LogTemp, Log, TEXT("Finished Level")); -} - -void ADReyeVRLevel::Tick(float DeltaSeconds) -{ - Super::Tick(DeltaSeconds); - /// TODO: clean up replay init - if (!bRecorderInitiated) // can't do this in constructor - { - // Initialize recorder/replayer - SetupReplayer(); // once this is successfully run, it no longer gets executed - } - - DrawBBoxes(); -} - -void ADReyeVRLevel::SetupPlayerInputComponent() -{ - InputComponent = NewObject(this); - InputComponent->RegisterComponent(); - // set up gameplay key bindings - check(InputComponent); - // InputComponent->BindAction("ToggleCamera", IE_Pressed, this, &ADReyeVRLevel::ToggleSpectator); - InputComponent->BindAction("PlayPause_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::PlayPause); - InputComponent->BindAction("FastForward_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::FastForward); - InputComponent->BindAction("Rewind_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::Rewind); - InputComponent->BindAction("Restart_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::Restart); - InputComponent->BindAction("Incr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::IncrTimestep); - InputComponent->BindAction("Decr_Timestep_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::DecrTimestep); - // Driver Handoff examples - InputComponent->BindAction("EgoVehicle_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::PossessEgoVehicle); - InputComponent->BindAction("Spectator_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::PossessSpectator); - InputComponent->BindAction("AI_DReyeVR", IE_Pressed, this, &ADReyeVRLevel::HandoffDriverToAI); -} - -void ADReyeVRLevel::PossessEgoVehicle() -{ - if (Player->GetPawn() != DReyeVR_Pawn) - { - UE_LOG(LogTemp, Log, TEXT("Possessing DReyeVR EgoVehicle")); - Player->Possess(DReyeVR_Pawn); - } - ensure(EgoVehiclePtr != nullptr); - if (EgoVehiclePtr) - { - EgoVehiclePtr->SetAutopilot(false); - UE_LOG(LogTemp, Log, TEXT("Disabling EgoVehicle Autopilot")); - this->ControlMode = DRIVER::AI; - } - this->ControlMode = DRIVER::HUMAN; -} - -void ADReyeVRLevel::PossessSpectator() -{ - // check if already possessing spectator - if (Player->GetPawn() == SpectatorPtr && ControlMode != DRIVER::AI) - return; - if (!SpectatorPtr) - { - UE_LOG(LogTemp, Error, TEXT("No spectator to possess")); - SetupSpectator(); - if (SpectatorPtr == nullptr) - { - return; - } - } - if (EgoVehiclePtr) - { - // spawn from EgoVehicle head position - const FVector &EgoLocn = EgoVehiclePtr->GetCameraPosn(); - const FRotator &EgoRotn = EgoVehiclePtr->GetCameraRot(); - SpectatorPtr->SetActorLocationAndRotation(EgoLocn, EgoRotn); - } - // repossess the ego vehicle - Player->Possess(SpectatorPtr); - UE_LOG(LogTemp, Log, TEXT("Possessing spectator player")); - this->ControlMode = DRIVER::SPECTATOR; -} - -void ADReyeVRLevel::HandoffDriverToAI() -{ - ensure(EgoVehiclePtr != nullptr); - if (EgoVehiclePtr) - { - EgoVehiclePtr->SetAutopilot(true); - UE_LOG(LogTemp, Log, TEXT("Enabling EgoVehicle Autopilot")); - this->ControlMode = DRIVER::AI; - } -} - -void ADReyeVRLevel::PlayPause() -{ - UE_LOG(LogTemp, Log, TEXT("Toggle Play-Pause")); - UCarlaStatics::GetRecorder(GetWorld())->RecPlayPause(); -} - -void ADReyeVRLevel::FastForward() -{ - UCarlaStatics::GetRecorder(GetWorld())->RecFastForward(); -} - -void ADReyeVRLevel::Rewind() -{ - if (UCarlaStatics::GetRecorder(GetWorld())) - UCarlaStatics::GetRecorder(GetWorld())->RecRewind(); -} - -void ADReyeVRLevel::Restart() -{ - UE_LOG(LogTemp, Log, TEXT("Restarting recording")); - if (UCarlaStatics::GetRecorder(GetWorld())) - UCarlaStatics::GetRecorder(GetWorld())->RecRestart(); -} - -void ADReyeVRLevel::IncrTimestep() -{ - if (UCarlaStatics::GetRecorder(GetWorld())) - UCarlaStatics::GetRecorder(GetWorld())->IncrTimeFactor(0.1); -} - -void ADReyeVRLevel::DecrTimestep() -{ - if (UCarlaStatics::GetRecorder(GetWorld())) - UCarlaStatics::GetRecorder(GetWorld())->IncrTimeFactor(-0.1); -} - -void ADReyeVRLevel::SetupReplayer() -{ - if (UCarlaStatics::GetRecorder(GetWorld()) && UCarlaStatics::GetRecorder(GetWorld())->GetReplayer()) - { - UCarlaStatics::GetRecorder(GetWorld())->GetReplayer()->SetSyncMode(bReplaySync); - bRecorderInitiated = true; - } -} - -void ADReyeVRLevel::DrawBBoxes() -{ -#if 0 - TArray FoundActors; - if (GetWorld() != nullptr) - { - UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); - } - for (AActor *A : FoundActors) - { - std::string name = TCHAR_TO_UTF8(*A->GetName()); - if (A->GetName().Contains("DReyeVR")) - continue; // skip drawing a bbox over the EgoVehicle - if (BBoxes.find(name) == BBoxes.end()) - { - BBoxes[name] = ADReyeVRCustomActor::CreateNew(SM_CUBE, MAT_TRANSLUCENT, GetWorld(), "BBox" + A->GetName()); - } - const float DistThresh = 20.f; // meters before nearby bounding boxes become red - ADReyeVRCustomActor *BBox = BBoxes[name]; - ensure(BBox != nullptr); - if (BBox != nullptr) - { - BBox->Activate(); - BBox->MaterialParams.Opacity = 0.1f; - FLinearColor Col = FLinearColor::Green; - if (FVector::Distance(EgoVehiclePtr->GetActorLocation(), A->GetActorLocation()) < DistThresh * 100.f) - { - Col = FLinearColor::Red; - } - BBox->MaterialParams.BaseColor = Col; - BBox->MaterialParams.Emissive = 0.1 * Col; - - FVector Origin; - FVector BoxExtent; - A->GetActorBounds(true, Origin, BoxExtent, false); - // UE_LOG(LogTemp, Log, TEXT("Origin: %s Extent %s"), *Origin.ToString(), *BoxExtent.ToString()); - // divide by 100 to get from m to cm, multiply by 2 bc the cube is scaled in both X and Y - BBox->SetActorScale3D(2 * BoxExtent / 100.f); - BBox->SetActorLocation(Origin); - // extent already covers the rotation aspect since the bbox is dynamic and axis aligned - // BBox->SetActorRotation(A->GetActorRotation()); - } - } -#endif -} - -void ADReyeVRLevel::ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per) -{ - // first spawn the actor if not currently active - const std::string ActorName = TCHAR_TO_UTF8(*RecorderData.Name); - ADReyeVRCustomActor *A = nullptr; - if (ADReyeVRCustomActor::ActiveCustomActors.find(ActorName) == ADReyeVRCustomActor::ActiveCustomActors.end()) - { - /// TODO: also track KnownNumMaterials? - A = ADReyeVRCustomActor::CreateNew(RecorderData.MeshPath, RecorderData.MaterialParams.MaterialPath, GetWorld(), - RecorderData.Name); - } - else - { - A = ADReyeVRCustomActor::ActiveCustomActors[ActorName]; - } - // ensure the actor is currently active (spawned) - // now that we know this actor exists, update its internals - if (A != nullptr) - { - A->SetInternals(RecorderData); - A->Activate(); - A->Tick(Per); // update locations immediately - } -} - -void ADReyeVRLevel::SetVolume() -{ - // update the non-ego volume percent - ACarlaWheeledVehicle::Volume = NonEgoVolumePercent / 100.f; - - // for all in-world audio components such as ambient birdsong, fountain splashing, smoke, etc. - for (TObjectIterator Itr; Itr; ++Itr) - { - if (Itr->GetWorld() != GetWorld()) // World Check - { - continue; - } - Itr->SetVolumeMultiplier(AmbientVolumePercent / 100.f); - } - - // for all in-world vehicles (including the EgoVehicle) manually set their volumes - TArray FoundActors; - UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), FoundActors); - for (AActor *A : FoundActors) - { - ACarlaWheeledVehicle *Vehicle = Cast(A); - if (Vehicle != nullptr) - { - float NewVolume = ACarlaWheeledVehicle::Volume; // Non ego volume - if (Vehicle->IsA(AEgoVehicle::StaticClass())) // dynamic cast, requires -frrti - NewVolume = EgoVolumePercent / 100.f; - Vehicle->SetVolume(NewVolume); - } - } -} - -FTransform ADReyeVRLevel::GetSpawnPoint(int SpawnPointIndex) const -{ - ACarlaGameModeBase *GM = UCarlaStatics::GetGameMode(GetWorld()); - if (GM != nullptr) - { - TArray SpawnPoints = GM->GetSpawnPointsTransforms(); - size_t WhichPoint = 0; // default to first one - if (SpawnPointIndex < 0) - WhichPoint = FMath::RandRange(0, SpawnPoints.Num()); - else - WhichPoint = FMath::Clamp(SpawnPointIndex, 0, SpawnPoints.Num()); - - if (WhichPoint < SpawnPoints.Num()) // SpawnPoints could be empty - return SpawnPoints[WhichPoint]; - } - /// TODO: return a safe bet (position of the player start maybe?) - return FTransform(FRotator::ZeroRotator, FVector::ZeroVector, FVector::OneVector); -} \ No newline at end of file diff --git a/DReyeVR/LevelScript.h b/DReyeVR/LevelScript.h deleted file mode 100644 index d97b36a..0000000 --- a/DReyeVR/LevelScript.h +++ /dev/null @@ -1,82 +0,0 @@ -#pragma once - -#include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor -#include "Carla/Sensor/DReyeVRData.h" // DReyeVR:: -#include "Engine/LevelScriptActor.h" // ALevelScriptActor -#include // std::unordered_map - -#include "LevelScript.generated.h" - -class AEgoVehicle; -class ADReyeVRPawn; - -UCLASS() -class ADReyeVRLevel : public ALevelScriptActor -{ - GENERATED_UCLASS_BODY() - - public: - ADReyeVRLevel(); - - virtual void BeginPlay() override; - - virtual void BeginDestroy() override; - - virtual void Tick(float DeltaSeconds) override; - - // input handling - void SetupPlayerInputComponent(); - void SetupSpectator(); - bool FindEgoVehicle(); - - // EgoVehicle functions - enum DRIVER - { - HUMAN, - SPECTATOR, - AI, - } ControlMode; - void PossessEgoVehicle(); - void PossessSpectator(); - void HandoffDriverToAI(); - - // Recorder media functions - void PlayPause(); - void FastForward(); - void Rewind(); - void Restart(); - void IncrTimestep(); - void DecrTimestep(); - - // Replayer - void SetupReplayer(); - - // Meta world functions - void SetVolume(); - FTransform GetSpawnPoint(int SpawnPointIndex = 0) const; - - // Custom actors - void ReplayCustomActor(const DReyeVR::CustomActorData &RecorderData, const double Per); - void DrawBBoxes(); - std::unordered_map BBoxes; - - private: - // for handling inputs and possessions - APlayerController *Player = nullptr; - void StartDReyeVRPawn(); - ADReyeVRPawn *DReyeVR_Pawn = nullptr; - - // for toggling bw spectator mode - bool bIsSpectating = true; - APawn *SpectatorPtr = nullptr; - AEgoVehicle *EgoVehiclePtr = nullptr; - - // for audio control - float EgoVolumePercent; - float NonEgoVolumePercent; - float AmbientVolumePercent; - - // for recorder/replayer params - bool bReplaySync = false; // false allows for interpolation - bool bRecorderInitiated = false; // allows tick-wise checking for replayer/recorder -}; \ No newline at end of file diff --git a/Docs/Figures/Install/steamvr-home.jpg b/Docs/Figures/Install/steamvr-home.jpg new file mode 100644 index 0000000..63153ff Binary files /dev/null and b/Docs/Figures/Install/steamvr-home.jpg differ diff --git a/Docs/Figures/Install/steamvr-settings.jpg b/Docs/Figures/Install/steamvr-settings.jpg new file mode 100644 index 0000000..5118a90 Binary files /dev/null and b/Docs/Figures/Install/steamvr-settings.jpg differ diff --git a/Docs/Install.md b/Docs/Install.md index e10de92..f23c737 100644 --- a/Docs/Install.md +++ b/Docs/Install.md @@ -1,39 +1,56 @@ -# Installing `DReyeVR` to a working Carla 0.9.13 build +# Installing `DReyeVR` to a working Carla 0.9.13 build ## Prerequisites -- To continue, this guide assumes the following: - - You have [SteamVR](https://store.steampowered.com/app/250820/SteamVR/) (free) installed and are using a SteamVR compatible headset. - - For eye tracking, we assume you are specifically using an [HTC Vive Pro Eye](https://enterprise.vive.com/us/product/vive-pro-eye-office/) headset, but this is optional as eye tracking can be disabled. - - If you need help setting up Carla/UE4 for VR. Take a look at [SetupVR.md](SetupVR.md) for a more in-depth explanation. - - You have [Unreal Engine 4.26 (Carla)](https://github.com/carlaunreal/unrealengine) installed from source - - Note, if the link does not work for you, you probably need to [join the Epic Games Organization](https://www.unrealengine.com/en-US/ue4-on-github) - - You are running a **Windows 10** or **Linux** x86-64 machine or **MacOS** m1 arm64 machine - - If on **Windows 10** you will *need* `Make-3.81` as per [Carla documentation](https://carla.readthedocs.io/en/latest/build_windows/#system-requirements) - - You have a fully functional vanilla [Carla 0.9.13 build](https://carla.readthedocs.io/en/0.9.13/#building-carla) installed - - This requires the `-b 0.9.13` when cloning (`git clone https://github.com/carla-simulator/carla -b 0.9.13`) from their [GitHub repo](https://github.com/carla-simulator/carla) - - Use [Building on Linux](https://carla.readthedocs.io/en/0.9.13/build_linux/) or [Building on Windows](https://carla.readthedocs.io/en/0.9.13/build_windows/) to follow their instructions on building CARLA 0.9.13. - - If you want to use our PythonAPI patches, you'll need to remove any prior PythonAPI installations - - This means if you [installed carla via pip](https://pypi.org/project/carla/), you'll **need to uninstall** it to proceed. - - (Optional) You have a fully functional default [Carla Scenario Runner v0.9.13 build](https://github.com/carla-simulator/scenario_runner/tree/v0.9.13) - - Simply clone `git clone https://github.com/carla-simulator/scenario_runner -b v0.9.13` and verify it works with your carla build -- **Tl;dr**:Make sure you compile Carla 0.9.13 and ensure it is working as expected. - - ie. `make PythonAPI && make launch` completes without error - - Can verify unit tests pass with `make check` - - -## DReyeVR installation command summary +- Make sure your machine satisfies the prerequisites required by Carla: [Windows](https://carla.readthedocs.io/en/0.9.13/build_windows), [Linux](https://carla.readthedocs.io/en/0.9.13/build_linux), [Mac*](https://github.com/GustavoSilvera/carla/blob/m1/Docs/build_mac.md) +- **IMPORTANT**: If on **Windows** you will **need** [`Make-3.81`](https://gnuwin32.sourceforge.net/packages/make.htm) as per the [Carla documentation](https://carla.readthedocs.io/en/latest/build_windows/#system-requirements) +- If you have previously installed Carla in your PYTHONPATH, you'll need to remove any prior PythonAPI installations + - For instance, if you [installed carla via pip](https://pypi.org/project/carla/), you'll **need to uninstall** it to proceed. + ```bash + pip uninstall carla + ``` + +## Getting started +- You should first make sure DReyeVR is downloaded: + ```bash + git clone https://github.com/HARPLab/DReyeVR --depth 1 + ``` +- You'll first need to install [Unreal Engine 4.26 (HARPLab fork)](https://github.com/HARPLab/UnrealEngine) from source + + ```bash + git clone https://github.com/HARPLab/UnrealEngine -b DReyeVR-0.9.13 --depth 1 + ``` + - **IMPORTANT:** if the link does not work for you, you probably need to [join the Epic Games Organization](https://www.unrealengine.com/en-US/ue4-on-github) to get access to UnrealEngine and all of its forks. + - UE4 build instructions for your system can be found here: [Windows](https://carla.readthedocs.io/en/0.9.13/build_windows/#unreal-engine), [Linux](https://carla.readthedocs.io/en/0.9.13/build_linux/#unreal-engine), [Mac*](https://github.com/GustavoSilvera/carla/blob/m1/Docs/build_mac.md#unreal-engine-fork ) + - NOTE: We only keep our own HARPLab fork of Carla's fork to preserve version compatibility and enable minor features that Carla doesn't need (ex. foveated rendering). + +- You'll then need to clone and build a [vanilla Carla 0.9.13](https://carla.readthedocs.io/en/0.9.13/#building-carla) + ```bash + git clone https://github.com/carla-simulator/carla -b 0.9.13 --depth 1 + ``` + - Use [Building on Linux](https://carla.readthedocs.io/en/0.9.13/build_linux/) for all versions up to Ubuntu 18.04 or [Building on Windows](https://carla.readthedocs.io/en/0.9.13/build_windows/) to follow their instructions on building CARLA 0.9.13. Use [our Ubuntu 20.04 CARLA installation guide](Install_Ubuntu.md) for Ubuntu 20.04. +- (Optional) Similarly, you can install a vanilla [Carla Scenario Runner v0.9.13 ](https://github.com/carla-simulator/scenario_runner/tree/v0.9.13) project to integrate DReyeVR+Carla with Scenario Runner. + ```bash + git clone https://github.com/carla-simulator/scenario-runner -b v0.9.13 --depth 1 + ``` + +(*=The Mac operating system is no longer officially supported by Carla but our development team has made it possible to build both UE4, Carla, and DReyeVR on new Mac machines with Apple Silicon (arm64) hardware. ) + +
+ +# DReyeVR installation command summary
-**NOTE** Since DReyeVR is still installed using `bash`, on Windows you'll need [WSL](https://docs.microsoft.com/en-us/windows/wsl/install) installed. +**NOTE** You'll need a terminal on Linux/Mac. On Windows you'll be fine with the same x64 Native Tools CMD prompt that you used to build Carla. Show command lines to install and build DReyeVR ```bash -# NOTE: On windows, this can almost all be done in WSL, except the make commands which need -# to be done in the "Windows x64 Native Tools Command Prompt for VS 2019" mkdir CarlaDReyeVR && cd CarlaDReyeVR # doing everything in this "CarlaDReyeVR" directory ##################################################### -######### install Carla's UnrealEngine fork ######### +########### install OUR UnrealEngine fork ########### ##################################################### +# Rather than https://github.com/CarlaUnreal/UnrealEngine UE4, you SHOULD clone https://github.com/HARPLab/UnrealEngine +# but otherwise all instructions remain the same. + # Linux: https://carla.readthedocs.io/en/0.9.13/build_linux/#unreal-engine # Windows: https://carla.readthedocs.io/en/0.9.13/build_windows/#unreal-engine @@ -42,18 +59,19 @@ mkdir CarlaDReyeVR && cd CarlaDReyeVR # doing everything in this "CarlaDReyeVR" ##################################################### # Linux: https://carla.readthedocs.io/en/0.9.13/build_linux/ # Windows: https://carla.readthedocs.io/en/0.9.13/build_windows/ -git clone https://github.com/carla-simulator/carla -b 0.9.13 +git clone https://github.com/carla-simulator/carla -b 0.9.13 --depth 1 cd carla -./Update.sh -make PythonAPI && make launch +./Update.sh # linux/mac +Update.bat # Windows +make PythonAPI && make launch # to build vanilla Carla ##################################################### ############## install DReyeVR plugins ############## ##################################################### -# (optional) install SRanipal (https://developer.vive.com/resources/vive-sense/eye-and-facial-tracking-sdk/download/latest/) -mv /PATH/TO/SRANIPALPLUGIN/SDK/03_Unreal/Plugins/SRanipal Unreal/CarlaUE4/Plugins/ # install to carla +# (optional) install SRanipal (eye tracking) +mv /PATH/TO/SRANIPALPLUGIN/SDK/03_Unreal/Plugins/SRanipal Unreal/CarlaUE4/Plugins/ -# (optional) install LogitechWheelPlugin +# (optional) install LogitechWheelPlugin (steering wheel) git clone https://github.com/HARPLab/LogitechWheelPlugin mv LogitechWheelPlugin/LogitechWheelPlugin Unreal/CarlaUE4/Plugins/ # install to carla @@ -76,8 +94,6 @@ make install CARLA=../carla SR=../scenario_runner make install CARLA=../carla make install SR=../scenario_runner -make patch-sranipal CARLA=../carla # only applies if you use SRanipal - # run filesystem checks after installing make check CARLA=../carla cd .. @@ -93,46 +109,58 @@ make check # run Carla unit tests ```
+ +
+ ## Simple install -Technically, the above prerequisites are all you really need to install DReyeVR and get a barebones VR ego-vehicle with **no eyetracking** and **no racing wheel integration**. If this suits your needs, simply skip down to the [Install DReyeVR](Install.md#installing-dreyevr) section of this doc and set the following variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: +Technically, the above prerequisites are all you really need to install DReyeVR and get a barebones VR ego-vehicle with **no eyetracking** and **no racing wheel integration**. If this suits your needs, simply skip down to the [Install DReyeVR Core](Install.md#installing-dreyevr-core) section of this doc and set the following variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: ```c# -//////////////////////////////////////////////////////////////////////////////////// +///////////////////////////////////////////////////////////// // Edit these variables to enable/disable features of DReyeVR bool UseSRanipalPlugin = true; bool UseLogitechPlugin = true; ... -//////////////////////////////////////////////////////////////////////////////////// +///////////////////////////////////////////////////////////// ``` - NOTE: you only need to install the SRanipal plugin if `UseSRanipalPlugin` is enabled, and similarly you only need to install the Logitech plugin if `UseLogitechPlugin` is enabled. -*** -## First Steps +# Installing DReyeVR Plugins Before installing `DReyeVR`, we'll also need to install the dependencies: -*** +- **SteamVR**: Required for VR +- **SRanipal***: Required for eye tracking (with HTC Vive Pro Eye), optional otherwise +- **LogitechWheelPlugin***: Required for Logitech Steering Wheel, optional otherwise + +(* = optional, depends on the features you are looking for) + ## SteamVR -### **Enabling SteamVR in UE4** - - In the Editor for Carla go to `Settings->Plugins->Virtual Reality->SteamVR` and enable the plugin - - Note that on Linux this you may need to install it through the [Valve GitHub repo](https://github.com/ValveSoftware/SteamVR-for-Linux) - - UE4DropDown +### **Download Steam and SteamVR** + - You'll need to use [SteamVR](https://store.steampowered.com/app/250820/SteamVR/) for the VR rendering environment, so you should first download the [Steam client application](https://store.steampowered.com/about/). + - From within the steam client, you can browse in store->search "[SteamVR](https://store.steampowered.com/app/250820/SteamVR/)" and download the free-to-install system utility. + + + + - You should be able to launch SteamVR from the client and in the small pop-up window reach both settings and "show VR view" + - Make sure to calibrate the VR system to your setup and preferences! + - Additionally we recommend disabling the "Motion Smoothing" effect within SteamVR Settings to avoid nasty distortion artifacts during rendering. + - SteamVR-settings *** ## HTC Eye Tracker Plugin ### **Download `SRanipal`** - - ## What is this? - - We are using [HTC's SRanipal plugin](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-tracking-sdk-sranipal/) as the primary means to communicate between Unreal Engine 4 and the Vive's Eye Tracker. - - To learn more about SRanipal and for **first-time-setup**, see this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC - - You'll need a (free-to-create) Vive developer account to [download](https://hub.vive.com/en-US/download) the following: - - `VIVE_SRanipalInstaller_1.3.X.Y.msi` -- executable to install Tobii firmware - - `SDK_v1.3.X.Y.zip` -- includes the Unreal plugin - - Our work has been tested on [SRanipal version 1.3.3.0](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-and-facial-tracking-sdk/) (latest version at time of writing) which we cannot redistribute. - - Bug 1: [Possible Bug in Unreal SDK for Left/Right Eye Gazes](https://forum.vive.com/topic/9306-possible-bug-in-unreal-sdk-for-leftright-eye-gazes/?ct=1613756396) - - Bug 2: Conflict with using `#define ERROR` with `UE4` that prevents compilation - - This can be fixed by running the [`patch_sranipal.sh`](../Scripts/patch_sranipal.sh) script in [`Scripts`](../Scripts) once SRanipal is installed - - You **must** fix **Bug 2** with in order to build, but *Bug 1* is more benign. - - if *Bug 1* still occurs in the latest `SRanipal` then you can edit the macro `SRANIPAL_EYE_SWAP_FIXED` in `EgoSensor.h` to `true`. This simply swaps the the `Right->GazeRay` and `Left->GazeRay` in [`EgoSensor.cpp`](../DReyeVR/EgoSensor.cpp) - - It is recommended to re-calibrate the SRanipal eye tracker plugin for every new participant in an experiment. To see how to do this check out this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC - -### **Installing SRanipal** + 0. *What is SRanipal?* + - We are using [HTC's SRanipal plugin](https://developer.vive.com/resources/vive-sense/sdk/vive-eye-tracking-sdk-sranipal/) as the means to communicate between Unreal Engine 4 and the Vive's Eye Tracker. + - To learn more about SRanipal and for **first-time-setup**, see this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC + 1. You'll need a (free-to-create) [Vive developer account](https://hub.vive.com/sso/login) to download the following: + - a) [`VIVE_SRanipalInstaller_1.3.2.0.msi`](https://hub.vive.com/en-US/download/VIVE_SRanipalInstaller_1.3.2.0.msi) -- executable to install Tobii firmware + - b) [`SDK_v1.3.3.0.zip`](https://hub.vive.com/en-US/download/SDK-v1.3.3.0.zip) -- includes the Unreal plugin + - **IMPORTANT**: The SRanipal versions above 1.3.6.0 are NOT supported and cause wild crashes! + - **If the download links above don't work for you, make sure you have a Vive Developer account! (Or [contact](mailto:gustavo@silvera.cloud) us directly to help you)** + 2. Install the Tobii firmware by double-clicking the `.msi` installer + - Once installed, you should see the `SR_runtime.exe` program available from the Start Menu. Launch it as administrator and you should see the robot head icon in the Windows system tray as follows: + - ![SR_runtime](https://mariosbikos.com/wp-content/uploads/2020/02/image-30.png) + - Image Credit: [MariosBikos](https://forum.htc.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine) + +### **Installing SRanipal UE4 Plugin** - After downloading the `.zip` file, unzipping it should present a directory similar to this - ``` SDK @@ -150,6 +178,9 @@ Before installing `DReyeVR`, we'll also need to install the dependencies: # assumes CARLA_ROOT is defined, else just use your Carla path cp -r Plugins/SRanipal $CARLA_ROOT/Unreal/CarlaUE4/Plugins/ ``` + - It is recommended to re-calibrate the SRanipal eye tracker plugin for every new participant in an experiment. You can do this by entering SteamVR home, and clicking the small icon in the bottom menu bar to calibrate eye tracker to the headset wearer. + - ![Calibration](Figures/Install/steamvr-home.jpg) + - You can find more information by checking out this [guide on foveated rendering using SRanipal](https://forum.vive.com/topic/7434-getting-started-with-vrs-foveated-rendering-using-htc-vive-pro-eye-unreal-engine/) by HTC developer MariosBikos_HTC *** ## Logitech Wheel Plugin ### **Installing Logitech Wheel Plugin** @@ -168,24 +199,61 @@ Before installing `DReyeVR`, we'll also need to install the dependencies: - After installing these plugins, you should see a `Unreal/CarlaUE4/Plugins` that looks like this: - ``` Plugins - - Carla/ - - CarlaExporter/ - - LogitechWheelPlugin/ - - SRanipal/ + ├── Carla # unchanged + │ └── ... + ├── CarlaExporter # unchanged + │ └── ... + ├── LogitechWheelPlugin # if installed + │ ├── Binaries + │ ├── Doc + │ ├── Logitech + │ ├── LogitechWheelPlugin.uplugin + │ ├── Resources + │ └── Source + └── SRanipal # if installed + ├── Binaries + ├── Config + ├── Content + ├── Resources + ├── Source + └── SRanipal.uplugin ``` + - If you still have questions or issues, feel free to post an issue on our [Issues](https://github.com/HARPLab/DReyeVR/issues) page and we'll try our best to help you out. -*** +
+
-## Using `conda` for PythonAPI -### **[OPTIONAL]Using Conda for the PythonAPI** - - While not at all required for DReyeVR, for those interested in using an Anaconda environment for their PythonAPI have to jump through a couple more hoops to get started: - - To begin working with the `PythonAPI` in a `Carla` based Anaconda environment you can follow [this guide](https://github.com/carla-simulator/carla/issues/1054) to create the environment. If doing work with the `python` clients it is advisable to use a `Conda` environment. This is especially useful for avoiding the `ModuleNotFoundError: No module named 'carla'` errors that occur when you're missing `Carla` python. - ```properties +# Installing `DReyeVR` Core + + +- **IMPORTANT** The installation requires that `make`, `python` and `git` are available on your shell. +- You only need to install to a `CARLA` directory, ScenarioRunner is optional. + - If you don't provide the `make` variables `CARLA=...` or `SR=...` the installation wizard will automatically detect your install destination by looking at the environment variables `CARLA_ROOT` and `SCENARIO_RUNNER_ROOT` required by Carla. + +```bash +# the CARLA= and SR= variables are optional +make install CARLA=../carla SR=../scenario_runner +# or +make install CARLA=../carla +make install SR=../scenario_runner + +# run filesystem checks after installing +make check CARLA=../carla +``` +**NOTE:** to learn more about how the DReyeVR `make` system works, see [`Scripts/README.md`](../Scripts/README.md) + + +# Building `DReyeVR` PythonAPI +## Using [`conda`](https://www.anaconda.com/products/distribution) for the PythonAPI + - While not required for DReyeVR, we highly recommend compartmentalizing Python installations via isolated environments such as [`anaconda`](https://www.anaconda.com/products/distribution) + - First download and install Anaconda to your machine from [here](https://www.anaconda.com/products/distribution). + ```bash # in /PATH/TO/CARLA/ - conda create --name carla python=3.7.2 - conda activate carla + conda create --name carla13 python=3.7.2 + conda activate carla13 # will need to run this ONCE before opening a new terminal! + conda install numpy ``` - - **NOTE (Linux)**: You might run into a problem when compiling Boost 1.72.0 (required by `LibCarla`). + - **READ THIS FIRST (Linux)**: You might run into a problem when compiling Boost 1.72.0 (required by `LibCarla`).
Show instructions to get Anaconda working on Linux @@ -193,10 +261,11 @@ Before installing `DReyeVR`, we'll also need to install the dependencies: - ```bash # find anaconda install: which python3 - ... - > PATH/TO/ANACONDA/envs/carla/bin/python3 # example output + ... PATH/TO/ANACONDA/envs/carla/bin/python3 # example output + # go to carla/install dir from here cd PATH/TO/ANACONDA/envs/carla/install + # create a symlink between python3.7 -> python3.7m ln -s python3.7m python3.7 ``` @@ -205,20 +274,26 @@ Before installing `DReyeVR`, we'll also need to install the dependencies:
- - **NOTE (Windows)**: Anaconda is not natively supported by CARLA, but it is very useful when managing multiple versions of CARLA and containerizing all the CARLA python dependencies. + - **READ THIS FIRST (Windows)**: Windows anaconda is a bit more of a pain to deal with.
Show instructions to get Anaconda working on Windows - 1. Create your environment + 1. Enable your environment ```bat - conda create --name carla python=3.7.2 - conda activate carla + conda activate carla13 ``` 2. When trying to `make PythonAPI` you'll need to apply [this fix](https://github.com/carla-simulator/carla/issues/2881#issuecomment-699452386) (Replace `py` with `python` in `BuildPythonAPI.bat`) ```bat - make PythonAPI + ... + rem previously called "py -3 setup.py ..." --> replace with just "python setup.py ..." + if %BUILD_FOR_PYTHON3%==true ( + echo Building Python API for Python 3. + python setup.py bdist_egg bdist_wheel + if %errorlevel% neq 0 goto error_build_wheel + ) ``` + - This is because Carla (by default) installs the PythonAPI to the native Python client that comes pre-installed with every Windows machine. This goes 100% against compartmentalizing python environments so we have to patch this file to proceed. 3. Add carla to "path" to locate the PythonAPI and ScenarioRunner. But since Anaconda [does not use the traditional `PYTHONPATH`](https://stackoverflow.com/questions/37006114/anaconda-permanently-include-external-packages-like-in-pythonpath) you'll need to: - 3.1. Create a file `carla.pth` in `\PATH\TO\ANACONDA\envs\carla\Lib\site-packages\` - 3.2. Insert the following content into `carla.pth`: @@ -231,22 +306,23 @@ Before installing `DReyeVR`, we'll also need to install the dependencies: C:\PATH\TO\SCENARIO_RUNNER\ ``` 4. Install the specific carla wheel (`whl`) to Anaconda - ```bat + ```bash conda activate carla - pip install --no-deps PATH\TO\CARLA\PythonAPI\carla\dist\carla-0.9.13-cp37-cp37m-win_amd64.whl - cd \PATH\TO\SCENARIO_RUNNER + pip install --no-deps --force-reinstall PATH\TO\CARLA\PythonAPI\carla\dist\carla-0.9.13-cp37-cp37m-win_amd64.whl + + # if applicable (and you installed Scenario runner) + cd %SCENARIO_RUNNER_ROOT% pip install -r requirements.txt # install all SR dependencies - conda install numpy ``` 5. Finally, there are some problems with `shapely` (SR dependency) and Conda. Luckily the solution is simple: - Copy the files: - - `PATH\TO\ANACONDA\envs\carla\Lib\site-packages\shapely\DLLs\geos.dll` - - `PATH\TO\ANACONDA\envs\carla\Lib\site-packages\shapely\DLLs\geos_c.dll` + - `PATH\TO\ANACONDA\envs\carla13\Lib\site-packages\shapely\DLLs\geos.dll` + - `PATH\TO\ANACONDA\envs\carla13\Lib\site-packages\shapely\DLLs\geos_c.dll` - To destination: - - `PATH\TO\ANACONDA\envs\carla\Library\bin\` + - `PATH\TO\ANACONDA\envs\carla13\Library\bin\` 6. Now finally, you should be able to verify all PythonAPI actions work as expected via: ```bat - conda activate carla + conda activate carla13 python >>> Python 3.7.2 (default, Feb 21 2019, 17:35:59) [MSC v.1915 64 bit (AMD64)] :: Anaconda, Inc. on win32 >>> Type "help", "copyright", "credits" or "license" for more information. @@ -255,34 +331,59 @@ Before installing `DReyeVR`, we'll also need to install the dependencies: >>> from scenario_runner import ScenarioRunner ``` With all these imports passing (no error/warning messages), you're good to go! +
-*** +Now you can finally build the PythonAPI to this isolated conda environment. + ```bash + conda activate carla13 + (carla13) make PythonAPI # builds LibCarla and PythonAPI to your (conda) python environment + ``` + - NOTE: You'll need to run `conda activate carla13` every time you open a new terminal if you want to build DReyeVR since the shell needs to know which python environment to use. Luckily this minor inconvenience saves us from the significant headaches that arise when dealing with multiple `python` projects, Carla installations, and versions, etc. +## Sanity Check: -## Installing `DReyeVR` -(Once you are done with this step, you should have a carla repo that looks just like this [Carla fork](https://github.com/HARPLab/carla/tree/DReyeVR-0.9.13) we created with the installation (and other minor things) pre-applied.) +It is nice to verify that the Carla PythonAPI is correctly visible in conda, to do this you should see all the following attributes in the `carla` module once calling `dir` on it. -- **IMPORTANT** The installation requires that `make`, `python` and `git` are available on your shell. -- You only need to install to a CARLA directory, ScenarioRunner is optional +
+Show instructions to verify Carla PythonAPI is installed ```bash -# the CARLA= and SR= variables are optional -make install CARLA=../carla SR=../scenario_runner -# or -make install CARLA=../carla -make install SR=../scenario_runner +# in your terminal (linux) or cmd (Windows) +conda activate carla13 # (if using conda) +(carla13) python # should default to python3!! +``` -# run filesystem checks after installing -make check CARLA=../carla -make patch-sranipal CARLA=../carla # only applies if you use SRanipal +```python +#in Python +... +>>> import carla +>>> dir(carla) +# the following output means carla is not correctly installed :( +>>> ['__doc__', '__file__', '__loader__', '__name__', '__package__', '__path__', '__spec__'] + +# OR the following output means carla is installed :) +>>> ['Actor', 'ActorAttribute', 'ActorAttributeType', 'ActorBlueprint', 'ActorList', 'ActorSnapshot', 'ActorState', 'AttachmentType', 'BlueprintLibrary', 'BoundingBox', 'CityObjectLabel', 'Client', 'ClientSideSensor', 'CollisionEvent', 'Color', 'ColorConverter', 'DReyeVREvent', 'DVSEvent', 'DVSEventArray', 'DebugHelper', 'EnvironmentObject', 'FakeImage', 'FloatColor', 'GearPhysicsControl', 'GeoLocation', 'GnssMeasurement', 'IMUMeasurement', 'Image', 'Junction', 'LabelledPoint', 'Landmark', 'LandmarkOrientation', 'LandmarkType', 'LaneChange', 'LaneInvasionEvent', 'LaneInvasionSensor', 'LaneMarking', 'LaneMarkingColor', 'LaneMarkingType', 'LaneType', 'LidarDetection', 'LidarMeasurement', 'Light', 'LightGroup', 'LightManager', 'LightState', 'Location', 'Map', 'MapLayer', 'MaterialParameter', 'ObstacleDetectionEvent', 'OpendriveGenerationParameters', 'OpticalFlowImage', 'OpticalFlowPixel', 'Osm2Odr', 'Osm2OdrSettings', 'RadarDetection', 'RadarMeasurement', 'Rotation', 'SemanticLidarDetection', 'SemanticLidarMeasurement', 'Sensor', 'SensorData', 'ServerSideSensor', 'TextureColor', 'TextureFloatColor', 'Timestamp', 'TrafficLight', 'TrafficLightState', 'TrafficManager', 'TrafficSign', 'Transform', 'Vector2D', 'Vector3D', 'Vehicle', 'VehicleControl', 'VehicleDoor', 'VehicleLightState', 'VehiclePhysicsControl', 'VehicleWheelLocation', 'Walker', 'WalkerAIController', 'WalkerBoneControlIn', 'WalkerBoneControlOut', 'WalkerControl', 'Waypoint', 'WeatherParameters', 'WheelPhysicsControl', 'World', 'WorldSettings', 'WorldSnapshot', '__builtins__', '__cached__', '__doc__', '__file__', '__loader__', '__name__', '__package__', '__path__', '__spec__', 'bone_transform', 'bone_transform_out', 'command', 'libcarla', 'vector_of_bones', 'vector_of_bones_out', 'vector_of_gears', 'vector_of_ints', 'vector_of_transform', 'vector_of_vector2D', 'vector_of_wheels'] ``` -**NOTE:** to learn more about how the DReyeVR `make` system works, see [`Scripts/README.md`](../Scripts/README.md) +
-*** +
-## Upgrading `DReyeVR` -If you currently have an older version of `DReyeVR` installed and want to upgrade to a newer version, the recommended strategy is as follows: +## Future modifications + +Additionally, if you make changes to the `PythonAPI` source and need to rebuild (`make PythonAPI` again) when using Conda you should reinstall the `.whl` file to ensure your changes will be reflected in the environment: + - ```bash + conda activate carla + + pip install --no-deps --force-reinstall /PATH/TO/CARLA/PythonAPI/carla/dist/carla-YOUR_VERSION.whl + ``` + + +# Upgrading `DReyeVR` +If you currently have an older version of `DReyeVR` installed and want to upgrade to a newer version, it is best to re-install DReyeVR from a fresh Carla repository. You can manually delete the `carla` repository and re-clone it directly (carefully ensuring the versions match) or use our provided scripts which attempt to reset the repository for you: + +
+ Show instructions to use DReyeVR scripts to reset CARLA repo **IMPORTANT:** the `DReyeVR` clean script will overwrite and reset the Carla repository you specify, so make your backups now if you have any unstaged code. (`git reset --hard HEAD` and `git clean -fd` will be invoked, so if you commit your local changes they will be safe) @@ -293,13 +394,15 @@ make clean # it is a good idea to clean the Content/ directory which is not tracked by Carla's git system rm -rf Unreal/CarlaUE4/Content/ -./Update.sh # re-install the Content fresh from Carla's servers (use .bat on Windows) + +# re-install the Content fresh from Carla's servers +./Update.sh # Linux/Mac +Update.bat # Windows # next, go to DReyeVR and get the latest updates cd /PATH/TO/DReyeVR/ git pull origin main # or dev, or whatever branch - # next, run the DReyeVR-cleaner to automatically hard-reset the Carla repo # accept the prompt to hard-clean CARLA, note that this will reset tracked and remove untracked files make clean CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional @@ -307,7 +410,7 @@ make clean CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional # now, you can cleanly install DReyeVR over Carla again make install CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional -# its a good idea to check that the Carla repository has all the expected files +# it's a good idea to check that the Carla repository has all the expected files make check CARLA=/PATH/TO/CARLA SR=/PATH/TO/SR # both args are optional # finally, you can go back to Carla and rebuild @@ -321,26 +424,34 @@ make package As long as you have no errors in the previous sections, you should be able to just build the `Carla` project with our `DReyeVR` files as follows: -## Building `DReyeVR` -- If you are not interested in using SRanipal or the LogitechWheelPlugin, you can disable these at compile-time by changing the variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: - - ```c# - ////////////////////////////////////////////////////////////// - // Edit these variables to enable/disable features of DReyeVR - bool UseSRanipalPlugin = true; - bool UseLogitechPlugin = true; - ... - ////////////////////////////////////////////////////////////// - ``` -- Open the project directory in any terminal (Unix) or `Windows x64 Native Tools Command Prompt for VS 2019` (Windows) +
+ +
+
+ +# Building `DReyeVR` UE4 +If you are not interested in using SRanipal or the LogitechWheelPlugin, you can disable these at compile-time by changing the variables in `Unreal/CarlaUE4/Source/CarlaUE4/CarlaUE4.Build.cs` to `false`: +```c# + ///////////////////////////////////////////////////////////// + // Edit these variables to enable/disable features of DReyeVR + bool UseSRanipalPlugin = true; + bool UseLogitechPlugin = true; + ... + ///////////////////////////////////////////////////////////// + ``` + +Finally, open the project directory in any terminal (Linux/Mac) or `Windows x64 Native Tools Command Prompt for VS 2019` (Windows) and run: ```bash make PythonAPI # build the PythonAPI & LibCarla -make launch # build the UE4 game in editor +make launch # build the development UE4 game in editor -make package # build the optimized UE4 packaged game +make package # build the optimized UE4 packaged game (shipping) ``` -With the package built, run the Carla executable in VR mode with: +# Running `DReyeVR` + +With the shipping package built, run the Carla (with DReyeVR installed) executable in VR mode with: ```bash # on Unix cd /PATH/TO/CARLA/Dist/CARLA_Shipping_0.9.13-dirty/LinuxNoEditor/ # or MacNoEditor on MacOS @@ -356,8 +467,8 @@ CarlaUE4.exe -vr **NOTE 2** You also don't necessarily NEED to run DReyeVR in VR. If you omit the `-vr` flag then you will be greeted with a flat-screen Carla game with the same features available for DReyeVR, just not in VR. -*** +
-## Now what? +# Now what? Now that you've successfully installed DReyeVR continue to [`Usage.md`](Usage.md) to learn how to use DReyeVR for your own VR driving research simulator. diff --git a/Docs/Install_Ubuntu.md b/Docs/Install_Ubuntu.md new file mode 100644 index 0000000..3c2ad78 --- /dev/null +++ b/Docs/Install_Ubuntu.md @@ -0,0 +1,97 @@ +# Installing Carla on Ubuntu 20.04 +This guide is for installing Carla 0.9.13 (along with Unreal Engine 4.26) build on Ubuntu 20.04.5 (Focal Fosca). It is largely based on [this tutorial](https://carla.readthedocs.io/en/latest/build_linux/) by Carla, and can be thought of as a shorter updated of it specifically for Ubuntu 20.04 and DReyeVR. Check out the original tutorial tutorial for more detailed explanations of some the commands. Commands themselves, however, slightly differ from the original version. + +## Part One: Prerequisites +- **Ubuntu 20.04** +- **130 GB disk space.** Carla will take around 31 GB and Unreal Engine will take around 91 GB so have about 130 GB free to account for both of these plus additional minor software installations. +- **An adequate GPU**. CARLA aims for realistic simulations, so the server needs at least a 6 GB GPU although 8 GB is recommended. A dedicated GPU is highly recommended for machine learning. +- **Two TCP ports and good internet connection.** 2000 and 2001 by default. Make sure that these ports are not blocked by firewalls or any other applications. +- **IMPORTANT: Proprietary drivers installed.** Please make sure that you are using the latest stable version of proprietary drivers (for instance, Nvidia). Check [this guide](https://linuxconfig.org/how-to-install-the-nvidia-drivers-on-ubuntu-20-04-focal-fossa-linux) for installing and updating the Nvidia driver on Ubuntu 20.04. + +## Installing software requirements +Please use the following set of commands to install the necessary software packages. +**Note**: you might want to go over each of the listed packages separately to ensure that each was installed correctly to avoid issues during the installation. Later on, the missing packages will be harder to track. +```bash +sudo apt-add-repository "deb http://apt.llvm.org/focal/ llvm-toolchain-focal main" +sudo apt-get install build-essential clang-8 lld-8 g++-7 cmake ninja-build libvulkan1 python-dev python3-dev python3-pip libpng-dev libtiff5-dev libjpeg-dev tzdata sed curl unzip autoconf libtool rsync libxml2-dev git +sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-8/bin/clang++ 180 && +sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-8/bin/clang 180 +``` + +#### Clang issue: +One of the issues specific to Ubuntu 20.04 installation is the **clang** compiler. The CARLA team uses clang-8 and LLVM's libc++. while clang-8 can be installed on Ubuntu 20.04, it is rather outdated and does not catch some of the existing bugs within carla. If you want to use a different version of clang and libc++, follow the instructions below: +
+how to use a different clang version +Uninstall clang-8 (installed if you executed the previous command): + +```bash +sudo apt-get remove clang-8 lld-8 +sudo rm /usr/bin/clang /usr/bin/clang++ +``` + +Install version 10: +```bash +sudo apt-get install clang-10 lld-10 +``` +Set up clang and clang++ commands: +```bash +sudo update-alternatives --install /usr/bin/clang++ clang++ /usr/lib/llvm-10/bin/clang++ 180 && +sudo update-alternatives --install /usr/bin/clang clang /usr/lib/llvm-10/bin/clang 180 +``` +Create a symbolic link that would tell the system to use version 10 whenever it encounters `usr/bin/clang-8` in one of the CARLA setup or installation scripts: +```bash +sudo ln -s /usr/bin/clang /usr/bin/clang-8 +sudo ln -s /usr/bin/clang++ /usr/bin/clang++-8 +``` +
+
+ + +### Python dependencies +Version 20.3 or higher of **pip3** is required. To check if you have a suitable version, run the following command: +```bash +pip3 -V +``` +If you need to upgrade: +```bash +pip3 install --upgrade pip +``` +You might be prompted to add the directory of the newer version to PATH. If yes, do so. + +You must install the following Python dependencies: +``` +pip3 install --user -Iv setuptools==47.3.1 && +pip3 install --user distro && +pip3 install --user wheel auditwheel && +pip3 install nose2 +``` +Some of the installation and setup scripts use the deprecated **python** command. One way to avoid the issues caused by this is with a symbolic link: +``` +sudo ln -s /usr/bin/python3 /usr/bin/python +``` +If your file is named other than **python3**, substitute python 3 for your python version. +
+ +### Unreal Engine +This section does not require updates or modifications. Please follow the exact steps from the corresponding section of [this tutorial](https://carla.readthedocs.io/en/latest/build_linux/). +
+ +## Part Two: Build CARLA +**Note**: downloading aria2 with `sudo apt-get install aria2` will speed up the following commands. + +Clone the CARLA repository: +```bash +git clone https://github.com/carla-simulator/carla -b 0.9.13 +``` +Once download is finished, from the new **carla** directory, run +```bash +Update.sh +``` + +Navigate to the **carla** directory. Open **./Util/BuildTools/Setup.sh** and replace `XERCESC_VERSION=3.2.3` (line 428) with `XERCESC_VERSION=3.2.4`. Next, open **./Util/BuildTools/BuildOSM2ODR.sh**, and replace all instances of `xerces-c-3.2.3` with `xerces-c-3.2.4`. + + +Follow the rest of the instructions from the [tutorial](https://carla.readthedocs.io/en/latest/build_linux/). + + +Now that you have a working CARLA 0.9.13 build, go back to the [DReyeVR installation guide](https://github.com/HARPLab/DReyeVR/blob/main/Docs/Install.md) and follow the rest of the steps to install DReyeVR on top of it. diff --git a/Docs/Model.md b/Docs/Model.md index 68dd156..52448b4 100644 --- a/Docs/Model.md +++ b/Docs/Model.md @@ -116,58 +116,10 @@ This will allow you to create a plain simple static mesh (cyan underline) from t Now that we have a reasonable steering wheel model as a simple static mesh, it is easy to spawn it and attach it to the ego-vehicle (currently without a steering wheel) in code. Managing it in code is nice because it will allow us to `SetRelativeRotation` of the mesh dynamically on every tick, allowing it to be responsive to our inputs at runtime. The first step to Spawn the steering wheel in code is to find its mesh in the editor. Right click on the static mesh (cyan underline) and select `Copy Reference`. For me it looks like this: -- `StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/SteeringWheel/SM_SteeringWheel_DReyeVR.SM_SteeringWheel_DReyeVR''` +- `"StaticMesh'/Game/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.Wheel_StaticMeshl_model3'"` (Note that we won't be needing any of the other steering wheel assets anymore, feel free to delete them) -The general strategy for adding Unreal components in code is to spawn them in the constructor then use their reference alongside their C++ API. For our case we'll only need a constructor and a tick method: -```c++ -// In EgoVehicle.h -////////////////:STEERINGWHEEL://////////////// -void ConstructSteeringWheel(); // needs to be called in the constructor -UPROPERTY(Category = Steering, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) -class UStaticMeshComponent *SteeringWheel; -void TickSteeringWheel(const float DeltaTime); -FVector InitWheelLocation; -FRotator InitWheelRotation; -float MaxSteerAngleDeg; -float MaxSteerVelocity; -float SteeringScale; -``` - -```c++ -// In EgoVehicle.cpp -void AEgoVehicle::ConstructSteeringWheel() -{ - static ConstructorHelpers::FObjectFinder SteeringWheelSM( - TEXT("StaticMesh'/Game/Carla/Blueprints/Vehicles/DReyeVR/SteeringWheel/" - "SM_SteeringWheel_DReyeVR.SM_SteeringWheel_DReyeVR'")); // from earlier - SteeringWheel = CreateDefaultSubobject(FName("SteeringWheel")); - SteeringWheel->SetStaticMesh(SteeringWheelSM.Object); - SteeringWheel->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself - SteeringWheel->SetRelativeLocation(InitWheelLocation); - SteeringWheel->SetRelativeRotation(InitWheelRotation); - SteeringWheel->SetGenerateOverlapEvents(false); // don't collide with itself - SteeringWheel->SetCollisionEnabled(ECollisionEnabled::NoCollision); - SteeringWheel->SetVisibility(true); -} - -void AEgoVehicle::TickSteeringWheel(const float DeltaTime) -{ - const FRotator CurrentRotation = SteeringWheel->GetRelativeRotation(); - const float TargetAngle = GetVehicleInputs().Steering * SteeringScale; - float DeltaAngle = (TargetAngle - CurrentRotation.Roll); - - // place a speed-limit on the steering wheel - DeltaAngle = FMath::Clamp(DeltaAngle, -MaxSteerVelocity, MaxSteerVelocity); - - // create the new rotation using the deltas - FRotator NewRotation = CurrentRotation + DeltaTime * FRotator(0.f, 0.f, DeltaAngle); - - // Clamp the roll amount so the wheel can't spin infinitely - NewRotation.Roll = FMath::Clamp(NewRotation.Roll, -MaxSteerAngleDeg, MaxSteerAngleDeg); - SteeringWheel->SetRelativeRotation(NewRotation); -} -``` +The general strategy for adding Unreal components in code is to spawn them in the constructor then use their reference alongside their C++ API. For our case we'll only need a constructor and a tick method (See [EgoVehicle::ConstructSteeringWheel & EgoVehicle::TickSteeringWheel](../DReyeVR/EgoVehicle.cpp)) Now enjoy a responsive steering wheel asset attached to the EgoVehicle as you drive around! \ No newline at end of file diff --git a/Docs/Usage.md b/Docs/Usage.md index 1c26d1b..0ce21b1 100644 --- a/Docs/Usage.md +++ b/Docs/Usage.md @@ -96,8 +96,8 @@ cd $SCENARIO_RUNNER_ROOT # go to scenario-runner/ ## Using our new DReyeVR PythonAPI For your own custom scripts, we recommend taking a look at the [`DReyeVR_utils.py`](../PythonAPI/DReyeVR_utils.py) file, specifically the two functions: -- `find_ego_vehicle` which takes in the `carla.libcarla.World` instance and returns the DReyeVR ego-vehicle (`carla.libcarla.Vehicle`) present in the world (or `None` if there is none) -- `find_ego_sensor` which takes in the `carla.libcarla.World` instance and returns the DReyeVR eye tracker (`carla.libcarla.Sensor`) present in the world (or `None` if there is none) +- `find_ego_vehicle` which takes in the `carla.libcarla.World` instance and returns the DReyeVR ego-vehicle (`carla.libcarla.Vehicle`) present in the world or spawns one in if there is none. +- `find_ego_sensor` which takes in the `carla.libcarla.World` instance and returns the DReyeVR eye tracker (`carla.libcarla.Sensor`) present in the world, which should be attached to the spawned EgoVehicle (if the EgoVehicle is spawned) Then, in your script, you can follow the technique we used in `schematic_mode.py` such as: ```python @@ -415,7 +415,7 @@ void AEgoVehicle::ReadConfigVariables() Then, in the config file, you can simply add this variable in the section and variable described from `ReadConfigValue` as follows ```ini [MyFavourites] -Number=867.5309; Note you can also write comments! +Number=867.5309 # You can also write comments! ``` And, just like the other variables in the file, you can bunch and organize them together under the same section header. @@ -424,10 +424,19 @@ And, just like the other variables in the file, you can bunch and organize them ## Motivations After performing (and recording) an [experiment](../ScenarioRunner/run_experiment.py), we are provided with a log of everything that happened in the simulator that we can use for live reenactment and post-hoc analysis. It is often the case that after some postprocessing on the data, we might be interested in overlaying something on the simulator view to match what a participant was seeing/doing and what the world looked like. Unfortunately, it is difficult to get the exact image frame corresponding to an exact recording event using an asynchronous screen recorder such as OBS, therefore we baked in this functionality within the engine itself, so it can directly go to any recorded event and take a high quality screenshot. The end result is the exact frame-by-frame views corresponding to the recorded world conditions without interpolation. -To enable this feature, toggle the `RunSyncReplay` flag in [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) under the `[Replayer]` section. This will allow for frame-by-frame reenactment (otherwise the replay will respect wall-clock-time and introduce interpolation between frames). In order to additionally perform frame capture during this replay, make sure to have the `RecordFrames` flag enabled as well. There are several other frame capture options below such as resolution and gamma parameters. +### Synchronized replay +To have this functionality, disable the `ReplayInterpolation` flag in [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) under the `[Replayer]` section. Disabling replay interpolation will allow for frame-by-frame reenactment of what was captured (otherwise the replay will respect wall-clock-time and introduce interpolation between frames). -The resulting frame capture images (`.png` or `.jpg` depending on the `FileFormatJPG` flag) will be found in `Unreal/CarlaUE4/{FrameDir}/{DateTimeNow}/{FrameName}*` where `{FrameDir}` and `{FrameName}` are both determined in the [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini). The `{DateTimeNow}` string is uniquely based on your machine's local current time so you can run multiple recordings without overwriting old files. +### Frame capture +While replaying (so, after the experiment was conducted) we can additionally perform frame capture during this replay. Since taking high-res screnshots is expensive, this is a slow process that is done during replays when real-time performance is less important. To enable this feature, enable the `RecordFrames` flag in the `[Replayer]` section as well. There are several other frame capture options below such as resolution and gamma parameters. +The resulting frame capture images (`.png` or `.jpg` depending on the `FileFormatJPG` flag) will be found in `Unreal/CarlaUE4/{FrameDir}/{DateTimeNow}/{FrameName}*` where `{FrameDir}` and `{FrameName}` are both determined in the [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini). The `{DateTimeNow}` string is uniquely based on your machine's local current time so you can run multiple recordings without overwriting old files. + +**NOTE**: Depending on whether you are running the Editor mode or package mode of DReyeVR will place the FrameCapture directory in the following: +- Editor (debug): `%CARLA_ROOT%\Unreal\CarlaUE4\FrameCap\` +- Package (shipping): `%CARLA_ROOT%\Build\UE4Carla\0.9.13-dirty\WindowsNoEditor\CarlaUE4\FrameCap\` + +(Showing Windows paths for convenience, but the desinations are similar for Linux/Mac) With these flags enabled, any time you initiate a replay such as: ```bash diff --git a/LibCarla/SensorRegistry.h b/LibCarla/SensorRegistry.h deleted file mode 100644 index 0a9b003..0000000 --- a/LibCarla/SensorRegistry.h +++ /dev/null @@ -1,106 +0,0 @@ -// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#ifndef LIBCARLA_SENSOR_REGISTRY_INCLUDE_H -#define LIBCARLA_SENSOR_REGISTRY_INCLUDE_H - -#include "carla/sensor/CompositeSerializer.h" - -// ============================================================================= -// Follow the 4 steps to register a new sensor. -// ============================================================================= - -// 1. Include the serializer here. -#include "carla/sensor/s11n/CollisionEventSerializer.h" -#include "carla/sensor/s11n/DVSEventArraySerializer.h" -#include "carla/sensor/s11n/EpisodeStateSerializer.h" -#include "carla/sensor/s11n/GnssSerializer.h" -#include "carla/sensor/s11n/ImageSerializer.h" -#include "carla/sensor/s11n/OpticalFlowImageSerializer.h" -#include "carla/sensor/s11n/IMUSerializer.h" -#include "carla/sensor/s11n/LidarSerializer.h" -#include "carla/sensor/s11n/NoopSerializer.h" -#include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h" -#include "carla/sensor/s11n/RadarSerializer.h" -#include "carla/sensor/s11n/SemanticLidarSerializer.h" -#include "carla/sensor/s11n/DReyeVRSerializer.h" // DReyeVR serializer header - -// 2. Add a forward-declaration of the sensor here. -class ACollisionSensor; -class ADepthCamera; -class ADVSCamera; -class AGnssSensor; -class AInertialMeasurementUnit; -class ALaneInvasionSensor; -class AObstacleDetectionSensor; -class AOpticalFlowCamera; -class ARadar; -class ARayCastSemanticLidar; -class ARayCastLidar; -class ASceneCaptureCamera; -class ASemanticSegmentationCamera; -class AInstanceSegmentationCamera; -class ARssSensor; -class FWorldObserver; -class ADReyeVRSensor; // DReyeVR forward declaration - -namespace carla { -namespace sensor { - - // 3. Register the sensor and its serializer in the SensorRegistry. - - /// Contains a registry of all the sensors available and allows serializing - /// and deserializing sensor data for the types registered. - /// - /// Use s11n::NoopSerializer if the sensor does not send data (sensors that - /// work only on client-side). - using SensorRegistry = CompositeSerializer< - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair, - std::pair - >; - -} // namespace sensor -} // namespace carla - -#endif // LIBCARLA_SENSOR_REGISTRY_INCLUDE_H - -#ifdef LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES - -// 4. Include the sensor here. -#include "Carla/Sensor/CollisionSensor.h" -#include "Carla/Sensor/DepthCamera.h" -#include "Carla/Sensor/DVSCamera.h" -#include "Carla/Sensor/GnssSensor.h" -#include "Carla/Sensor/InertialMeasurementUnit.h" -#include "Carla/Sensor/LaneInvasionSensor.h" -#include "Carla/Sensor/ObstacleDetectionSensor.h" -#include "Carla/Sensor/OpticalFlowCamera.h" -#include "Carla/Sensor/Radar.h" -#include "Carla/Sensor/RayCastLidar.h" -#include "Carla/Sensor/RayCastSemanticLidar.h" -#include "Carla/Sensor/RssSensor.h" -#include "Carla/Sensor/SceneCaptureCamera.h" -#include "Carla/Sensor/SemanticSegmentationCamera.h" -#include "Carla/Sensor/InstanceSegmentationCamera.h" -#include "Carla/Sensor/WorldObserver.h" -#include "Carla/Sensor/DReyeVRSensor.h" // DReyeVRSensor header file - -#endif // LIBCARLA_SENSOR_REGISTRY_WITH_SENSOR_INCLUDES diff --git a/LibCarla/Client/Vehicle.cpp b/LibCarla/source/carla/client/Vehicle.cpp similarity index 100% rename from LibCarla/Client/Vehicle.cpp rename to LibCarla/source/carla/client/Vehicle.cpp diff --git a/LibCarla/source/carla/client/detail/ActorFactory.cpp b/LibCarla/source/carla/client/detail/ActorFactory.cpp new file mode 100644 index 0000000..f875c13 --- /dev/null +++ b/LibCarla/source/carla/client/detail/ActorFactory.cpp @@ -0,0 +1,106 @@ +// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/client/detail/ActorFactory.h" + +#include "carla/Logging.h" +#include "carla/StringUtil.h" +#include "carla/client/Actor.h" +#include "carla/client/LaneInvasionSensor.h" +#include "carla/client/ServerSideSensor.h" +#ifdef RSS_ENABLED +#include "carla/rss/RssSensor.h" +#endif +#include "carla/client/TrafficLight.h" +#include "carla/client/TrafficSign.h" +#include "carla/client/Vehicle.h" +#include "carla/client/Walker.h" +#include "carla/client/WalkerAIController.h" +#include "carla/client/World.h" +#include "carla/client/detail/Client.h" + +#include +#include + +#include + +namespace carla { +namespace client { +namespace detail { + + // A deleter cannot throw exceptions; and unlike std::unique_ptr, the deleter + // of (std|boost)::shared_ptr is invoked even if the managed pointer is null. + struct GarbageCollector { + void operator()(::carla::client::Actor *ptr) const noexcept { + if ((ptr != nullptr) && ptr->IsAlive()) { + try { + ptr->Destroy(); + delete ptr; + } catch (const ::rpc::timeout &timeout) { + log_error(timeout.what()); + log_error( + "timeout while trying to garbage collect Actor", + ptr->GetDisplayId(), + "actor hasn't been removed from the simulation"); + } catch (const std::exception &e) { + log_critical( + "exception thrown while trying to garbage collect Actor", + ptr->GetDisplayId(), + e.what()); + std::terminate(); + } catch (...) { + log_critical( + "unknown exception thrown while trying to garbage collect an Actor :", + ptr->GetDisplayId()); + std::terminate(); + } + } + } + }; + + template + static auto MakeActorImpl(ActorInitializer init, GarbageCollectionPolicy gc) { + if (gc == GarbageCollectionPolicy::Enabled) { + return SharedPtr{new ActorT(std::move(init)), GarbageCollector()}; + } + DEBUG_ASSERT(gc == GarbageCollectionPolicy::Disabled); + return SharedPtr{new ActorT(std::move(init))}; + } + + SharedPtr ActorFactory::MakeActor( + EpisodeProxy episode, + rpc::Actor description, + GarbageCollectionPolicy gc) { + auto init = ActorInitializer{description, episode}; + if (description.description.id == "sensor.other.lane_invasion") { + return MakeActorImpl(std::move(init), gc); +#ifdef RSS_ENABLED + } else if (description.description.id == "sensor.other.rss") { + return MakeActorImpl(std::move(init), gc); +#endif + } else if (description.HasAStream()) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "vehicle.")) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "harplab.dreyevr_vehicle.")) { + return MakeActorImpl(std::move(init), gc); // for DReyeVR vehicles! + } else if (StringUtil::StartsWith(description.description.id, "harplab.dreyevr_sensor.")) { + return MakeActorImpl(std::move(init), gc); // for DReyeVR sensors! + } else if (StringUtil::StartsWith(description.description.id, "walker.")) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "traffic.traffic_light")) { + return MakeActorImpl(std::move(init), gc); + } else if (StringUtil::StartsWith(description.description.id, "traffic.")) { + return MakeActorImpl(std::move(init), gc); + } else if (description.description.id == "controller.ai.walker") { + return MakeActorImpl(std::move(init), gc); + } + return MakeActorImpl(std::move(init), gc); + } + +} // namespace detail +} // namespace client +} // namespace carla diff --git a/LibCarla/Sensor/SensorRegistry.h b/LibCarla/source/carla/sensor/SensorRegistry.h similarity index 100% rename from LibCarla/Sensor/SensorRegistry.h rename to LibCarla/source/carla/sensor/SensorRegistry.h diff --git a/LibCarla/Sensor/data/DReyeVREvent.h b/LibCarla/source/carla/sensor/data/DReyeVREvent.h similarity index 100% rename from LibCarla/Sensor/data/DReyeVREvent.h rename to LibCarla/source/carla/sensor/data/DReyeVREvent.h diff --git a/LibCarla/Sensor/s11n/DReyeVRSerializer.cpp b/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.cpp similarity index 100% rename from LibCarla/Sensor/s11n/DReyeVRSerializer.cpp rename to LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.cpp diff --git a/LibCarla/Sensor/s11n/DReyeVRSerializer.h b/LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h similarity index 100% rename from LibCarla/Sensor/s11n/DReyeVRSerializer.h rename to LibCarla/source/carla/sensor/s11n/DReyeVRSerializer.h diff --git a/Tools/BuildTools/test_streaming.cpp b/LibCarla/source/test/common/test_streaming.cpp similarity index 100% rename from Tools/BuildTools/test_streaming.cpp rename to LibCarla/source/test/common/test_streaming.cpp diff --git a/Makefile b/Makefile index 8b09301..433fe20 100644 --- a/Makefile +++ b/Makefile @@ -17,12 +17,9 @@ test: check: # TODO: make better DReyeVR unit tests! python Scripts/check_install.py --carla ${CARLA} --scenario-runner ${SR} --verbose -patch-sranipal: - python Scripts/patch_sranipal.py --carla ${CARLA} - rev: r-install r-install: python Scripts/r-install.py --carla ${CARLA} --scenario-runner ${SR} -all: install patch-sranipal check \ No newline at end of file +all: install check \ No newline at end of file diff --git a/Maps/Town01.umap b/Maps/Town01.umap deleted file mode 100644 index cad1b98..0000000 Binary files a/Maps/Town01.umap and /dev/null differ diff --git a/Maps/Town02.umap b/Maps/Town02.umap deleted file mode 100644 index 6b084f7..0000000 Binary files a/Maps/Town02.umap and /dev/null differ diff --git a/Maps/Town03.umap b/Maps/Town03.umap deleted file mode 100644 index 396d0e1..0000000 Binary files a/Maps/Town03.umap and /dev/null differ diff --git a/Maps/Town04.umap b/Maps/Town04.umap deleted file mode 100644 index 34da03f..0000000 Binary files a/Maps/Town04.umap and /dev/null differ diff --git a/Maps/Town05.umap b/Maps/Town05.umap deleted file mode 100644 index 6d0c879..0000000 Binary files a/Maps/Town05.umap and /dev/null differ diff --git a/Maps/Town06.umap b/Maps/Town06.umap deleted file mode 100644 index 8c17392..0000000 Binary files a/Maps/Town06.umap and /dev/null differ diff --git a/Maps/Town07.umap b/Maps/Town07.umap deleted file mode 100644 index 7d2096b..0000000 Binary files a/Maps/Town07.umap and /dev/null differ diff --git a/Maps/Town10HD.umap b/Maps/Town10HD.umap deleted file mode 100644 index ee4cde1..0000000 Binary files a/Maps/Town10HD.umap and /dev/null differ diff --git a/LibCarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp similarity index 100% rename from LibCarla/SensorData.cpp rename to PythonAPI/carla/source/libcarla/SensorData.cpp diff --git a/PythonAPI/DReyeVR_AI.py b/PythonAPI/examples/DReyeVR_AI.py similarity index 97% rename from PythonAPI/DReyeVR_AI.py rename to PythonAPI/examples/DReyeVR_AI.py index d8205ac..8bd7da6 100755 --- a/PythonAPI/DReyeVR_AI.py +++ b/PythonAPI/examples/DReyeVR_AI.py @@ -119,6 +119,7 @@ def main(): random.seed(args.seed if args.seed is not None else int(time.time())) other_vehicles = [] + ego_vehicle = None try: world = client.get_world() @@ -137,7 +138,8 @@ def main(): while True: world.wait_for_tick() finally: - ego_vehicle.set_autopilot(False, traffic_manager.get_port()) + if ego_vehicle is not None: + ego_vehicle.set_autopilot(False, traffic_manager.get_port()) print("\ndestroying %d vehicles" % len(other_vehicles)) client.apply_batch([carla.command.DestroyActor(x) for x in other_vehicles]) @@ -152,4 +154,3 @@ def main(): pass finally: print("\ndone.") - diff --git a/PythonAPI/DReyeVR_logging.py b/PythonAPI/examples/DReyeVR_logging.py similarity index 100% rename from PythonAPI/DReyeVR_logging.py rename to PythonAPI/examples/DReyeVR_logging.py diff --git a/PythonAPI/DReyeVR_utils.py b/PythonAPI/examples/DReyeVR_utils.py similarity index 85% rename from PythonAPI/DReyeVR_utils.py rename to PythonAPI/examples/DReyeVR_utils.py index 3421700..cb8198c 100644 --- a/PythonAPI/DReyeVR_utils.py +++ b/PythonAPI/examples/DReyeVR_utils.py @@ -24,21 +24,27 @@ def find_ego_vehicle(world: carla.libcarla.World) -> Optional[carla.libcarla.Vehicle]: DReyeVR_vehicle = None - ego_vehicles = world.get_actors().filter("vehicle.dreyevr.egovehicle") - try: + ego_vehicles = list(world.get_actors().filter("harplab.dreyevr_vehicle.*")) + if len(ego_vehicles) >= 1: DReyeVR_vehicle = ego_vehicles[0] # TODO: support for multiple ego vehicles? - except IndexError: - print("Unable to find DReyeVR ego vehicle in world!") + else: + model: str = "harplab.dreyevr_vehicle.model3" + print(f'No EgoVehicle found, spawning one: "{model}"') + bp = world.get_blueprint_library().find(model) + transform = world.get_map().get_spawn_points()[0] + DReyeVR_vehicle = world.spawn_actor(bp, transform) return DReyeVR_vehicle def find_ego_sensor(world: carla.libcarla.World) -> Optional[carla.libcarla.Sensor]: sensor = None - ego_sensors = world.get_actors().filter("sensor.dreyevr.dreyevrsensor") - try: - sensor = ego_sensors[0] # TODO: support for multiple eye trackers? - except IndexError: - print("Unable to find DReyeVR ego sensor in world!") + ego_sensors = list(world.get_actors().filter("harplab.dreyevr_sensor.*")) + if len(ego_sensors) >= 1: + sensor = ego_sensors[0] # TODO: support for multiple ego sensors? + elif find_ego_vehicle(world) is None: + raise Exception( + "No EgoVehicle (nor EgoSensor) found in the world! EgoSensor needs EgoVehicle as parent" + ) return sensor diff --git a/PythonAPI/schematic_mode.py b/PythonAPI/examples/schematic_mode.py similarity index 100% rename from PythonAPI/schematic_mode.py rename to PythonAPI/examples/schematic_mode.py diff --git a/PythonAPI/start_recording.py b/PythonAPI/examples/start_recording.py similarity index 100% rename from PythonAPI/start_recording.py rename to PythonAPI/examples/start_recording.py diff --git a/PythonAPI/libcarla/SensorData.cpp b/PythonAPI/libcarla/SensorData.cpp deleted file mode 100644 index 2383247..0000000 --- a/PythonAPI/libcarla/SensorData.cpp +++ /dev/null @@ -1,619 +0,0 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma -// de Barcelona (UAB). -// -// This work is licensed under the terms of the MIT license. -// For a copy, see . - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include // DReyeVR sensor event - -#include - -#include - -#include -#include -#include -#include -#include -#include - -namespace carla { -namespace sensor { -namespace data { - - std::ostream &operator<<(std::ostream &out, const Image &image) { - out << "Image(frame=" << std::to_string(image.GetFrame()) - << ", timestamp=" << std::to_string(image.GetTimestamp()) - << ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const OpticalFlowImage &image) { - out << "OpticalFlowImage(frame=" << std::to_string(image.GetFrame()) - << ", timestamp=" << std::to_string(image.GetTimestamp()) - << ", size=" << std::to_string(image.GetWidth()) << 'x' << std::to_string(image.GetHeight()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) { - out << "LidarMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", number_of_points=" << std::to_string(meas.size()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const SemanticLidarMeasurement &meas) { - out << "SemanticLidarMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", number_of_points=" << std::to_string(meas.size()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) { - out << "CollisionEvent(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", other_actor=" << meas.GetOtherActor() - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) { - out << "ObstacleDetectionEvent(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", other_actor=" << meas.GetOtherActor() - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) { - out << "LaneInvasionEvent(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const GnssMeasurement &meas) { - out << "GnssMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", lat=" << std::to_string(meas.GetLatitude()) - << ", lon=" << std::to_string(meas.GetLongitude()) - << ", alt=" << std::to_string(meas.GetAltitude()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const IMUMeasurement &meas) { - out << "IMUMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", accelerometer=" << meas.GetAccelerometer() - << ", gyroscope=" << meas.GetGyroscope() - << ", compass=" << std::to_string(meas.GetCompass()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const RadarMeasurement &meas) { - out << "RadarMeasurement(frame=" << std::to_string(meas.GetFrame()) - << ", timestamp=" << std::to_string(meas.GetTimestamp()) - << ", point_count=" << std::to_string(meas.GetDetectionAmount()) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const DVSEvent &event) { - out << "Event(x=" << std::to_string(event.x) - << ", y=" << std::to_string(event.y) - << ", t=" << std::to_string(event.t) - << ", pol=" << std::to_string(event.pol) << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const DVSEventArray &events) { - out << "EventArray(frame=" << std::to_string(events.GetFrame()) - << ", timestamp=" << std::to_string(events.GetTimestamp()) - << ", dimensions=" << std::to_string(events.GetWidth()) << 'x' << std::to_string(events.GetHeight()) - << ", number_of_events=" << std::to_string(events.size()) - << ')'; - return out; - } - - - std::ostream &operator<<(std::ostream &out, const RadarDetection &det) { - out << "RadarDetection(velocity=" << std::to_string(det.velocity) - << ", azimuth=" << std::to_string(det.azimuth) - << ", altitude=" << std::to_string(det.altitude) - << ", depth=" << std::to_string(det.depth) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const LidarDetection &det) { - out << "LidarDetection(x=" << std::to_string(det.point.x) - << ", y=" << std::to_string(det.point.y) - << ", z=" << std::to_string(det.point.z) - << ", intensity=" << std::to_string(det.intensity) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const SemanticLidarDetection &det) { - out << "SemanticLidarDetection(x=" << std::to_string(det.point.x) - << ", y=" << std::to_string(det.point.y) - << ", z=" << std::to_string(det.point.z) - << ", cos_inc_angle=" << std::to_string(det.cos_inc_angle) - << ", object_idx=" << std::to_string(det.object_idx) - << ", object_tag=" << std::to_string(det.object_tag) - << ')'; - return out; - } - - std::ostream &operator<<(std::ostream &out, const DReyeVREvent &event) { - // what is used when printing the data streamed to the PythonAPI (converting to string) - auto &GazeDir = event.GetGazeDir(); - auto &GazeOrigin = event.GetGazeOrigin(); - auto &CameraLocn = event.GetCameraLocation(); - auto &CameraRotn = event.GetCameraRotation(); - const std::string sep = ", "; - out << "DReyeVR(frame=" << event.GetFrame() << sep - << "t=" << event.GetTimestamp() << sep - << "GazeDir(" << event.GetGazeValid() << ")={" << GazeDir.x << ", " << GazeDir.y << ", " << GazeDir.z<< "}" << sep - << "GazeOrigin={" << GazeOrigin.x << ", " << GazeOrigin.y << ", " << GazeOrigin.z << "}" << sep - << "Vergence=" << event.GetGazeVergence() << sep - << "CameraLoc={" << CameraLocn.x << ", " << CameraLocn.y << ", " << CameraLocn.z<< "}" << sep - << "CameraRot={" << CameraRotn.x << ", " << CameraRotn.y << ", " << CameraRotn.z<< "}" << sep - << ')'; - return out; - } -} // namespace s11n -} // namespace sensor -} // namespace carla - -enum class EColorConverter { - Raw, - Depth, - LogarithmicDepth, - CityScapesPalette -}; - -template -static auto GetRawDataAsBuffer(T &self) { - auto *data = reinterpret_cast(self.data()); - auto size = static_cast(sizeof(typename T::value_type) * self.size()); -#if PY_MAJOR_VERSION >= 3 - auto *ptr = PyMemoryView_FromMemory(reinterpret_cast(data), size, PyBUF_READ); -#else - auto *ptr = PyBuffer_FromMemory(data, size); -#endif - return boost::python::object(boost::python::handle<>(ptr)); -} - -template -static void ConvertImage(T &self, EColorConverter cc) { - carla::PythonUtil::ReleaseGIL unlock; - using namespace carla::image; - auto view = ImageView::MakeView(self); - switch (cc) { - case EColorConverter::Depth: - ImageConverter::ConvertInPlace(view, ColorConverter::Depth()); - break; - case EColorConverter::LogarithmicDepth: - ImageConverter::ConvertInPlace(view, ColorConverter::LogarithmicDepth()); - break; - case EColorConverter::CityScapesPalette: - ImageConverter::ConvertInPlace(view, ColorConverter::CityScapesPalette()); - break; - case EColorConverter::Raw: - break; // ignore. - default: - throw std::invalid_argument("invalid color converter!"); - } -} - -// image object resturned from optical flow to color conversion -class FakeImage : public std::vector { - public: - unsigned int Width = 0; - unsigned int Height = 0; - float FOV = 0; -}; -// method to convert optical flow images to rgb -static FakeImage ColorCodedFlow ( - carla::sensor::data::OpticalFlowImage& image) { - namespace bp = boost::python; - namespace csd = carla::sensor::data; - constexpr float pi = 3.1415f; - constexpr float rad2ang = 360.f/(2.f*pi); - FakeImage result; - result.Width = image.GetWidth(); - result.Height = image.GetHeight(); - result.FOV = image.GetFOVAngle(); - result.resize(image.GetHeight()*image.GetWidth()* 4); - - // lambda for computing batches of pixels - auto command = [&] (size_t min_index, size_t max_index) { - for (size_t index = min_index; index < max_index; index++) { - const csd::OpticalFlowPixel& pixel = image[index]; - float vx = pixel.x; - float vy = pixel.y; - - float angle = 180.f + std::atan2(vy, vx)*rad2ang; - if (angle < 0) angle = 360.f + angle; - angle = std::fmod(angle, 360.f); - - float norm = std::sqrt(vx*vx + vy*vy); - const float shift = 0.999f; - const float a = 1.f/std::log(0.1f + shift); - float intensity = carla::geom::Math::Clamp(a*std::log(norm + shift), 0.f, 1.f); - - float& H = angle; - float S = 1.f; - float V = intensity; - float H_60 = H*(1.f/60.f); - - float C = V * S; - float X = C*(1.f - std::abs(std::fmod(H_60, 2.f) - 1.f)); - float m = V - C; - - float r = 0,g = 0,b = 0; - unsigned int angle_case = static_cast(H_60); - switch (angle_case) { - case 0: - r = C; - g = X; - b = 0; - break; - case 1: - r = X; - g = C; - b = 0; - break; - case 2: - r = 0; - g = C; - b = X; - break; - case 3: - r = 0; - g = X; - b = C; - break; - case 4: - r = X; - g = 0; - b = C; - break; - case 5: - r = C; - g = 0; - b = X; - break; - default: - r = 1; - g = 1; - b = 1; - break; - } - - uint8_t R = static_cast((r+m)*255.f); - uint8_t G = static_cast((g+m)*255.f); - uint8_t B = static_cast((b+m)*255.f); - result[4*index] = B; - result[4*index + 1] = G; - result[4*index + 2] = R; - result[4*index + 3] = 0; - } - }; - size_t num_threads = std::max(8u, std::thread::hardware_concurrency()); - size_t batch_size = image.size() / num_threads; - std::vector t(num_threads+1); - - for(size_t n = 0; n < num_threads; n++) { - t[n] = new std::thread(command, n * batch_size, (n+1) * batch_size); - } - t[num_threads] = new std::thread(command, num_threads * batch_size, image.size()); - - for(size_t n = 0; n <= num_threads; n++) { - if(t[n]->joinable()){ - t[n]->join(); - } - delete t[n]; - } - return result; -} - -template -static std::string SaveImageToDisk(T &self, std::string path, EColorConverter cc) { - carla::PythonUtil::ReleaseGIL unlock; - using namespace carla::image; - auto view = ImageView::MakeView(self); - switch (cc) { - case EColorConverter::Raw: - return ImageIO::WriteView( - std::move(path), - view); - case EColorConverter::Depth: - return ImageIO::WriteView( - std::move(path), - ImageView::MakeColorConvertedView(view, ColorConverter::Depth())); - case EColorConverter::LogarithmicDepth: - return ImageIO::WriteView( - std::move(path), - ImageView::MakeColorConvertedView(view, ColorConverter::LogarithmicDepth())); - case EColorConverter::CityScapesPalette: - return ImageIO::WriteView( - std::move(path), - ImageView::MakeColorConvertedView(view, ColorConverter::CityScapesPalette())); - default: - throw std::invalid_argument("invalid color converter!"); - } -} - -template -static std::string SavePointCloudToDisk(T &self, std::string path) { - carla::PythonUtil::ReleaseGIL unlock; - return carla::pointcloud::PointCloudIO::SaveToDisk(std::move(path), self.begin(), self.end()); -} - -void export_sensor_data() { - using namespace boost::python; - namespace cc = carla::client; - namespace cr = carla::rpc; - namespace cs = carla::sensor; - namespace csd = carla::sensor::data; - namespace css = carla::sensor::s11n; - - // Fake image returned from optical flow to color conversion - // fakes the regular image object. Only used for visual purposes - class_("FakeImage", no_init) - .def(vector_indexing_suite>()) - .add_property("width", &FakeImage::Width) - .add_property("height", &FakeImage::Height) - .add_property("fov", &FakeImage::FOV) - .add_property("raw_data", &GetRawDataAsBuffer); - - class_>("SensorData", no_init) - .add_property("frame", &cs::SensorData::GetFrame) - .add_property("frame_number", &cs::SensorData::GetFrame) // deprecated. - .add_property("timestamp", &cs::SensorData::GetTimestamp) - .add_property("transform", CALL_RETURNING_COPY(cs::SensorData, GetSensorTransform)) - ; - - enum_("ColorConverter") - .value("Raw", EColorConverter::Raw) - .value("Depth", EColorConverter::Depth) - .value("LogarithmicDepth", EColorConverter::LogarithmicDepth) - .value("CityScapesPalette", EColorConverter::CityScapesPalette) - ; - - class_, boost::noncopyable, boost::shared_ptr>("Image", no_init) - .add_property("width", &csd::Image::GetWidth) - .add_property("height", &csd::Image::GetHeight) - .add_property("fov", &csd::Image::GetFOVAngle) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("convert", &ConvertImage, (arg("color_converter"))) - .def("save_to_disk", &SaveImageToDisk, (arg("path"), arg("color_converter")=EColorConverter::Raw)) - .def("__len__", &csd::Image::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::Image &self, size_t pos) -> csd::Color { - return self.at(pos); - }) - .def("__setitem__", +[](csd::Image &self, size_t pos, csd::Color color) { - self.at(pos) = color; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("OpticalFlowImage", no_init) - .add_property("width", &csd::OpticalFlowImage::GetWidth) - .add_property("height", &csd::OpticalFlowImage::GetHeight) - .add_property("fov", &csd::OpticalFlowImage::GetFOVAngle) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_color_coded_flow", &ColorCodedFlow) - .def("__len__", &csd::OpticalFlowImage::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::OpticalFlowImage &self, size_t pos) -> csd::OpticalFlowPixel { - return self.at(pos); - }) - .def("__setitem__", +[](csd::OpticalFlowImage &self, size_t pos, csd::OpticalFlowPixel color) { - self.at(pos) = color; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("LidarMeasurement", no_init) - .add_property("horizontal_angle", &csd::LidarMeasurement::GetHorizontalAngle) - .add_property("channels", &csd::LidarMeasurement::GetChannelCount) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_point_count", &csd::LidarMeasurement::GetPointCount, (arg("channel"))) - .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) - .def("__len__", &csd::LidarMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::LidarMeasurement &self, size_t pos) -> csd::LidarDetection { - return self.at(pos); - }) - .def("__setitem__", +[](csd::LidarMeasurement &self, size_t pos, const csd::LidarDetection &detection) { - self.at(pos) = detection; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("SemanticLidarMeasurement", no_init) - .add_property("horizontal_angle", &csd::SemanticLidarMeasurement::GetHorizontalAngle) - .add_property("channels", &csd::SemanticLidarMeasurement::GetChannelCount) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_point_count", &csd::SemanticLidarMeasurement::GetPointCount, (arg("channel"))) - .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) - .def("__len__", &csd::SemanticLidarMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::SemanticLidarMeasurement &self, size_t pos) -> csd::SemanticLidarDetection { - return self.at(pos); - }) - .def("__setitem__", +[](csd::SemanticLidarMeasurement &self, size_t pos, const csd::SemanticLidarDetection &detection) { - self.at(pos) = detection; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("CollisionEvent", no_init) - .add_property("actor", &csd::CollisionEvent::GetActor) - .add_property("other_actor", &csd::CollisionEvent::GetOtherActor) - .add_property("normal_impulse", CALL_RETURNING_COPY(csd::CollisionEvent, GetNormalImpulse)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("ObstacleDetectionEvent", no_init) - .add_property("actor", &csd::ObstacleDetectionEvent::GetActor) - .add_property("other_actor", &csd::ObstacleDetectionEvent::GetOtherActor) - .add_property("distance", CALL_RETURNING_COPY(csd::ObstacleDetectionEvent, GetDistance)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("LaneInvasionEvent", no_init) - .add_property("actor", &csd::LaneInvasionEvent::GetActor) - .add_property("crossed_lane_markings", CALL_RETURNING_LIST(csd::LaneInvasionEvent, GetCrossedLaneMarkings)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("GnssMeasurement", no_init) - .add_property("latitude", &csd::GnssMeasurement::GetLatitude) - .add_property("longitude", &csd::GnssMeasurement::GetLongitude) - .add_property("altitude", &csd::GnssMeasurement::GetAltitude) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("IMUMeasurement", no_init) - .add_property("accelerometer", &csd::IMUMeasurement::GetAccelerometer) - .add_property("gyroscope", &csd::IMUMeasurement::GetGyroscope) - .add_property("compass", &csd::IMUMeasurement::GetCompass) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("RadarMeasurement", no_init) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_detection_count", &csd::RadarMeasurement::GetDetectionAmount) - .def("__len__", &csd::RadarMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::RadarMeasurement &self, size_t pos) -> csd::RadarDetection { - return self.at(pos); - }) - .def("__setitem__", +[](csd::RadarMeasurement &self, size_t pos, const csd::RadarDetection &detection) { - self.at(pos) = detection; - }) - .def(self_ns::str(self_ns::self)) - ; - - class_("RadarDetection") - .def_readwrite("velocity", &csd::RadarDetection::velocity) - .def_readwrite("azimuth", &csd::RadarDetection::azimuth) - .def_readwrite("altitude", &csd::RadarDetection::altitude) - .def_readwrite("depth", &csd::RadarDetection::depth) - .def(self_ns::str(self_ns::self)) - ; - - class_("LidarDetection") - .def_readwrite("point", &csd::LidarDetection::point) - .def_readwrite("intensity", &csd::LidarDetection::intensity) - .def(self_ns::str(self_ns::self)) - ; - - class_("SemanticLidarDetection") - .def_readwrite("point", &csd::SemanticLidarDetection::point) - .def_readwrite("cos_inc_angle", &csd::SemanticLidarDetection::cos_inc_angle) - .def_readwrite("object_idx", &csd::SemanticLidarDetection::object_idx) - .def_readwrite("object_tag", &csd::SemanticLidarDetection::object_tag) - .def(self_ns::str(self_ns::self)) - ; - - class_("DVSEvent") - .add_property("x", &csd::DVSEvent::x) - .add_property("y", &csd::DVSEvent::y) - .add_property("t", &csd::DVSEvent::t) - .add_property("pol", &csd::DVSEvent::pol) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("DVSEventArray", no_init) - .add_property("width", &csd::DVSEventArray::GetWidth) - .add_property("height", &csd::DVSEventArray::GetHeight) - .add_property("fov", &csd::DVSEventArray::GetFOVAngle) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("__len__", &csd::DVSEventArray::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::DVSEventArray &self, size_t pos) -> csd::DVSEvent { - return self.at(pos); - }) - .def("__setitem__", +[](csd::DVSEventArray &self, size_t pos, csd::DVSEvent event) { - self.at(pos) = event; - }) - .def("to_image", CALL_RETURNING_LIST(csd::DVSEventArray, ToImage)) - .def("to_array", CALL_RETURNING_LIST(csd::DVSEventArray, ToArray)) - .def("to_array_x", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayX)) - .def("to_array_y", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayY)) - .def("to_array_t", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayT)) - .def("to_array_pol", CALL_RETURNING_LIST(csd::DVSEventArray, ToArrayPol)) - .def(self_ns::str(self_ns::self)) - ; - - class_, boost::noncopyable, boost::shared_ptr>("DReyeVREvent", no_init) - .add_property("timestamp_carla", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestampCarla)) - .add_property("timestamp_device", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestampDevice)) - .add_property("framesequence", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFrameSequence)) - .add_property("timestamp_stream", CALL_RETURNING_COPY(csd::DReyeVREvent, GetTimestamp)) // Stream timestamp - .add_property("camera_location", CALL_RETURNING_COPY(csd::DReyeVREvent, GetCameraLocation)) - .add_property("camera_rotation", CALL_RETURNING_COPY(csd::DReyeVREvent, GetCameraRotation)) - // combined gaze attributes - .add_property("gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeDir)) - .add_property("gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeOrigin)) - .add_property("gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeValid)) - .add_property("gaze_vergence", CALL_RETURNING_COPY(csd::DReyeVREvent, GetGazeVergence)) - // left gaze attributes - .add_property("left_gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeDir)) - .add_property("left_gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeOrigin)) - .add_property("left_gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLGazeValid)) - .add_property("left_eye_openness", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLEyeOpenness)) - .add_property("left_eye_openness_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLEyeOpenValid)) - .add_property("left_pupil_posn", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilPos)) - .add_property("left_pupil_posn_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilPosValid)) - .add_property("left_pupil_diam", CALL_RETURNING_COPY(csd::DReyeVREvent, GetLPupilDiam)) - // right gaze attributes - .add_property("right_gaze_dir", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeDir)) - .add_property("right_gaze_origin", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeOrigin)) - .add_property("right_gaze_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRGazeValid)) - .add_property("right_eye_openness", CALL_RETURNING_COPY(csd::DReyeVREvent, GetREyeOpenness)) - .add_property("right_eye_openness_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetREyeOpenValid)) - .add_property("right_pupil_posn", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilPos)) - .add_property("right_pupil_posn_valid", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilPosValid)) - .add_property("right_pupil_diam", CALL_RETURNING_COPY(csd::DReyeVREvent, GetRPupilDiam)) - // focus info attributes - .add_property("focus_actor_name", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorName)) - .add_property("focus_actor_pt", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorPoint)) - .add_property("focus_actor_dist", CALL_RETURNING_COPY(csd::DReyeVREvent, GetFocusActorDist)) - // user inputs attributes - .add_property("throttle_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetThrottle)) - .add_property("steering_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetSteering)) - .add_property("brake_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetBrake)) - .add_property("current_gear_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetToggledReverse)) - .add_property("handbrake_input", CALL_RETURNING_COPY(csd::DReyeVREvent, GetHandbrake)) - .def(self_ns::str(self_ns::self)) - ; -} diff --git a/README.md b/README.md index f4d9cf7..9699c3a 100644 --- a/README.md +++ b/README.md @@ -6,11 +6,12 @@ [Submission Video Demonstration (YouTube)](https://www.youtube.com/watch?v=yGIPSDOMGpY) -This project extends the [`Carla`](https://github.com/carla-simulator/carla/tree/0.9.13) build that adds virtual reality integration, a first-person maneuverable ego-vehicle, eye tracking support, and several immersion enhancements. - +This project extends the [`Carla`](https://github.com/carla-simulator/carla/tree/0.9.13) simulator to add virtual reality integration, a first-person maneuverable ego-vehicle, eye tracking support, and several immersion enhancements. If you have questions, hopefully our [F.A.Q. wiki page](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) can answer some of them. +**IMPORTANT:** Currently DReyeVR only supports Carla versions: [0.9.13](https://github.com/carla-simulator/carla/tree/0.9.13) + ## Highlights ### Ego Vehicle Fully drivable **virtual reality (VR) ego-vehicle** with [SteamVR integration](https://github.com/ValveSoftware/steamvr_unreal_plugin/tree/4.23) (see [EgoVehicle.h](DReyeVR/EgoVehicle.h)) @@ -18,7 +19,7 @@ Fully drivable **virtual reality (VR) ego-vehicle** with [SteamVR integration](h - We have tested with the following devices: | Device | VR Supported | Eye tracking | OS | | --- | --- | --- | --- | - | [HTC Vive Pro Eye](https://business.vive.com/us/product/vive-pro-eye-office/) | :heavy_check_mark: | :heavy_check_mark: ([SRanipal](https://developer-express.vive.com/resources/vive-sense/eye-and-facial-tracking-sdk/) >=1.3.1.1) | Windows, Linux | + | [HTC Vive Pro Eye](https://business.vive.com/us/product/vive-pro-eye-office/) | :heavy_check_mark: | :heavy_check_mark: | Windows, Linux | | [Oculus/Meta Quest 2](https://www.oculus.com/quest-2/) | :heavy_check_mark: | :x: | Windows | - Vehicle controls - Generic keyboard WASD + mouse @@ -75,16 +76,18 @@ Carla-compatible **ego-vehicle sensor** (see [EgoSensor.h](DReyeVR/EgoSensor.h)) - Static in-environment directional signs for natural navigation (See [`Docs/Signs.md`](Docs/Signs.md)) - Adding weather to the Carla recorder/replayer/query (See this [Carla PR](https://github.com/carla-simulator/carla/pull/5235)) - Custom dynamic 3D actors with full recording support (eg. HUD indicators for direction, AR bounding boxes, visual targets, etc.). See [CustomActor.md](Docs/CustomActor.md) for more. -- Empty room for "blank slate" eye tracking experiments without cognitive overhead of driving - (DEBUG ONLY) Foveated rendering for improved performance with gaze-aware (or fixed) variable rate shading -## Install -See [`Docs/Install.md`](Docs/Install.md) to either: -- Install and build `DReyeVR` on top of a working Carla (0.9.13) build. -- Use our [Carla fork](https://github.com/HARPLab/carla/tree/DReyeVR-0.9.13) with `DReyeVR` pre-installed. +## Install/Build +See [`Docs/Install.md`](Docs/Install.md) to: +- Install and build `DReyeVR` on top of a working `Carla` repository. +- Download plugins for `DReyeVR` required for fancy features such as: + - Eye tracking (SRanipal) + - Steering wheel/pedals (Logitech) +- Set up a `conda` environment for DReyeVR PythonAPI ## OS compatibility -| OS | VR | Eye tracking | Audio | Keyboard+Mouse | Racing wheel | Foveated Rendering (WIP) | +| OS | VR | Eye tracking | Audio | Keyboard+Mouse | Racing wheel | Foveated Rendering (Editor) | | --- | --- | --- | --- | --- | --- | --- | | Windows | :heavy_check_mark: | :heavy_check_mark: | :heavy_check_mark: | :heavy_check_mark: | :heavy_check_mark: | :heavy_check_mark: | | Linux | :heavy_check_mark: | :x: | :heavy_check_mark: | :heavy_check_mark: | :x: | :x: | diff --git a/Scripts/DReyeVR.mk.help b/Scripts/DReyeVR.mk.help index bed671c..3eefe81 100644 --- a/Scripts/DReyeVR.mk.help +++ b/Scripts/DReyeVR.mk.help @@ -28,11 +28,6 @@ Use the following commands: Can specify Carla path with CARLA=/PATH/TO/CARLA Can specify ScenarioRunner path with SR=/PATH/TO/SCENARIO_RUNNER - patch-sranipal: - - Apply the patches required for building the SRanipal plugin in UE4. - Requires a Carla path, use CARLA=/PATH/TO/CARLA - rev | r-install: Copy files from the Carla/ScenarioRunner directory into DReyeVR. Useful for DReyeVR development. diff --git a/Scripts/Other/.gitignore b/Scripts/Other/.gitignore index 9feac38..888c885 100644 --- a/Scripts/Other/.gitignore +++ b/Scripts/Other/.gitignore @@ -15,11 +15,19 @@ Build* # added by DReyeVR so the frame captures are ignored Unreal/CarlaUE4/FrameCap +# added by DReyeVR to ignore plugins +Unreal/CarlaUE4/Config/steamvr_ue_editor_app.json +Unreal/CarlaUE4/Config/SteamVRBindings/ +Unreal/CarlaUE4/Plugins/LogitechWheelPlugin/ +Unreal/CarlaUE4/Plugins/SRanipal + # added by DReyeVR to MacOS builds don't track the .xcworkspace Unreal/CarlaUE4/CarlaUE4.xcworkspace # added by DReyeVR to ignore this auto-generated file Unreal/CarlaUE4/Config/OptionalModules.ini +!Unreal/CarlaUE4/Plugins +cmake-build-debug /ExportedMaps /Import/* @@ -60,3 +68,5 @@ _out* _site core profiler.csv +CarlaUE4.xcworkspace +OptionalModules.ini \ No newline at end of file diff --git a/Scripts/Paths/DReyeVR.csv b/Scripts/Paths/DReyeVR.csv index 9f1fe27..e928b88 100644 --- a/Scripts/Paths/DReyeVR.csv +++ b/Scripts/Paths/DReyeVR.csv @@ -1,20 +1,14 @@ DReyeVR,Unreal/CarlaUE4/Source/CarlaUE4/ -Configs/CarlaUE4.Build.cs,Unreal/CarlaUE4/Source/CarlaUE4 -Configs/Default*.ini,Unreal/CarlaUE4/Config/ -Configs/DReyeVRConfig.ini,Unreal/CarlaUE4/Config/ -Configs/CarlaUE4.uproject,Unreal/CarlaUE4/ -Blueprints/*,Unreal/CarlaUE4/Content/Carla/Blueprints/ -Content/DReyeVR_Signs/*,Unreal/CarlaUE4/Content/DReyeVR/DReyeVR_Signs/ -Content/Custom/*,Unreal/CarlaUE4/Content/DReyeVR/Custom/ -Content/Default.Package.json,Unreal/CarlaUE4/Content/Carla/Config/ -Maps/*,Unreal/CarlaUE4/Content/Carla/Maps/ -LibCarla/Client/*,LibCarla/source/carla/client/ -LibCarla/Client/detail/*,LibCarla/source/carla/client/detail/ -LibCarla/Sensor/*,LibCarla/source/carla/sensor/ -PythonAPI/*.py,PythonAPI/examples/ -PythonAPI/libcarla/*,PythonAPI/carla/source/libcarla/ -Carla/*,Unreal/CarlaUE4/Plugins/Carla/Source/Carla/ +CarlaUE4,Unreal/CarlaUE4/Source/ +Config/CarlaUE4.Build.cs,Unreal/CarlaUE4/Source/CarlaUE4 +Config/Default*.ini,Unreal/CarlaUE4/Config/ +Config/DReyeVRConfig.ini,Unreal/CarlaUE4/Config/ +Config/Default.Package.json,Unreal/CarlaUE4/Content/Carla/Config/ +Config/CarlaUE4.uproject,Unreal/CarlaUE4/ +Content,Unreal/CarlaUE4/ +LibCarla,/ +PythonAPI,/ +Carla,Unreal/CarlaUE4/Plugins/Carla/Source/ Tools/BuildTools/*.sh,Util/BuildTools/ -Tools/BuildTools/test_streaming.cpp,LibCarla/source/test/common/ Scripts/Other/.gitignore,/ Shaders/*.uasset,Unreal/CarlaUE4/Plugins/Carla/Content/PostProcessingMaterials/ diff --git a/Scripts/README.md b/Scripts/README.md index 3c827ff..0fc5be5 100644 --- a/Scripts/README.md +++ b/Scripts/README.md @@ -156,18 +156,6 @@ Done check ************************************************** ``` -## `make patch-sranipal` - -Patch SRanipal as described in [`patch_sranipal.py`](patch_sranipal.py) - -```bash -# automatically check $CARLA_ROOT -make patch-sranipal - -# optionally, patch SRanipal on a specific directory -make patch-sranipal CARLA=../carla -``` - ## `make r-install` ```bash diff --git a/Scripts/check_install.py b/Scripts/check_install.py index b1c9ab0..ef826e6 100644 --- a/Scripts/check_install.py +++ b/Scripts/check_install.py @@ -2,6 +2,7 @@ import os from typing import List, Optional +import filecmp from utils import ( CARLA_PATH_FILE, @@ -9,9 +10,11 @@ SUPPORTED_CARLA, SUPPORTED_SCENARIO_RUNNER, advanced_join, + advanced_is_dir, default_args, expand_correspondences_glob, generate_correspondences, + get_all_files, get_leaf_from_path, print_line, print_status, @@ -41,17 +44,45 @@ def check_repo( corr = generate_correspondences(corr_file) all_corr = expand_correspondences_glob(corr) + all_files = get_all_files(all_corr) + + def found(filepath: str) -> None: + if verbose: + print(f"{filepath} -- found") + + def check(filepath: str, local_file: str = None) -> None: + # make sure the files have the same content + if filecmp.cmp(filepath, local_file) is False: + if verbose: + print(f"{filepath} -- modified") + modified_files.append(filepath) + else: + found(filepath) + + def not_found(filepath: str) -> None: + if verbose: + print(f"{filepath} -- not found") missing_files: List[str] = [] + modified_files: List[str] = [] for k in all_corr.keys(): leafname = get_leaf_from_path(k) expected_path: str = advanced_join([ROOT, all_corr[k], leafname]) if os.path.exists(expected_path): - if verbose: - print(f"{expected_path} -- found") + if advanced_is_dir(expected_path): + found(expected_path) + for inner_f in all_files[k]: + inner_f_relative: str = inner_f[inner_f.find(leafname) :] + file_path = advanced_join([ROOT, all_corr[k], inner_f_relative]) + if os.path.exists(file_path): + check(file_path, local_file=inner_f) + else: + not_found(file_path) + missing_files.append(file_path) + else: + check(expected_path, local_file=k) else: - if verbose: - print(f"{expected_path} -- not found") + not_found(expected_path) missing_files.append(expected_path) # raise Exception(f"Failed to find {expected_path}") @@ -62,6 +93,13 @@ def check_repo( print(m) return False + if len(modified_files) > 0: + print() + print("ERROR: the following files are modified:") + for m in modified_files: + print(m) + return False + print("Success!") return True diff --git a/Scripts/install.py b/Scripts/install.py index 7866db7..87aaa32 100755 --- a/Scripts/install.py +++ b/Scripts/install.py @@ -11,8 +11,12 @@ SUPPORTED_SCENARIO_RUNNER, advanced_cp, advanced_join, + advanced_is_dir, + get_leaf_from_path, + get_all_files, default_args, generate_correspondences, + expand_correspondences_glob, print_line, update_backups, verify_installation, @@ -42,8 +46,20 @@ def install_over( update_backups(ROOT_ABS) # generate the DReyeVR -> root path correspondences corr = generate_correspondences(correspondences_file) - for DReyeVR_path, CARLA_path in corr.items(): - advanced_cp(DReyeVR_path, advanced_join([ROOT, CARLA_path]), verbose=True) + all_corr = expand_correspondences_glob(corr) + all_files_within = get_all_files(all_corr) + for DReyeVR_path, CARLA_path in all_corr.items(): + if advanced_is_dir(DReyeVR_path): + # installing a directory (many files within) + for local_file in all_files_within[DReyeVR_path]: + dest_path: str = advanced_join([ROOT, CARLA_path, local_file]) + advanced_cp(local_file, dest_path, verbose=True) + else: + # installing an individual file + assert os.path.isfile(DReyeVR_path) + file_leafname: str = get_leaf_from_path(DReyeVR_path) + dest_path: str = advanced_join([ROOT, CARLA_path, file_leafname]) + advanced_cp(DReyeVR_path, dest_path, verbose=True) print() print(f"Installation success!") print(f"Backups created in {advanced_join([BACKUPS_DIR, ROOT_ABS])}") diff --git a/Scripts/patch_sranipal.py b/Scripts/patch_sranipal.py deleted file mode 100644 index e877979..0000000 --- a/Scripts/patch_sranipal.py +++ /dev/null @@ -1,58 +0,0 @@ -#!/usr/bin/env python - -import os - -from utils import default_args - -# the reason for this patch's existance is that the latest (at time of writing) SRanipal plugin -# source code has an enum "FrameworkStatus::ERROR" in Source/SRanipalEye/Public/SRanipalEye_Framework.h -# which directly conflicts with some lingering #defines from UE4's WebRTC or CEF3 code which include a -# #define ERROR 0, this unfortunately gets propogated through the build and causes syntax errors when -# trying to compile SRanipal directly. The easiest fix with least ramifications is to simply rename the -# SRanipal's FrameworkStatus::ERROR variable to something specific like FrameworkStatus::ERROR_SRANIPAL - -DOC_STRING: str = "Patch SRanipal for use with DReyeVR" - - -PLUGIN_DIR: str = "Unreal/CarlaUE4/Plugins" - -# which files need to be modified -HEADER_FILE: str = "SRanipal/Source/SRanipalEye/Public/SRanipalEye_Framework.h" -SOURCE_FILE: str = "SRanipal/Source/SRanipalEye/Private/SRanipalEye_Framework.cpp" - -NEW_ERROR: str = "ERROR_SRANIPAL" # make sure this matches with EgoSensor.cpp - - -def patch_file(filepath: str) -> None: - filepath = os.path.abspath(filepath) - if not os.path.exists(filepath): - raise Exception(f"file {filepath} does not exist") - - # read from file to string - with open(filepath, "r") as f: - file_data: str = f.read() - - if NEW_ERROR in file_data: - print(f"Patch has already been applied for {filepath}") - return - - # perform operations on the string - file_data = file_data.replace("ERROR", NEW_ERROR) - - # write back to file - with open(filepath, "w") as f: - f.write(file_data) - print(f'Successfully patched "{filepath}"') - - -if __name__ == "__main__": - args = default_args(DOC_STRING, with_sr=False) - - # first patch header file - if args.carla is not None: - patch_file(os.path.join(args.carla, PLUGIN_DIR, HEADER_FILE)) - patch_file(os.path.join(args.carla, PLUGIN_DIR, SOURCE_FILE)) - print() - print("Completed SRanipal patches for DReyeVR") - else: - print("No Carla root provided") diff --git a/Scripts/utils.py b/Scripts/utils.py index cc0bd1e..8fd0386 100644 --- a/Scripts/utils.py +++ b/Scripts/utils.py @@ -307,6 +307,27 @@ def expand_correspondences_glob(corr: Dict[str, str]) -> Dict[str, str]: return expanded +def get_all_files(corr: Dict[str, str]) -> Dict[str, str]: + files_map = {} + for k in corr.keys(): + if advanced_is_dir(k): + only_files = [] + for root, _, files in os.walk(k): + for f in files: + filepath = advanced_join([root, f]) + if os.path.isfile(filepath): + only_files.append(filepath) + assert os.path.exists(filepath) + + files_map[k] = list(sorted(only_files)) + else: + files_map[k] = [k] # already a file + for group in files_map.values(): + for f in group: + assert not advanced_is_dir(f) + return files_map + + def check_env_var(user_in: str, env_var: str) -> Optional[str]: if user_in is not None: # just use the path provided to us diff --git a/Tools/BuildTools/BuildPythonAPI.sh b/Tools/BuildTools/BuildPythonAPI.sh index 84c87d3..2e00d69 100755 --- a/Tools/BuildTools/BuildPythonAPI.sh +++ b/Tools/BuildTools/BuildPythonAPI.sh @@ -89,7 +89,7 @@ if ${BUILD_PYTHONAPI} ; then # Add patchelf to the path. Auditwheel relies on patchelf to repair ELF files. export PATH="${LIBCARLA_INSTALL_CLIENT_FOLDER}/bin:${PATH}" - CODENAME=$(cat /etc/os-release | grep VERSION_CODENAME) + CODENAME=$(uname -s) if [[ ! -z ${TARGET_WHEEL_PLATFORM} ]] && [[ ${CODENAME#*=} != "bionic" ]] ; then log "A target platform has been specified but you are not using a compatible linux distribution. The wheel repair step will be skipped" TARGET_WHEEL_PLATFORM=