diff --git a/CHANGELOG.md b/CHANGELOG.md index 737d612..61bcf50 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,3 +1,21 @@ +## DReyeVR 0.2.1 +- Adding smart (weak) pointers for the major DReyeVR class connections to ensure better pointer validity before dereference. Helps with detecting dangling (freed, but not-null) pointers which happens commonly during map changes and would otherwise crash the replay system. +- Adding PythonAPI startup function (namely a custom `__init__.py` script that is loaded when using `DReyeVR_utils.py`) +- Fix bug with shaders not being cooked in package mode +- Fine-tune ego-vehicle mirrors according to vehicle chassis +- Adding threshold for manual takeover of logitech inputs. Logitech wheel actuation follows autopilot otherwise. +- Disabling shadows for wheel face buttons +- Adding autopilot light indicator + +## DReyeVR 0.2.0 +- Add face button indicators on the steering wheel +- Revamping `ConfigFile` class rather than a static `ReadConfigFile` helper function +- Adding Config-file check as part of the tracked DReyeVRData, gives you a warning if your loaded ConfigFile is different from the one that was used during recording (so you can match your replay config with that which was recorded) +- Adding per-vehicle configuration files in `Content/DReyeVR/EgoVehicle` that can be selected via parameters. Allows parameterization of all EgoVehicle components, magic numbers (ex. location of camera, mirrors, engine), sound files, mirror meshes, steering wheel types, and enable/disable these on a highly granular basis +- Revamp EgoVehicle input controls to use parent (ACarlaWheeledVehicle) controls and flush +- Disabling (turning invisible) default Carla spectator in map +- Added tutorial for custom EgoVehicle + ## DReyeVR 0.1.3 - Fix bug where other non-ego Autopilto vehicles ignored the EgoVehicle and would routinely crash into it - Fix bug where some EgoVehicle attributes were missing, notably `"number_of_wheels"` @@ -30,4 +48,4 @@ - 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 +- Updated documentation and config file \ No newline at end of file diff --git a/Carla/Actor/DReyeVRCustomActor.cpp b/Carla/Actor/DReyeVRCustomActor.cpp index 7f6e03b..a872754 100644 --- a/Carla/Actor/DReyeVRCustomActor.cpp +++ b/Carla/Actor/DReyeVRCustomActor.cpp @@ -49,12 +49,6 @@ ADReyeVRCustomActor::ADReyeVRCustomActor(const FObjectInitializer &ObjectInitial Internals.Scale3D = this->GetActorScale3D(); } -ADReyeVRCustomActor::~ADReyeVRCustomActor() -{ - this->Deactivate(); - this->Destroy(); // UE4 Destroy method -} - bool ADReyeVRCustomActor::AssignSM(const FString &Path, UWorld *World) { UStaticMesh *SM = LoadObject(nullptr, *Path); @@ -164,9 +158,14 @@ void ADReyeVRCustomActor::Tick(float DeltaSeconds) Internals.Scale3D = this->GetActorScale3D(); Internals.MaterialParams = MaterialParams; } + UpdateMaterial(); + /// TODO: use other string? +} + +void ADReyeVRCustomActor::UpdateMaterial() +{ // update the materials according to the params MaterialParams.Apply(DynamicMat); - /// TODO: use other string? } void ADReyeVRCustomActor::SetInternals(const DReyeVR::CustomActorData &InData) diff --git a/Carla/Actor/DReyeVRCustomActor.h b/Carla/Actor/DReyeVRCustomActor.h index a2a8235..1302e70 100644 --- a/Carla/Actor/DReyeVRCustomActor.h +++ b/Carla/Actor/DReyeVRCustomActor.h @@ -24,7 +24,7 @@ class CARLA_API ADReyeVRCustomActor : public AActor // abstract class public: ADReyeVRCustomActor(const FObjectInitializer &ObjectInitializer); - ~ADReyeVRCustomActor(); + ~ADReyeVRCustomActor() = default; /// factory function to create a new instance of a given type static ADReyeVRCustomActor *CreateNew(const FString &SM_Path, const FString &Mat_Path, UWorld *World, @@ -39,6 +39,16 @@ class CARLA_API ADReyeVRCustomActor : public AActor // abstract class return bIsActive; } + void SetActorRecordEnabled(const bool bEnabled) + { + bShouldRecord = bEnabled; + } + + const bool GetShouldRecord() const + { + return bShouldRecord; + } + void Initialize(const FString &Name); void SetInternals(const DReyeVR::CustomActorData &In); @@ -47,14 +57,21 @@ class CARLA_API ADReyeVRCustomActor : public AActor // abstract class static std::unordered_map ActiveCustomActors; + inline class UStaticMeshComponent *GetMesh() + { + return ActorMesh; + } + // function to dynamically change the material params of the object at runtime void AssignMat(const FString &Path); + void UpdateMaterial(); struct DReyeVR::CustomActorData::MaterialParamsStruct MaterialParams; private: void BeginPlay() override; void BeginDestroy() override; - bool bIsActive = false; // initially deactivated + bool bIsActive = false; // initially deactivated + bool bShouldRecord = true; // should record in the Carla Recorder/Replayer bool AssignSM(const FString &Path, UWorld *World); diff --git a/Carla/Recorder/CarlaRecorder.cpp b/Carla/Recorder/CarlaRecorder.cpp index 327ab7e..4fdbada 100644 --- a/Carla/Recorder/CarlaRecorder.cpp +++ b/Carla/Recorder/CarlaRecorder.cpp @@ -91,12 +91,15 @@ void ACarlaRecorder::Ticking(float DeltaSeconds) PlatformTime.UpdateTime(); const FActorRegistry &Registry = Episode->GetActorRegistry(); + // Skip the spectator actor + FCarlaActor* CarlaSpectator = Episode->FindCarlaActor(Episode->GetSpectatorPawn()); + // through all actors in registry for (auto It = Registry.begin(); It != Registry.end(); ++It) { FCarlaActor* View = It.Value().Get(); - if (View->GetActorId() == 0) + if (CarlaSpectator && (View->GetActor() == CarlaSpectator->GetActor())) continue; // don't record the spectator switch (View->GetActorType()) @@ -277,18 +280,20 @@ void ACarlaRecorder::AddActorBoundingBox(FCarlaActor *CarlaActor) void ACarlaRecorder::AddDReyeVRData() { + static bool bAddedConfigFile; + if (!bAddedConfigFile) { + // add DReyeVR config files (only once at the beginning of recording) + DReyeVRConfigFileData.Add(ADReyeVRSensor::ConfigFile); + bAddedConfigFile = true; + } + // Add the latest instance of the DReyeVR snapshot to our data DReyeVRAggData.Add(DReyeVRDataRecorder(ADReyeVRSensor::Data)); - TArray FoundActors; - if (Episode != nullptr && Episode->GetWorld() != nullptr) + for (auto &ActiveCAs : ADReyeVRCustomActor::ActiveCustomActors) { - UGameplayStatics::GetAllActorsOfClass(Episode->GetWorld(), ADReyeVRCustomActor::StaticClass(), FoundActors); - } - for (AActor *A : FoundActors) - { - ADReyeVRCustomActor *CustomActor = Cast(A); - if (CustomActor != nullptr && CustomActor->IsActive()) + ADReyeVRCustomActor *CustomActor = ActiveCAs.second; + if (CustomActor != nullptr && CustomActor->IsActive() && CustomActor->GetShouldRecord()) { DReyeVRCustomActorData.Add(DReyeVRDataRecorder(&(CustomActor->GetInternals()))); } @@ -427,6 +432,7 @@ void ACarlaRecorder::Clear(void) TrafficLightTimes.Clear(); DReyeVRAggData.Clear(); DReyeVRCustomActorData.Clear(); + DReyeVRConfigFileData.Clear(); Weathers.Clear(); } @@ -470,6 +476,14 @@ void ACarlaRecorder::Write(double DeltaSeconds) // custom DReyeVR Actor data write DReyeVRCustomActorData.Write(File); + // only write this once (at the beginning) + static bool bWroteConfigFile = false; + if (!bWroteConfigFile) { + // DReyeVR configuration/parameters + DReyeVRConfigFileData.Write(File); + bWroteConfigFile = true; + } + // weather state Weathers.Write(File); diff --git a/Carla/Recorder/CarlaRecorder.h b/Carla/Recorder/CarlaRecorder.h index 5545963..621b170 100644 --- a/Carla/Recorder/CarlaRecorder.h +++ b/Carla/Recorder/CarlaRecorder.h @@ -47,6 +47,7 @@ class ATrafficLightBase; #define DREYEVR_PACKET_ID 139 #define DREYEVR_CUSTOM_ACTOR_PACKET_ID 140 +#define DREYEVR_CONFIG_FILE_PACKET_ID 141 enum class CarlaRecorderPacketId : uint8_t { @@ -70,8 +71,9 @@ enum class CarlaRecorderPacketId : uint8_t TriggerVolume, Weather, // "We suggest to use id over 100 for user custom packets, because this list will keep growing in the future" - DReyeVR = DREYEVR_PACKET_ID, // our custom DReyeVR packet (for raw sensor data) - DReyeVRCustomActor = DREYEVR_CUSTOM_ACTOR_PACKET_ID // custom DReyeVR actors (not raw sensor data) + DReyeVR = DREYEVR_PACKET_ID, // our custom DReyeVR packet (for raw sensor data) + DReyeVRCustomActor = DREYEVR_CUSTOM_ACTOR_PACKET_ID, // custom DReyeVR actors (not raw sensor data) + DReyeVRConfigFile = DREYEVR_CONFIG_FILE_PACKET_ID // DReyeVR configuration files (parameters) }; /// Recorder for the simulation @@ -205,6 +207,7 @@ class CARLA_API ACarlaRecorder : public AActor CarlaRecorderWeathers Weathers; DReyeVRDataRecorders DReyeVRAggData; DReyeVRDataRecorders DReyeVRCustomActorData; + DReyeVRDataRecorders DReyeVRConfigFileData; // replayer CarlaReplayer Replayer; diff --git a/Carla/Recorder/CarlaRecorderQuery.cpp b/Carla/Recorder/CarlaRecorderQuery.cpp index 2bf9f27..17b7cef 100644 --- a/Carla/Recorder/CarlaRecorderQuery.cpp +++ b/Carla/Recorder/CarlaRecorderQuery.cpp @@ -604,6 +604,27 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll) else SkipPacket(); break; + + // DReyeVR data (ConfigFileData) + case static_cast(CarlaRecorderPacketId::DReyeVRConfigFile): + if (bShowAll) + { + ReadValue(File, Total); + if (Total > 0 && !bFramePrinted) + { + PrintFrame(Info); + bFramePrinted = true; + } + Info << " DReyeVR config files: " << Total << std::endl; + for (i = 0; i < Total; ++i) + { + DReyeVRConfigFileDataInstance.Read(File); + Info << DReyeVRConfigFileDataInstance.Print() << std::endl; + } + } + else + SkipPacket(); + break; // frame end case static_cast(CarlaRecorderPacketId::FrameEnd): // do nothing, it is empty diff --git a/Carla/Recorder/CarlaRecorderQuery.h b/Carla/Recorder/CarlaRecorderQuery.h index cf03ac9..96974c6 100644 --- a/Carla/Recorder/CarlaRecorderQuery.h +++ b/Carla/Recorder/CarlaRecorderQuery.h @@ -72,6 +72,7 @@ class CarlaRecorderQuery // custom DReyeVR packets DReyeVRDataRecorder DReyeVRAggDataInstance; DReyeVRDataRecorder DReyeVRCustomActorDataInstance; + DReyeVRDataRecorder DReyeVRConfigFileDataInstance; // read next header packet bool ReadHeader(void); diff --git a/Carla/Recorder/CarlaReplayer.cpp b/Carla/Recorder/CarlaReplayer.cpp index 61a8568..0a03451 100644 --- a/Carla/Recorder/CarlaReplayer.cpp +++ b/Carla/Recorder/CarlaReplayer.cpp @@ -32,6 +32,10 @@ void CarlaReplayer::Stop(bool bKeepActors) // callback Helper.ProcessReplayerFinish(bKeepActors, IgnoreHero, IsHeroMap); + + // turn off DReyeVR replay + if (GetEgoSensor()) + GetEgoSensor()->StopReplaying(); } File.close(); @@ -291,6 +295,85 @@ void CarlaReplayer::CheckPlayAfterMapLoaded(void) Enabled = true; } +class ADReyeVRSensor *CarlaReplayer::GetEgoSensor() +{ + if (EgoSensor.IsValid()) { + return EgoSensor.Get(); + } + // not tracked yet, lets find the EgoSensor + if (Episode == nullptr) { + DReyeVR_LOG_ERROR("No Replayer Episode available!"); + return nullptr; + } + EgoSensor = ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld()); + if (!EgoSensor.IsValid()) { + DReyeVR_LOG_ERROR("No EgoSensor available!"); + return nullptr; + } + return EgoSensor.Get(); +} + +template<> +void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) +{ + uint16_t Total; + // read number of DReyeVR entries + ReadValue(File, Total); // read number of events + check(Total == 1); // should be only one Agg data + for (uint16_t i = 0; i < Total; ++i) + { + struct DReyeVRDataRecorder Instance; + Instance.Read(File); + Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); + } +} + +template<> +void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) +{ + uint16_t Total; + // read number of DReyeVR entries + ReadValue(File, Total); // read number of events + check(Total == 1); // should be only one ConfigFile data + for (uint16_t i = 0; i < Total; ++i) + { + struct DReyeVRDataRecorder Instance; + Instance.Read(File); + Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); + } +} + +template<> +void CarlaReplayer::ProcessDReyeVR(double Per, double DeltaTime) +{ + uint16_t Total; + ReadValue(File, Total); // read number of events + CustomActorsVisited.clear(); + for (uint16_t i = 0; i < Total; ++i) + { + struct DReyeVRDataRecorder Instance; + Instance.Read(File); + Helper.ProcessReplayerDReyeVR(GetEgoSensor(), Instance.Data, Per); + auto Name = Instance.GetUniqueName(); + CustomActorsVisited.insert(Name); // to track lifetime + } + + for (auto It = ADReyeVRCustomActor::ActiveCustomActors.begin(); It != ADReyeVRCustomActor::ActiveCustomActors.end();){ + const std::string &ActiveActorName = It->first; + if (CustomActorsVisited.find(ActiveActorName) == CustomActorsVisited.end()) // currently alive actor who was not visited... time to disable + { + // now this has to be garbage collected + auto Next = std::next(It, 1); // iterator following the last removed element + It->second->Deactivate(); + It = Next; + } + else + { + ++It; // increment iterator if not erased + } + } +} + void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime) { double Per = 0.0f; @@ -401,18 +484,26 @@ void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime) ProcessWeather(); break; - // DReyeVR eye logging data + // DReyeVR ego sensor data case static_cast(CarlaRecorderPacketId::DReyeVR): if (bFrameFound) - ProcessDReyeVRData>(Per, Time, true); + ProcessDReyeVR(Per, Time); else SkipPacket(); break; - // DReyeVR eye logging data + // DReyeVR custom actor data case static_cast(CarlaRecorderPacketId::DReyeVRCustomActor): if (bFrameFound) - ProcessDReyeVRData>(Per, Time, false); + ProcessDReyeVR(Per, Time); + else + SkipPacket(); + break; + + // DReyeVR config file data + case static_cast(CarlaRecorderPacketId::DReyeVRConfigFile): + if (bFrameFound) + ProcessDReyeVR(Per, Time); else SkipPacket(); break; @@ -647,49 +738,6 @@ void CarlaReplayer::ProcessWeather(void) } } -template void CarlaReplayer::ProcessDReyeVRData(double Per, double DeltaTime, bool bShouldBeOnlyOne) -{ - uint16_t Total; - // custom DReyeVR packets - - // read Total DReyeVR events - ReadValue(File, Total); // read number of events - - Visited.clear(); - for (uint16_t i = 0; i < Total; ++i) - { - T DReyeVRDataInstance; - DReyeVRDataInstance.Read(File); - Helper.ProcessReplayerDReyeVRData(DReyeVRDataInstance, Per); - if (!bShouldBeOnlyOne) - { - auto Name = DReyeVRDataInstance.GetUniqueName(); - Visited.insert(Name); - } - } - if (bShouldBeOnlyOne) - { - check(Total == 1); - } - else - { - for (auto It = ADReyeVRCustomActor::ActiveCustomActors.begin(); It != ADReyeVRCustomActor::ActiveCustomActors.end();){ - const std::string &ActiveActorName = It->first; - if (Visited.find(ActiveActorName) == Visited.end()) // currently alive actor who was not visited... time to disable - { - // now this has to be garbage collected - auto Next = std::next(It, 1); // iterator following the last removed element - It->second->Deactivate(); - It = Next; - } - else - { - ++It; // increment iterator if not erased - } - } - } -} - void CarlaReplayer::ProcessPositions(bool IsFirstTime) { uint16_t i, Total; @@ -823,12 +871,8 @@ void CarlaReplayer::ProcessFrameByFrame() if (SyncCurrentFrameId > 0) LastTime = FrameStartTimes[SyncCurrentFrameId - 1]; ProcessToTime(FrameStartTimes[SyncCurrentFrameId] - LastTime, (SyncCurrentFrameId == 0)); - if (ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld())) - // have the vehicle camera take a screenshot to record the replay - ADReyeVRSensor::GetDReyeVRSensor()->TakeScreenshot(); - else - DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); - + if (GetEgoSensor()) // take screenshot of this frame + GetEgoSensor()->TakeScreenshot(); // progress to the next frame if (SyncCurrentFrameId < FrameStartTimes.size() - 1) SyncCurrentFrameId++; diff --git a/Carla/Recorder/CarlaReplayer.h b/Carla/Recorder/CarlaReplayer.h index 9002013..0331b8c 100644 --- a/Carla/Recorder/CarlaReplayer.h +++ b/Carla/Recorder/CarlaReplayer.h @@ -168,8 +168,11 @@ class CARLA_API CarlaReplayer void ProcessWeather(void); // DReyeVR recordings - template void ProcessDReyeVRData(double Per, double DeltaTime, bool bShouldBeOnlyOne); - std::unordered_set Visited = {}; + template + void ProcessDReyeVR(double Per, double DeltaTime); + std::unordered_set CustomActorsVisited = {}; + class ADReyeVRSensor *GetEgoSensor(); // (safe) getter for EgoSensor + TWeakObjectPtr EgoSensor; // For restarting the recording with the same params struct LastReplayStruct diff --git a/Carla/Recorder/CarlaReplayerHelper.cpp b/Carla/Recorder/CarlaReplayerHelper.cpp index b7130f9..82afabb 100644 --- a/Carla/Recorder/CarlaReplayerHelper.cpp +++ b/Carla/Recorder/CarlaReplayerHelper.cpp @@ -477,20 +477,20 @@ bool CarlaReplayerHelper::ProcessReplayerFinish(bool bApplyAutopilot, bool bIgno break; } } - // tell the DReyeVR sensor to NOT continue replaying - if (ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld())) - ADReyeVRSensor::GetDReyeVRSensor()->StopReplaying(); - else - DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); return true; } -template void CarlaReplayerHelper::ProcessReplayerDReyeVRData(const T &DReyeVRDataInstance, const double Per) +template +void CarlaReplayerHelper::ProcessReplayerDReyeVR(ADReyeVRSensor *EgoSensor, const T &Data, const double Per) { - if (ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld())) - ADReyeVRSensor::GetDReyeVRSensor()->UpdateData(DReyeVRDataInstance.Data, Per); - else + if (EgoSensor == nullptr) { // try getting and assigning the new EgoSensor + EgoSensor = ADReyeVRSensor::GetDReyeVRSensor(Episode->GetWorld()); + } + if (EgoSensor == nullptr) { // still null?? throw an error DReyeVR_LOG_ERROR("No DReyeVR sensor available!"); + return; + } + EgoSensor->UpdateData(Data, Per); } void CarlaReplayerHelper::SetActorVelocity(FCarlaActor *CarlaActor, FVector Velocity) diff --git a/Carla/Recorder/CarlaReplayerHelper.h b/Carla/Recorder/CarlaReplayerHelper.h index 9e78129..b4695f4 100644 --- a/Carla/Recorder/CarlaReplayerHelper.h +++ b/Carla/Recorder/CarlaReplayerHelper.h @@ -23,6 +23,7 @@ class UCarlaEpisode; class FCarlaActor; struct FActorDescription; +class ADReyeVRSensor; // fwd for DReyeVR (avoid header conflict) class CarlaReplayerHelper { @@ -75,7 +76,8 @@ class CarlaReplayerHelper bool ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, std::unordered_map &IsHero); // update the DReyeVR ego sensor and custom types - template void ProcessReplayerDReyeVRData(const T &DReyeVRDataInstance, const double Per); + template + void ProcessReplayerDReyeVR(ADReyeVRSensor *EgoSensor, const T &Data, const double Per); // set the camera position to follow an actor bool SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation); diff --git a/Carla/Sensor/DReyeVRData.cpp b/Carla/Sensor/DReyeVRData.cpp index bc89432..b14845e 100644 --- a/Carla/Sensor/DReyeVRData.cpp +++ b/Carla/Sensor/DReyeVRData.cpp @@ -233,6 +233,30 @@ FString EyeTracker::ToString() const return Print; } +/// ========================================== /// +/// ------------:CONFIGFILEDATA:-------------- /// +/// ========================================== /// + +void ConfigFileData::Set(const std::string &Contents) +{ + StringContents = FString(Contents.c_str()); +} + +void ConfigFileData::Read(std::ifstream &InFile) +{ + ReadFString(InFile, StringContents); +} + +void ConfigFileData::Write(std::ofstream &OutFile) const +{ + WriteFString(OutFile, StringContents); +} + +FString ConfigFileData::ToString() const +{ + return StringContents; +} + /// ========================================== /// /// -------------:AGGREGATEDATA:-------------- /// /// ========================================== /// @@ -443,8 +467,8 @@ void AggregateData::UpdateVehicle(const FVector &NewVehicleLoc, const FRotator & } void AggregateData::Update(int64_t NewTimestamp, const struct EyeTracker &NewEyeData, - const struct EgoVariables &NewEgoVars, const struct FocusInfo &NewFocus, - const struct UserInputs &NewInputs) + const struct EgoVariables &NewEgoVars, const struct FocusInfo &NewFocus, + const struct UserInputs &NewInputs) { TimestampCarlaUE4 = NewTimestamp; EyeTrackerData = NewEyeData; @@ -484,11 +508,6 @@ FString AggregateData::ToString() const return print; } -std::string AggregateData::GetUniqueName() const -{ - return "DReyeVRSensorAggregateData"; -} - /// ========================================== /// /// ------------:CUSTOMACTORDATA:------------- /// /// ========================================== /// diff --git a/Carla/Sensor/DReyeVRData.h b/Carla/Sensor/DReyeVRData.h index dc896c8..3495fb4 100644 --- a/Carla/Sensor/DReyeVRData.h +++ b/Carla/Sensor/DReyeVRData.h @@ -133,6 +133,18 @@ enum class Eye LEFT, }; +// all DReyeVR Config data (only used once at the start of each recording) +class CARLA_API ConfigFileData : public DataSerializer +{ + private: + FString StringContents; // all the config files, concatenated + public: + void Set(const std::string &Contents); + void Read(std::ifstream &InFile) override; + void Write(std::ofstream &OutFile) const override; + FString ToString() const override; +}; + // all DReyeVR sensor data is held here class CARLA_API AggregateData : public DataSerializer { @@ -161,7 +173,6 @@ class CARLA_API AggregateData : public DataSerializer float GetVehicleVelocity() const; const FVector &GetVehicleLocation() const; const FRotator &GetVehicleRotation() const; - std::string GetUniqueName() const; // focus const FString &GetFocusActorName() const; diff --git a/Carla/Sensor/DReyeVRSensor.cpp b/Carla/Sensor/DReyeVRSensor.cpp index a93e6c5..4124d62 100644 --- a/Carla/Sensor/DReyeVRSensor.cpp +++ b/Carla/Sensor/DReyeVRSensor.cpp @@ -13,13 +13,17 @@ #include "carla/sensor/s11n/DReyeVRSerializer.h" // DReyeVRSerializer::Data class DReyeVR::AggregateData *ADReyeVRSensor::Data = nullptr; +class DReyeVR::ConfigFileData *ADReyeVRSensor::ConfigFile = nullptr; bool ADReyeVRSensor::bIsReplaying = false; // initially not replaying ADReyeVRSensor::ADReyeVRSensor(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) { // no need for any other initialization PrimaryActorTick.bCanEverTick = true; - ADReyeVRSensor::Data = new DReyeVR::AggregateData(); + if (ADReyeVRSensor::Data == nullptr) + ADReyeVRSensor::Data = new DReyeVR::AggregateData(); + if (ADReyeVRSensor::ConfigFile == nullptr) + ADReyeVRSensor::ConfigFile = new DReyeVR::ConfigFileData(); } FActorDefinition ADReyeVRSensor::GetSensorDefinition() @@ -191,9 +195,16 @@ void ADReyeVRSensor::UpdateData(const DReyeVR::AggregateData &RecorderData, cons } } +void ADReyeVRSensor::UpdateData(const class DReyeVR::ConfigFileData &RecorderData, const double Per) +{ + // should be implemented in the EgoSensor (child) impl + unimplemented(); +} + void ADReyeVRSensor::UpdateData(const class DReyeVR::CustomActorData &RecorderData, const double Per) { - // should be implemented in the child class impl + // should be implemented in the EgoSensor (child) impl + unimplemented(); } void ADReyeVRSensor::StopReplaying() diff --git a/Carla/Sensor/DReyeVRSensor.h b/Carla/Sensor/DReyeVRSensor.h index 55451bc..7edef65 100644 --- a/Carla/Sensor/DReyeVRSensor.h +++ b/Carla/Sensor/DReyeVRSensor.h @@ -32,6 +32,7 @@ class CARLA_API ADReyeVRSensor : public ASensor // everything stored in the sensor is held in this struct /// TODO: make this non-static and use a smarter scheme for cross-class communication static class DReyeVR::AggregateData *Data; + static class DReyeVR::ConfigFileData *ConfigFile; class DReyeVR::AggregateData *GetData() { @@ -46,6 +47,7 @@ class CARLA_API ADReyeVRSensor : public ASensor bool IsReplaying() const; virtual void UpdateData(const class DReyeVR::AggregateData &RecorderData, const double Per); // starts replaying + virtual void UpdateData(const class DReyeVR::ConfigFileData &RecorderData, const double Per); virtual void UpdateData(const class DReyeVR::CustomActorData &RecorderData, const double Per); void StopReplaying(); virtual void TakeScreenshot() diff --git a/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Carla/Vehicle/CarlaWheeledVehicle.cpp index 3562246..78dd59c 100644 --- a/Carla/Vehicle/CarlaWheeledVehicle.cpp +++ b/Carla/Vehicle/CarlaWheeledVehicle.cpp @@ -182,6 +182,14 @@ void ACarlaWheeledVehicle::BeginPlay() SetVolume(0); } +void ACarlaWheeledVehicle::Tick(float DeltaSeconds) +{ + Super::Tick(DeltaSeconds); + + // Play sound that requires constant ticking + TickSounds(DeltaSeconds); +} + // ============================================================================= // -- Sound Functions ---------------------------------------------------------- // ============================================================================= @@ -213,7 +221,7 @@ void ACarlaWheeledVehicle::ConstructSounds() check(CrashSound != nullptr); } -void ACarlaWheeledVehicle::TickSounds() +void ACarlaWheeledVehicle::TickSounds(float DeltaSeconds) { // Respect the global vehicle volume param SetVolume(ACarlaWheeledVehicle::Volume); @@ -230,12 +238,6 @@ void ACarlaWheeledVehicle::TickSounds() // add other sounds that need tick-level granularity here... } -void ACarlaWheeledVehicle::PlayCrashSound(const float DelayBeforePlay) const -{ - if (this->CrashSound) - this->CrashSound->Play(DelayBeforePlay); -} - void ACarlaWheeledVehicle::SetVolume(const float VolumeIn) { if (EngineRevSound) @@ -258,39 +260,44 @@ void ACarlaWheeledVehicle::ConstructCollisionHandler() Bounds->OnComponentBeginOverlap.AddDynamic(this, &ACarlaWheeledVehicle::OnOverlapBegin); } +bool ACarlaWheeledVehicle::EnableCollisionForActor(AActor *OtherActor) +{ + // define whether or not we should "collide" with these actors + // as opposed to actors such as the ground/grass + const FString OtherName = OtherActor->GetName().ToLower(); + double Now = GetWorld()->GetTimeSeconds(); + bool bIsAVehicle = OtherActor->IsA(ACarlaWheeledVehicle::StaticClass()); + return (CollisionCooldownTime < Now && // respect collision audio cooldown + (bIsAVehicle || // do collide with vehicles + OtherName.Contains("spline") || // do collide with carla "spline" (misc) objects + OtherName.Contains("streetlight") || // do collide with street lights + OtherName.Contains("curb") // do collide with curb objects + )); +} + void ACarlaWheeledVehicle::OnOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, int32 OtherBodyIndex, bool bFromSweep, const FHitResult &SweepResult) { - if (OtherActor != nullptr && OtherActor != this) + if (OtherActor == nullptr || OtherActor == this) + return; + + // can be more flexible, such as having collisions with static props or people too + if (EnableCollisionForActor(OtherActor)) { - FString actor_name = OtherActor->GetName(); - // UE_LOG(LogTemp, Log, TEXT("Collision with \"%s\""), *actor_name); - // can be more flexible, such as having collisions with static props or people too - const FString OtherName = OtherActor->GetName().ToLower(); - double Now = FPlatformTime::Seconds(); + // emit the car collision sound at the midpoint between the vehicles' collision + /// TODO: would be ideal to use FHitPoint::ImpactPoint but there is a bug in UE4 where this is not initialized + // see: https://answers.unrealengine.com/questions/219744/component-overlap-hit-position-always-returns-000.html + FVector SoundEmitLocation = EngineLocnInVehicle; bool bIsAVehicle = OtherActor->IsA(ACarlaWheeledVehicle::StaticClass()); - if (CollisionCooldownTime < Now && // respect collision audio cooldown - (bIsAVehicle || // do collide with vehicles - OtherName.Contains("spline") || // do collide with carla "spline" (misc) objects - OtherName.Contains("streetlight") || // do collide with street lights - OtherName.Contains("curb") // do collide with curb objects - ) - ) - { - // emit the car collision sound at the midpoint between the vehicles' collision - /// TODO: would be ideal to use FHitPoint::ImpactPoint but there is a bug in UE4 where this is not initialized - // see: https://answers.unrealengine.com/questions/219744/component-overlap-hit-position-always-returns-000.html - FVector SoundEmitLocation = EngineLocnInVehicle; - if (bIsAVehicle) { // in the case where the other actor is a vehicle, do emit the sound at the location midpoint - SoundEmitLocation = (OtherActor->GetActorLocation() - this->GetActorLocation()) / 2.f; - SoundEmitLocation += 75.f * FVector::UpVector; // Make the sound emitted not at the ground (0.75m above ground) - } - if (CrashSound != nullptr) { - CrashSound->SetRelativeLocation(SoundEmitLocation); - PlayCrashSound(); - CollisionCooldownTime = Now + 0.5f; // have at least 1s of buffer between collision audio - } + if (bIsAVehicle) { // in the case where the other actor is a vehicle, do emit the sound at the location midpoint + SoundEmitLocation = (OtherActor->GetActorLocation() - this->GetActorLocation()) / 2.f; + SoundEmitLocation += 75.f * FVector::UpVector; // Make the sound emitted not at the ground (0.75m above ground) + } + if (CrashSound != nullptr) { + CrashSound->SetRelativeLocation(SoundEmitLocation); + CrashSound->Play(); + CollisionCooldownTime = GetWorld()->GetTimeSeconds() + 0.5f; // have at least 0.5s of buffer between collision audio } } } @@ -368,9 +375,6 @@ void ACarlaWheeledVehicle::FlushVehicleControl() InputControl.Control.bReverse = InputControl.Control.Gear < 0; LastAppliedControl = InputControl.Control; InputControl.Priority = EVehicleInputPriority::INVALID; - - // Play sound that requires constant ticking - TickSounds(); } void ACarlaWheeledVehicle::SetThrottleInput(const float Value) diff --git a/Carla/Vehicle/CarlaWheeledVehicle.h b/Carla/Vehicle/CarlaWheeledVehicle.h index 47e6934..2257e65 100644 --- a/Carla/Vehicle/CarlaWheeledVehicle.h +++ b/Carla/Vehicle/CarlaWheeledVehicle.h @@ -260,6 +260,7 @@ class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle // =========================================================================== /// @{ + virtual void Tick(float DeltaTime) override; // called once per frame protected: virtual void BeginPlay() override; @@ -267,14 +268,19 @@ class CARLA_API ACarlaWheeledVehicle : public AWheeledVehicle // sounds (DReyeVR) void ConstructSounds(); - void TickSounds(); - const FVector EngineLocnInVehicle{180.f, 0.f, 70.f}; + virtual void TickSounds(float DeltaSeconds); + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + FVector EngineLocnInVehicle{180.f, 0.f, 70.f}; + // need to disable these for EgoVehicle to have our own Ego versions + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UAudioComponent *EngineRevSound = nullptr; // driver feedback on throttle + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UAudioComponent *CrashSound = nullptr; // crashing with another actor double CollisionCooldownTime = 0.0; // can add more sounds here... like a horn maybe? // collisions (DReyeVR) + bool EnableCollisionForActor(AActor *OtherActor); void ConstructCollisionHandler(); // needs to be called in the constructor UFUNCTION() void OnOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, diff --git a/Config/DReyeVRConfig.ini b/Config/DReyeVRConfig.ini index 60b2140..cd73b09 100644 --- a/Config/DReyeVRConfig.ini +++ b/Config/DReyeVRConfig.ini @@ -8,24 +8,13 @@ # 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 +VehicleType="TeslaM3" # this is the name of the .ini config file in Config/EgoVehicles/ -[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 +# general parameters for all vehicles +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 [CameraParams] FieldOfView=90.0 # horizontal field of view (only in stereo camera => NOT VR) @@ -38,33 +27,6 @@ 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) -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 @@ -91,6 +53,12 @@ EnableSpectatorScreen=True # whether or not to enable the flat-screen spectator 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 !! + +[Sound] +DefaultEngineRev="SoundCue'/Game/DReyeVR/Sounds/EngineRev/EngineRev.EngineRev'" +DefaultCrashSound="SoundCue'/Game/DReyeVR/Sounds/Crash/CrashCue.CrashCue'" +DefaultGearShiftSound="SoundWave'/Game/DReyeVR/Sounds/GearShift.GearShift'" +DefaultTurnSignalSound="SoundWave'/Game/DReyeVR/Sounds/TurnSignal.TurnSignal'" EgoVolumePercent=100 NonEgoVolumePercent=100 AmbientVolumePercent=20 @@ -115,10 +83,31 @@ FrameHeight=720 # resolution y for screenshot FrameDir="FrameCap" # directory name for screenshot FrameName="tick" # title of screenshot (differentiated via tick-suffix) +[CameraPose] +# starting pose should be one of: {DriversSeat, Front, BirdsEyeView, ThirdPerson} +StartingPose="DriversSeat" # starting position of camera in vehicle (on begin play) +# offsets from the EgoVehicle's bounding box positions if you need +Front=(X=1.1, Y=0.0, Z=0.3 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # front "license plate" view +BirdsEyeView=(X=0.0, Y=0.0, Z=15 | R=0.0, P=270.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # top down view +ThirdPerson=(X=-2, Y=0.0, Z=4 | R=0.0, P=330.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # back angled view + +[WheelFace] +# ABXY and Dpad buttons as custom-actors on the steering wheel face +EnableWheelButtons=True # enable dpad & ABXY indicator buttons on wheel face or not +ABXYLocation=(X=-7, Y=-10, Z=4) # location relative to steering wheel where the center of ABXY is +DpadLocation=(X=-7, Y=10, Z=4) # location relative to steering wheel where the center of Dpad is +QuadButtonSpread=2.0 # distance between the 4 buttons +# Autopilot status indicator (blue light) +EnableAutopilotIndicator=True # enable blue light indicator for autopilot status +AutopilotIndicatorLoc=(X=-7, Y=0, Z=4) # location relative to steering wheel for center of indicator +AutopilotIndicatorSize=0.03 # size of the indicator + # 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 +DeviceIdx=0 # Device index of the hardware (Logitech has 2, can be 0 or 1) +LogUpdates=False # whether or not to print debug messages +DeltaInputThreshold=0.02 # how much change the logi wheels need applied to overtake autopilot +ForceFeedbackMagnitude=30 # "Level of saturation" for the physical wheel actuation (0 to 100) # 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 diff --git a/Config/DefaultGame.ini b/Config/DefaultGame.ini index 00c38f8..ff84233 100644 --- a/Config/DefaultGame.ini +++ b/Config/DefaultGame.ini @@ -1,6 +1,6 @@ [/Script/EngineSettings.GeneralProjectSettings] ProjectID=675BF8694238308FA9368292CC440350 -ProjectName=CARLA UE4 +ProjectName=CARLA UE4 + DReyeVR CompanyName=CVC CopyrightNotice="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 ." ProjectVersion=0.9.13 @@ -67,8 +67,10 @@ bSkipEditorContent=False +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/Carla/Static/GenericMaterials/Licenseplates/Textures") +DirectoriesToAlwaysCook=(Path="/Game/DReyeVR") ++DirectoriesToAlwaysCook=(Path="/Game/DReyeVR/EgoVehicle/Extra") ++DirectoriesToAlwaysCook=(Path="/Carla/PostProcessingMaterials") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/OpenDrive") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/Nav") +DirectoriesToAlwaysStageAsUFS=(Path="Carla/Maps/TM") diff --git a/Config/EgoVehicles/Jeep.ini b/Config/EgoVehicles/Jeep.ini new file mode 100644 index 0000000..95eae1e --- /dev/null +++ b/Config/EgoVehicles/Jeep.ini @@ -0,0 +1,55 @@ +# Config for custom EgoVehicle +# Vehicle: Jeep Wrangler Rubicon + +# 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 + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/Jeep/BP_Jeep.BP_Jeep'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=-30, Y=-33.0, Z=145.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=30.0, Y=0.0, Z=125.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=30.0, Y=11.0, Z=120.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=30.0, Y=15.0, Z=125.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + +[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=20, Y=1.43, Z=158.0 | R=0.0, P=5.0, Y=13.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=-2.55, Y=0.0, Z=-2.2 | R=0.0, P=90.0, Y=0.0 | X=0.002, Y=0.006, Z=1.0) +RearScreenPercentage=85 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=32.0, Y=-78.0, Z=125.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=30.0, P=83, Y=22.5 | X=0.005, Y=0.003, Z=1.0) +LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=32.0, Y=78.0, Z=125.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=3.0 | R=340, P=90.0, Y=0 | X=0.005, Y=0.003, Z=1.0) +RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=True +InitLocation=(X=12.0, Y=-32.0, Z=112.0) # position of the steering wheel in the vehicle +InitRotation=(R=0.0, P=-15.0, Y=0.0) # tilt of the steering wheel at rest +MaxSteerAngleDeg=900 # max wheel rotation in degrees (pos and negative) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Config/EgoVehicles/Mustang66.ini b/Config/EgoVehicles/Mustang66.ini new file mode 100644 index 0000000..9ee87e6 --- /dev/null +++ b/Config/EgoVehicles/Mustang66.ini @@ -0,0 +1,55 @@ +# Config for custom EgoVehicle +# Vehicle: Mustang 1966 + +# 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 + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/Mustang66/BP_Mustang66.BP_Mustang66'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=-20.0, Y=-40.0, Z=110.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=60.0, Y=0.0, Z=90.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=60.0, Y=11.0, Z=85.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=60.0, Y=15.0, Z=90.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + +[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=10.0, Y=0.0, Z=120.0 | R=0.0, P=3.0, Y=20.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 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=22.0, Y=-88.0, Z=97 | R=0.0, P=0.0, Y=0.0 | X=0.9, Y=0.9, Z=0.9) +LeftReflectionTransform=(X=0, Y=0, Z=0.0 | R=43, P=86, Y=22 | X=0.003, Y=0.003, Z=1.0) +LeftScreenPercentage=65 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=-22, Y=87.7, Z=97 | R=0, P=-4, Y=2.79 | X=0.9, Y=0.9, Z=0.9) +RightReflectionTransform=(X=0.0, Y=0.0, Z=0 | R=-4.16, P=90.0, Y=18.4 | X=0.003, Y=0.003, Z=1.0) +RightScreenPercentage=50 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=True +InitLocation=(X=31.33, Y=-42.0, Z=76.8) # 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) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Config/EgoVehicles/TeslaM3.ini b/Config/EgoVehicles/TeslaM3.ini new file mode 100644 index 0000000..22699b4 --- /dev/null +++ b/Config/EgoVehicles/TeslaM3.ini @@ -0,0 +1,55 @@ +# Config for custom EgoVehicle +# Vehicle: Tesla Model 3 + +# 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 + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/TeslaM3/BP_TeslaM3.BP_TeslaM3'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=20.0, Y=-40.0, Z=120.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=180.0 | Y=0.0 | Z=70.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=110.0, Y=0.0, Z=105.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=110.0, Y=11.0, Z=100.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=110.0, Y=15.0, Z=105.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + +[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=2.0, Y=21.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 # 100 is max quality, 0 is minimum 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=27 | X=0.003, Y=0.005, Z=1.0) +LeftScreenPercentage=65 # 100 is max quality, 0 is minimum 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 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=True +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) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Config/EgoVehicles/Vespa.ini b/Config/EgoVehicles/Vespa.ini new file mode 100644 index 0000000..64459cc --- /dev/null +++ b/Config/EgoVehicles/Vespa.ini @@ -0,0 +1,56 @@ +# Config for custom EgoVehicle +# Vehicle: Vespa 2-wheeled vehicle + +# 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 + +[Blueprint] +# get this by right clicking on the item in the asset menu and select "Copy Reference" +Path="Blueprint'/Game/DReyeVR/EgoVehicle/Vespa/BP_Vespa.BP_Vespa'" + +[CameraPose] +# location & rotation of camera (root position) relative to vehicle (location units in cm, rotation in degrees) +DriversSeat=(X=-30.0, Y=0.0, Z=130.0 | R=0.0, P=0.0, Y=0.0 | X=1.0, Y=1.0, Z=1.0) # transform of first-person camera + +[Sounds] +EngineLocn=(X=0.0 | Y=0.0 | Z=30.0) # where is the engine in the Vehicle chassis + +[Dashboard] +SpeedometerEnabled=True +SpeedometerTransform=(X=40.0, Y=0.0, Z=119.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +TurnSignalsEnabled=True +TurnSignalsTransform=(X=30.0, Y=0.0, Z=126.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) +GearShifterEnabled=True +GearShifterTransform=(X=26.0, Y=0.0, Z=111.0 | R=0.0, P=0.0, Y=180.0 | X=1.0, Y=1.0, Z=1.0) + + +[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=False +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=0 # 100 is max quality, 0 is minimum quality +# left view side mirror +LeftMirrorEnabled=True +LeftMirrorTransform=(X=23.2, Y=-37.5, Z=118 | R=0.0, P=0.0, Y=-7 | X=1, Y=1, Z=1) +LeftReflectionTransform=(X=0.43, Y=0.17, Z=0.036 | R=43.2, P=90, Y=47.6 | X=0.003, Y=0.003, Z=1.0) +LeftScreenPercentage=100 # 100 is max quality, 0 is minimum quality +# right view side mirror +RightMirrorEnabled=True +RightMirrorTransform=(X=23.07, Y=37.5, Z=118.46 | R=0, P=-4, Y=2.79 | X=1, Y=1, Z=1) +RightReflectionTransform=(X=0.0, Y=0.0, Z=-0.78 | R=68, P=90.0, Y=75.6 | X=0.003, Y=0.003, Z=1.0) +RightScreenPercentage=100 # 100 is max quality, 0 is minimum quality + +[SteeringWheel] +Enabled=False +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) +SteeringScale=360 # scale with which to rotate the wheel (normalized [-1, 1] -> degrees) diff --git a/Content/DReyeVR/Custom/MirrorMaterial.uasset b/Content/DReyeVR/Custom/MirrorMaterial.uasset index 5b7ece0..42a0215 100644 Binary files a/Content/DReyeVR/Custom/MirrorMaterial.uasset and b/Content/DReyeVR/Custom/MirrorMaterial.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/BP_model3.uasset b/Content/DReyeVR/EgoVehicle/BP_model3.uasset deleted file mode 100644 index 6c169fe..0000000 Binary files a/Content/DReyeVR/EgoVehicle/BP_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/Extra/Tesla_Wheel_Plain.uasset b/Content/DReyeVR/EgoVehicle/Extra/Tesla_Wheel_Plain.uasset new file mode 100644 index 0000000..f720291 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Extra/Tesla_Wheel_Plain.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Jeep/BP_Jeep.uasset b/Content/DReyeVR/EgoVehicle/Jeep/BP_Jeep.uasset new file mode 100644 index 0000000..144f436 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Jeep/BP_Jeep.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Jeep/Mesh/A_Jeep.uasset b/Content/DReyeVR/EgoVehicle/Jeep/Mesh/A_Jeep.uasset new file mode 100644 index 0000000..e80d97e Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Jeep/Mesh/A_Jeep.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Jeep/Mesh/SK_Jeep.uasset b/Content/DReyeVR/EgoVehicle/Jeep/Mesh/SK_Jeep.uasset new file mode 100644 index 0000000..654879f Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Jeep/Mesh/SK_Jeep.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Jeep/Mesh/SM_Jeep.uasset b/Content/DReyeVR/EgoVehicle/Jeep/Mesh/SM_Jeep.uasset new file mode 100644 index 0000000..53707a8 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Jeep/Mesh/SM_Jeep.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Jeep/Mirrors/SM_Jeep_Mirror_Rear.uasset b/Content/DReyeVR/EgoVehicle/Jeep/Mirrors/SM_Jeep_Mirror_Rear.uasset new file mode 100644 index 0000000..34f30b4 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Jeep/Mirrors/SM_Jeep_Mirror_Rear.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Jeep/SteeringWheel/SM_Jeep_Wheel.uasset b/Content/DReyeVR/EgoVehicle/Jeep/SteeringWheel/SM_Jeep_Wheel.uasset new file mode 100644 index 0000000..8423315 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Jeep/SteeringWheel/SM_Jeep_Wheel.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/BP_Mustang66.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/BP_Mustang66.uasset new file mode 100644 index 0000000..9d63550 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/BP_Mustang66.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Anim_Mustang.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Anim_Mustang.uasset new file mode 100644 index 0000000..6cd08a9 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Anim_Mustang.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Physics_Mustang.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Physics_Mustang.uasset new file mode 100644 index 0000000..8fed986 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Physics_Mustang.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/SkeletalMesh_Mustang.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/SkeletalMesh_Mustang.uasset new file mode 100644 index 0000000..b6fe5ae Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/SkeletalMesh_Mustang.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Skeleton_Mustang.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Skeleton_Mustang.uasset new file mode 100644 index 0000000..3508b8f Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/Mesh/Skeleton_Mustang.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/Mirrors/SideMirror_Mustang.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/Mirrors/SideMirror_Mustang.uasset new file mode 100644 index 0000000..e509800 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/Mirrors/SideMirror_Mustang.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Mustang66/SteeringWheel/Mustang_Wheel.uasset b/Content/DReyeVR/EgoVehicle/Mustang66/SteeringWheel/Mustang_Wheel.uasset new file mode 100644 index 0000000..f205324 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Mustang66/SteeringWheel/Mustang_Wheel.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/BP_TeslaM3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/BP_TeslaM3.uasset new file mode 100644 index 0000000..ad733e7 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/BP_TeslaM3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Animation_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Animation_model3.uasset new file mode 100644 index 0000000..e945314 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Animation_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Physics_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Physics_model3.uasset new file mode 100644 index 0000000..4cb01ff Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Physics_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/SkeletalMesh_model3.uasset similarity index 95% rename from Content/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.uasset rename to Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/SkeletalMesh_model3.uasset index beeeace..ed08fea 100644 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mesh/SkeletalMesh_model3.uasset and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/SkeletalMesh_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Skeleton_model3.uasset similarity index 69% rename from Content/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.uasset rename to Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Skeleton_model3.uasset index 8fdc8dc..a9775ad 100644 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mesh/Skeleton_model3.uasset and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Skeleton_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/LeftMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/LeftMirror_model3.uasset new file mode 100644 index 0000000..de1e12c Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/LeftMirror_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RearMirror_Mesh_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RearMirror_Mesh_model3.uasset new file mode 100644 index 0000000..81bff90 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RearMirror_Mesh_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RearMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RearMirror_model3.uasset new file mode 100644 index 0000000..e5862a9 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RearMirror_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RightMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RightMirror_model3.uasset new file mode 100644 index 0000000..2b30612 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Mirrors/RightMirror_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/SteeringWheel/Wheel_StaticMesh_model3.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/SteeringWheel/Wheel_StaticMesh_model3.uasset new file mode 100644 index 0000000..190d7be Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/SteeringWheel/Wheel_StaticMesh_model3.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/TeslaM3/Tires/BP_DReyeVR_Front.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Tires/BP_DReyeVR_Front.uasset new file mode 100644 index 0000000..a211012 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/TeslaM3/Tires/BP_DReyeVR_Front.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Rear.uasset b/Content/DReyeVR/EgoVehicle/TeslaM3/Tires/BP_DReyeVR_Rear.uasset similarity index 53% rename from Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Rear.uasset rename to Content/DReyeVR/EgoVehicle/TeslaM3/Tires/BP_DReyeVR_Rear.uasset index 037f183..098db0e 100644 Binary files a/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Rear.uasset and b/Content/DReyeVR/EgoVehicle/TeslaM3/Tires/BP_DReyeVR_Rear.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Vespa/BP_Vespa.uasset b/Content/DReyeVR/EgoVehicle/Vespa/BP_Vespa.uasset new file mode 100644 index 0000000..821b054 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Vespa/BP_Vespa.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/Vespa/Mirrors/SideMirror_Vespa.uasset b/Content/DReyeVR/EgoVehicle/Vespa/Mirrors/SideMirror_Vespa.uasset new file mode 100644 index 0000000..ec84357 Binary files /dev/null and b/Content/DReyeVR/EgoVehicle/Vespa/Mirrors/SideMirror_Vespa.uasset differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.uasset deleted file mode 100644 index 5980c0c..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mesh/Animation_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.uasset deleted file mode 100644 index 2345b40..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mesh/Physics_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.uasset deleted file mode 100644 index b9aeecd..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mirrors/LeftMirror_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.uasset deleted file mode 100644 index c844223..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_Mesh_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.uasset deleted file mode 100644 index 68c3d83..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RearMirror_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.uasset deleted file mode 100644 index db5dea0..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Mirrors/RightMirror_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Physics_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Physics_model3.uasset deleted file mode 100644 index 2f193e2..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Physics_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_SkeletalMesh_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_SkeletalMesh_model3.uasset deleted file mode 100644 index 2a083a7..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_SkeletalMesh_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Skeleton_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Skeleton_model3.uasset deleted file mode 100644 index 383e73e..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_Skeleton_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.uasset b/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.uasset deleted file mode 100644 index 4f68a6c..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.uasset and /dev/null differ diff --git a/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Front.uasset b/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Front.uasset deleted file mode 100644 index dd3bf3a..0000000 Binary files a/Content/DReyeVR/EgoVehicle/model3/Tires/BP_DReyeVR_Front.uasset and /dev/null differ diff --git a/DReyeVR/ConfigFile.h b/DReyeVR/ConfigFile.h new file mode 100644 index 0000000..7c20580 --- /dev/null +++ b/DReyeVR/ConfigFile.h @@ -0,0 +1,334 @@ +#pragma once +#include // std::ifstream +#include // std::istream +#include // std::istringstream +#include +#include + +const static FString CarlaUE4Path = FPaths::ConvertRelativePathToFull(FPaths::ProjectDir()); + +struct ConfigFile +{ + ConfigFile() = default; // empty constructor (no params yet) + ConfigFile(const FString &Path, bool bVerbose = true) : FilePath(Path) + { + /// TODO: add feature to "hot-reload" new params during runtime + bSuccessfulUpdate = ReadFile(bVerbose); // ensures all the variables are updated upon construction + + // simple sanity check to ensure exporting and importing the same config file works as intended + // (exporting self and creating a new import should be equal to self) + static bool bSanityCheck = this->IsEqual(ConfigFile::Import(this->Export())); + ensureMsgf(bSanityCheck, TEXT("Sanity check for ConfigFile import/export failed!")); + } + + template bool Get(const FString &Section, const FString &Variable, T &Value) const + { + const std::string SectionStdStr(TCHAR_TO_UTF8(*Section)); + const std::string VariableStdStr(TCHAR_TO_UTF8(*Variable)); + return GetValue(SectionStdStr, VariableStdStr, Value); + } + + template T Get(const FString &Section, const FString &Variable) const + { + T Value; + /// TODO: implement exception when Get returns false? + Get(Section, Variable, Value); + return Value; + } + + template + T GetConstrained(const FString &Section, const FString &Variable, const std::unordered_set &Options, + const T &DefaultValue) const + { + T Value = Get(Section, Variable); + if (Options.find(Value) == Options.end()) + { + // not found within the constrained available options + Value = DefaultValue; + } + return Value; + } + + bool bIsValid() const + { + return bSuccessfulUpdate; + } + + bool IsEqual(const ConfigFile &Other, bool bPrintWarning = false) const + { + // calculates if A subset B and B subset A + return this->IsSubset(Other, bPrintWarning) && Other.IsSubset(*this, bPrintWarning); + } + + bool IsSubset(const ConfigFile &Other, bool bPrintWarning = false) const + { + // only checking that this is a perfect subset of Other + // => Other can contain data that this config does not have + // (if you want perfect equality, do A.CompareEqual(B) && B.CompareEqual(A)) + struct Comparison + { + Comparison(const std::string &Section, const std::string &Variable, const FString &Expected, + const FString &Other) + : SectionName(Section), VariableName(Variable), ThisValue(Expected), OtherValue(Other) + { + } + + Comparison(const std::string &Section, const std::string &Variable) + : SectionName(Section), VariableName(Variable), bIsMissing(true) + { + } + const std::string SectionName, VariableName; + const FString ThisValue, OtherValue; + const bool bIsMissing = false; + }; + std::vector Diff = {}; + for (const auto &SectionData : Sections) + { + const std::string &SectionName = SectionData.first; + const IniSection &Section = SectionData.second; + for (const auto &EntryData : Section.Entries) + { + const std::string &VariableName = EntryData.first; + const ParamString &Value = EntryData.second; + ParamString OtherValue; + if (Other.Find(SectionName, VariableName, OtherValue)) + { + // compare equality + if (!Value.DataStr.Equals(OtherValue.DataStr, ESearchCase::IgnoreCase)) + { + Diff.push_back({SectionName, VariableName, Value.DataStr, OtherValue.DataStr}); + } + } + else // did not find, missing + { + Diff.push_back({SectionName, VariableName}); + } + } + } + + bool bIsDifferent = (Diff.size() > 0); + // print differences + if (bPrintWarning && bIsDifferent) + { + LOG_WARN("Found config differences this {\"%s\"} and Other {\"%s\"}", *FilePath, *Other.FilePath); + for (const Comparison &Comp : Diff) + { + if (Comp.bIsMissing) + { + LOG_WARN("Missing [%s] \"%s\"", *FString(Comp.SectionName.c_str()), + *FString(Comp.VariableName.c_str())); + } + else + { + LOG_WARN("This [%s] \"%s\" {%s} does not match {%s}", *FString(Comp.SectionName.c_str()), + *FString(Comp.VariableName.c_str()), *Comp.ThisValue, *Comp.OtherValue); + } + } + } + return !bIsDifferent; + } + + void Insert(const ConfigFile &Other) + { + if (!Other.bIsValid()) + return; + FilePath += ";" + Other.FilePath; + if (Other.Sections.size() > 0) + Sections.insert(Other.Sections.begin(), Other.Sections.end()); + bSuccessfulUpdate = true; + } + + static ConfigFile Import(const std::string &Configuration) + { + // takes a flattened INI configuration file as parameter and reads it into a ConfigFile class + return ConfigFile(Configuration); + } + + std::string Export() const + { + std::ostringstream oss; + oss << std::endl + << "# This is an exported config file originally from \"" << TCHAR_TO_UTF8(*FilePath) << "\"" << std::endl + << std::endl; + for (const auto &SectionData : Sections) + { + const std::string &SectionName = SectionData.first; + const IniSection &Section = SectionData.second; + oss << "[" << SectionName << "]" << std::endl; // The overarching section first + for (const auto &EntryData : Section.Entries) + { + const std::string &VariableName = EntryData.first; + const ParamString &Data = EntryData.second; + const std::string DataUTF = TCHAR_TO_UTF8(*Data.DataStr); // convert to UTF-8 format + const std::string DataStdStr = Data.bHasQuotes ? "\"" + DataUTF + "\"" : DataUTF; + oss << VariableName << "=" << DataStdStr << std::endl; + } + oss << std::endl; + } + return oss.str(); + } + + private: + bool ReadFile(bool bVerbose) + { + check(!FilePath.IsEmpty()); + if (bVerbose) + { + LOG("Reading config from %s", *FilePath); + } + std::ifstream MatchingFile(TCHAR_TO_ANSI(*FilePath), std::ios::in); + if (MatchingFile) + { + return Update(MatchingFile); + } + LOG_ERROR("Unable to open the config file \"%s\"", *FilePath); + return false; + } + + bool Update(std::istream &InputStream) // reload the internally tracked table of params + { + /// performs a single pass over the config stream to collect all variables into Params + std::string Line; + std::string Section = ""; + while (std::getline(InputStream, Line)) + { + if (InputStream.bad()) // IO error + return false; + // std::string stdKey = std::string(TCHAR_TO_UTF8(*Key)); + if (Line[0] == '#' || Line[0] == ';') // ignore comments + continue; + std::istringstream iss_Line(Line); + if (Line[0] == '[') // test section + { + std::getline(iss_Line, Section, ']'); + Section = Section.substr(1); // skip leading '[' + continue; + } + std::string Key; + 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 + { + // ensure there is a section (create one if necesary) to store this key:value pair + if (Sections.find(Section) == Sections.end()) + { + Sections.insert({Section, IniSection(Section)}); + } + check(Sections.find(Section) != Sections.end()); + auto &CorrespondingSection = Sections.find(Section)->second; + CorrespondingSection.Entries.insert({Key, ParamString(Value)}); + } + } + } + return true; + } + + private: + struct ParamString + { + ParamString() = default; + ParamString(const std::string &Value) + { + DataStr = FString(Value.c_str()).TrimStartAndEnd().TrimQuotes(&bHasQuotes); + } + + FString DataStr = ""; // string representation of the data to parse into primitives + + 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); + } + bool bHasQuotes = false; + }; + + struct IniSection + { + IniSection(const std::string &SectionName) : SectionHeader(SectionName) + { + } + + std::string SectionHeader; // typically what is contained in [Sections] + std::unordered_map Entries; // everything else + }; + + private: + // construct a ConfigFile by passing in the entire contents of the config file (rather than the path to read) + ConfigFile(const std::string &ConfigurationContents) : FilePath("") + { + std::istringstream iss(ConfigurationContents); + bSuccessfulUpdate = Update(iss); + } + + // using std::string variant for internal use (FString for user-facing) + template bool GetValue(const std::string &SectionName, const std::string &VariableName, T &Value) const + { + ParamString Param; + bool bFound = Find(SectionName, VariableName, Param); + if (bFound) + Value = Param.DecipherToType(); + return bFound; + } + + bool Find(const std::string &SectionName, const std::string &VariableName, ParamString &Out) const + { + auto SectionIt = Sections.find(SectionName); + if (SectionIt == Sections.end()) + { + LOG_ERROR("No section in config file matches \"%s\"", *FString(SectionName.c_str())); + return false; + } + const IniSection &Section = SectionIt->second; + auto EntryIt = Section.Entries.find(VariableName); + if (EntryIt == Section.Entries.end()) + { + LOG_ERROR("No entry for \"%s\" in [%s] section found!", *FString(VariableName.c_str()), + *FString(SectionName.c_str())); + return false; + } + Out = EntryIt->second; + + // enable this for debug purposes + // LOG("Read [%s]\"%s\" -> %s", *FString(SectionName.c_str()), *FString(VariableName.c_str()), *Out.DataStr); + return true; // found successfully! + } + + private: + FString FilePath; // const except for overwrite + bool bSuccessfulUpdate = false; + std::unordered_map Sections; +}; + +static ConfigFile GeneralParams(FPaths::Combine(CarlaUE4Path, TEXT("Config/DReyeVRConfig.ini"))); diff --git a/DReyeVR/DReyeVRFactory.cpp b/DReyeVR/DReyeVRFactory.cpp index ca60c8e..6c58ebe 100644 --- a/DReyeVR/DReyeVRFactory.cpp +++ b/DReyeVR/DReyeVRFactory.cpp @@ -3,47 +3,58 @@ #include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // UActorBlueprintFunctionLibrary #include "Carla/Actor/VehicleParameters.h" // FVehicleParameters #include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode +#include "DReyeVRGameMode.h" // ADReyeVRGameMode +#include "DReyeVRUtils.h" // DReyeVRCategory #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); + for (const std::string &NameStdStr : VehicleTypes) + { + const FString Name = FString(NameStdStr.c_str()); + ConfigFile VehicleParams(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles"), Name + ".ini")); + FString BP_Path; + // make sure we can load the BP path and its nonempty (else construct a C++ EgoVehicle class) + if (VehicleParams.bIsValid() && VehicleParams.Get("Blueprint", "Path", BP_Path) && !BP_Path.IsEmpty()) + { + ConstructorHelpers::FObjectFinder BlueprintObject(*UE4RefToClassPath(BP_Path)); + BP_Classes.Add(Name, BlueprintObject.Object); + } + else + { + LOG_WARN("Unable to load custom EgoVehicle \"%s\"", *Name); + } + } } TArray ADReyeVRFactory::GetDefinitions() { - FActorDefinition EgoVehicleDef; + TArray Definitions; + + for (auto &BP_Class_pair : BP_Classes) { + FActorDefinition Def; FVehicleParameters Parameters; - Parameters.Model = "Model3"; - Parameters.ObjectType = EgoVehicleBP_Str; - Parameters.Class = AEgoVehicle::StaticClass(); + Parameters.Model = BP_Class_pair.Key; // vehicle type + /// TODO: BP_Path?? + Parameters.ObjectType = BP_Class_pair.Key; + Parameters.Class = BP_Class_pair.Value; + /// TODO: manage number of wheels? (though carla's 2-wheeled are just secret 4-wheeled) Parameters.NumberOfWheels = 4; - ADReyeVRFactory::MakeVehicleDefinition(Parameters, EgoVehicleDef); + ADReyeVRFactory::MakeVehicleDefinition(Parameters, Def); + Definitions.Add(Def); } FActorDefinition EgoSensorDef; { - const FString Id = "Ego_Sensor"; + const FString Id = "ego_sensor"; ADReyeVRFactory::MakeSensorDefinition(Id, EgoSensorDef); + Definitions.Add(EgoSensorDef); } - return {EgoVehicleDef, EgoSensorDef}; + return Definitions; } // copied and modified from UActorBlueprintFunctionLibrary @@ -60,7 +71,7 @@ FActorDefinition MakeGenericDefinition(const FString &Category, const FString &T 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 = MakeGenericDefinition(DReyeVRCategory, TEXT("DReyeVR_Vehicle"), Parameters.Model); Definition.Class = Parameters.Class; FActorAttribute ActorRole; @@ -90,7 +101,7 @@ void ADReyeVRFactory::MakeVehicleDefinition(const FVehicleParameters &Parameters void ADReyeVRFactory::MakeSensorDefinition(const FString &Id, FActorDefinition &Definition) { - Definition = MakeGenericDefinition(CATEGORY, TEXT("DReyeVR_Sensor"), Id); + Definition = MakeGenericDefinition(DReyeVRCategory, TEXT("DReyeVR_Sensor"), Id); Definition.Class = AEgoSensor::StaticClass(); } @@ -130,14 +141,27 @@ FActorSpawnResult ADReyeVRFactory::SpawnActor(const FTransform &SpawnAtTransform return SpawnedSingleton; }; - if (ActorDescription.Class == AEgoVehicle::StaticClass()) + if (UClass::FindCommonBase(ActorDescription.Class, AEgoVehicle::StaticClass()) == + AEgoVehicle::StaticClass()) // is EgoVehicle or derived class { - // check if an EgoVehicle already exists, if so, don't spawn another. + // see if this requested actor description is one of the available EgoVehicles /// NOTE: multi-ego-vehicle is not officially supported by DReyeVR, but it could be an interesting extension - SpawnedActor = SpawnSingleton(ActorDescription.Class, ActorDescription.Id, SpawnAtTransform, [&]() { - // EgoVehicle needs the special EgoVehicleBPClass since they depend on the EgoVehicle Blueprint - return World->SpawnActor(EgoVehicleBPClass, SpawnAtTransform, SpawnParameters); - }); + for (const auto &AvailableEgoVehicles : BP_Classes) + { + const FString &Name = AvailableEgoVehicles.Key; + if (ActorDescription.Id.ToLower().Contains(Name.ToLower())) // contains name + { + // check if an EgoVehicle already exists, if so, don't spawn another. + SpawnedActor = SpawnSingleton(ActorDescription.Class, ActorDescription.Id, SpawnAtTransform, [&]() { + auto *Class = AvailableEgoVehicles.Value; + return World->SpawnActor(Class, SpawnAtTransform, SpawnParameters); + }); + } + } + // update the GameMode's EgoVehicle in case it was spawned by someone else + auto *Game = Cast(UGameplayStatics::GetGameMode(World)); + if (Game != nullptr) + Game->SetEgoVehicle(Cast(SpawnedActor)); } else if (ActorDescription.Class == AEgoSensor::StaticClass()) { @@ -150,5 +174,10 @@ FActorSpawnResult ADReyeVRFactory::SpawnActor(const FTransform &SpawnAtTransform { LOG_ERROR("Unknown actor class in DReyeVR factory!"); } + + if (SpawnedActor == nullptr) + { + LOG_WARN("Unable to spawn DReyeVR actor (\"%s\")", *ActorDescription.Id) + } return FActorSpawnResult(SpawnedActor); } diff --git a/DReyeVR/DReyeVRFactory.h b/DReyeVR/DReyeVRFactory.h index c881686..554c0a8 100644 --- a/DReyeVR/DReyeVRFactory.h +++ b/DReyeVR/DReyeVRFactory.h @@ -4,6 +4,9 @@ #include "Carla/Actor/CarlaActorFactory.h" #include "Carla/Actor/VehicleParameters.h" +#include +#include + #include "DReyeVRFactory.generated.h" /// Factory in charge of spawning DReyeVR actors. @@ -22,5 +25,16 @@ class ADReyeVRFactory : public ACarlaActorFactory void MakeVehicleDefinition(const FVehicleParameters &Parameters, FActorDefinition &Definition); void MakeSensorDefinition(const FString &Id, FActorDefinition &Definition); - class UClass *EgoVehicleBPClass = nullptr; -}; + // place the names of all your new custom EgoVehicle types here: + /// IMPORTANT: make sure these match the ConfigFile AND Blueprint!! + // We expect Config/EgoVehicle/XYZ.ini and Content/DReyeVR/EgoVehicles/XYZ/BP_XYZ.uasset + const std::vector VehicleTypes = { + "TeslaM3", // Tesla Model 3 (Default) + "Mustang66", // Mustang66 + "Jeep", // JeepWranglerRubicon + "Vespa" // Vespa (2WheeledVehicles) + // add more here + }; + + TMap BP_Classes; +}; \ No newline at end of file diff --git a/DReyeVR/DReyeVRGameMode.cpp b/DReyeVR/DReyeVRGameMode.cpp index 1da988c..5406af8 100644 --- a/DReyeVR/DReyeVRGameMode.cpp +++ b/DReyeVR/DReyeVRGameMode.cpp @@ -53,17 +53,15 @@ ADReyeVRGameMode::ADReyeVRGameMode(FObjectInitializer const &FO) : Super(FO) }; // 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); + EgoVolumePercent = GeneralParams.Get("Sound", "EgoVolumePercent"); + NonEgoVolumePercent = GeneralParams.Get("Sound", "NonEgoVolumePercent"); + AmbientVolumePercent = GeneralParams.Get("Sound", "AmbientVolumePercent"); + bDoSpawnEgoVehicleTransform = GeneralParams.Get("Game", "DoSpawnEgoVehicleTransform"); + SpawnEgoVehicleTransform = GeneralParams.Get("Game", "SpawnEgoVehicleTransform"); // Recorder/replayer - ReadConfigValue("Replayer", "UseCarlaSpectator", bUseCarlaSpectator); - bool bEnableReplayInterpolation = false; - ReadConfigValue("Replayer", "ReplayInterpolation", bEnableReplayInterpolation); + bUseCarlaSpectator = GeneralParams.Get("Replayer", "UseCarlaSpectator"); + bool bEnableReplayInterpolation = GeneralParams.Get("Replayer", "ReplayInterpolation"); bReplaySync = !bEnableReplayInterpolation; // synchronous => no interpolation! } @@ -72,7 +70,7 @@ void ADReyeVRGameMode::BeginPlay() Super::BeginPlay(); // Initialize player - Player = UGameplayStatics::GetPlayerController(GetWorld(), 0); + GetPlayer(); // Can we tick? SetActorTickEnabled(false); // make sure we do not tick ourselves @@ -85,16 +83,27 @@ void ADReyeVRGameMode::BeginPlay() // spawn the DReyeVR pawn and possess it (first) SetupDReyeVRPawn(); + ensure(GetPawn() != nullptr); // Initialize the DReyeVR EgoVehicle and Sensor (second) - SetupEgoVehicle(); + if (GeneralParams.Get("Game", "AutomaticallySpawnEgo")) + { + SetupEgoVehicle(); + ensure(GetEgoVehicle() != nullptr); + } // Initialize DReyeVR spectator (third) SetupSpectator(); + ensure(GetSpectator() != nullptr); } void ADReyeVRGameMode::SetupDReyeVRPawn() { + if (DReyeVR_Pawn.IsValid()) + { + LOG("Not spawning new DReyeVR pawn"); + return; + } FActorSpawnParameters SpawnParams; SpawnParams.Owner = this; SpawnParams.SpawnCollisionHandlingOverride = ESpawnActorCollisionHandlingMethod::AlwaysSpawn; @@ -102,30 +111,37 @@ void ADReyeVRGameMode::SetupDReyeVRPawn() /// 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) + if (!DReyeVR_Pawn.IsValid()) { LOG_ERROR("Unable to spawn DReyeVR pawn!") } else { - DReyeVR_Pawn->BeginPlayer(Player); + DReyeVR_Pawn.Get()->BeginPlayer(GetPlayer()); LOG("Successfully spawned DReyeVR pawn"); } } +void ADReyeVRGameMode::SetEgoVehicle(AEgoVehicle *Ego) +{ + EgoVehiclePtr.Reset(); + EgoVehiclePtr = Ego; + check(EgoVehiclePtr.IsValid()); + ensure(GetPawn() != nullptr); // also respawn DReyeVR pawn if needed + // assign the (possibly new) EgoVehicle to the pawn + if (GetPawn() != nullptr) + { + DReyeVR_Pawn.Get()->BeginEgoVehicle(EgoVehiclePtr.Get(), GetWorld()); + } +} + bool ADReyeVRGameMode::SetupEgoVehicle() { - if (EgoVehiclePtr != nullptr || bDoSpawnEgoVehicle == false) + if (EgoVehiclePtr.IsValid()) { 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); @@ -148,37 +164,53 @@ bool ADReyeVRGameMode::SetupEgoVehicle() } // finalize the EgoVehicle by installing the DReyeVR_Pawn to control it - check(EgoVehiclePtr != nullptr); - return (EgoVehiclePtr != nullptr); + return (EgoVehiclePtr.IsValid()); } void ADReyeVRGameMode::SetupSpectator() { - if (bUseCarlaSpectator) - { // look for existing spectator in world - UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); - if (Episode != nullptr) - SpectatorPtr = Episode->GetSpectatorPawn(); - else if (Player != nullptr) - { - SpectatorPtr = Player->GetPawn(); - } + if (SpectatorPtr.IsValid()) + { + LOG("Not spawning new Spectator"); + return; } - // spawn if necessary - if (SpectatorPtr != nullptr) + // always disable the Carla spectator from DReyeVR use + UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); + APawn *CarlaSpectator = nullptr; + if (Episode != nullptr) { - LOG("Found available spectator in world"); + CarlaSpectator = Episode->GetSpectatorPawn(); + if (CarlaSpectator != nullptr) + CarlaSpectator->SetActorHiddenInGame(true); } - else + + // whether or not to use Carla spectator + if (bUseCarlaSpectator) + { + if (CarlaSpectator != nullptr) + SpectatorPtr = CarlaSpectator; + else if (GetPlayer() != nullptr) + SpectatorPtr = Player.Get()->GetPawn(); + } + + // spawn the Spectator pawn { LOG("Spawning DReyeVR Spectator Pawn in the world"); FVector SpawnLocn; FRotator SpawnRotn; - if (EgoVehiclePtr != nullptr) + if (EgoVehiclePtr.IsValid()) { - SpawnLocn = EgoVehiclePtr->GetCameraPosn(); - SpawnRotn = EgoVehiclePtr->GetCameraRot(); + SpawnLocn = EgoVehiclePtr.Get()->GetCameraPosn(); + SpawnRotn = EgoVehiclePtr.Get()->GetCameraRot(); + } + else + { + // spawn above the vehicle recommended spawn pt + FTransform RecommendedPt = GetSpawnPoint(); + SpawnLocn = RecommendedPt.GetLocation(); + SpawnLocn.Z += 10.f * 100.f; // up in the air 10m ish + SpawnRotn = RecommendedPt.Rotator(); } // create new spectator pawn FActorSpawnParameters SpawnParams; @@ -189,27 +221,57 @@ void ADReyeVRGameMode::SetupSpectator() SpawnLocn, SpawnRotn, SpawnParams); } - if (SpectatorPtr) + if (SpectatorPtr.IsValid()) { - SpectatorPtr->SetActorHiddenInGame(true); // make spectator invisible - SpectatorPtr->GetRootComponent()->DestroyPhysicsState(); // no physics (just no-clip) - SpectatorPtr->SetActorEnableCollision(false); // no collisions + SpectatorPtr.Get()->SetActorHiddenInGame(true); // make spectator invisible + SpectatorPtr.Get()->GetRootComponent()->DestroyPhysicsState(); // no physics (just no-clip) + SpectatorPtr.Get()->SetActorEnableCollision(false); // no collisions LOG("Successfully initiated spectator actor"); } + + // automatically possess the spectator ptr if no ego vehicle present! + if (!EgoVehiclePtr.IsValid()) + { + PossessSpectator(); + } +} + +APawn *ADReyeVRGameMode::GetSpectator() +{ + return SafePtrGet("Spectator", SpectatorPtr, [&](void) { SetupSpectator(); }); +} + +AEgoVehicle *ADReyeVRGameMode::GetEgoVehicle() +{ + return SafePtrGet("EgoVehicle", EgoVehiclePtr, [&](void) { SetupEgoVehicle(); }); +} + +APlayerController *ADReyeVRGameMode::GetPlayer() +{ + return SafePtrGet("Player", Player, + [&](void) { Player = GetWorld()->GetFirstPlayerController(); }); +} + +ADReyeVRPawn *ADReyeVRGameMode::GetPawn() +{ + return SafePtrGet("Pawn", DReyeVR_Pawn, [&](void) { SetupDReyeVRPawn(); }); } void ADReyeVRGameMode::BeginDestroy() { Super::BeginDestroy(); - if (DReyeVR_Pawn) - DReyeVR_Pawn->Destroy(); + if (DReyeVR_Pawn.IsValid()) + DReyeVR_Pawn.Get()->Destroy(); + DReyeVR_Pawn = nullptr; // release object and assign to null - if (EgoVehiclePtr) - EgoVehiclePtr->Destroy(); + if (EgoVehiclePtr.IsValid()) + EgoVehiclePtr.Get()->Destroy(); + EgoVehiclePtr = nullptr; - if (SpectatorPtr) - SpectatorPtr->Destroy(); + if (SpectatorPtr.IsValid()) + SpectatorPtr.Get()->Destroy(); + SpectatorPtr = nullptr; LOG("DReyeVRGameMode has been destroyed"); } @@ -229,11 +291,14 @@ void ADReyeVRGameMode::Tick(float DeltaSeconds) void ADReyeVRGameMode::SetupPlayerInputComponent() { + if (GetPlayer() == nullptr) + return; + check(Player.IsValid()); InputComponent = NewObject(this); InputComponent->RegisterComponent(); // set up gameplay key bindings check(InputComponent); - Player->PushInputComponent(InputComponent); // enable this InputComponent with the PlayerController + Player.Get()->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); @@ -249,98 +314,68 @@ void ADReyeVRGameMode::SetupPlayerInputComponent() 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 (GetEgoVehicle() == nullptr || GetPawn() == nullptr || GetPlayer() == nullptr) + return; + + check(EgoVehiclePtr.IsValid()); + check(DReyeVR_Pawn.IsValid()); + check(Player.IsValid()); + EgoVehiclePtr.Get()->SetAutopilot(false); - if (DReyeVR_Pawn == nullptr) + // check if already possessing EgoVehicle (DReyeVRPawn) + if (Player.Get()->GetPawn() == DReyeVR_Pawn.Get()) { - 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; - } + LOG("Already possessing EgoVehicle"); 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); + Player.Get()->Possess(DReyeVR_Pawn.Get()); + DReyeVR_Pawn.Get()->BeginEgoVehicle(EgoVehiclePtr.Get(), GetWorld()); } 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; - } - } + if (GetSpectator() == nullptr || GetPlayer() == nullptr) + return; - { // check if already possessing spectator - ensure(Player != nullptr); - if (Player->GetPawn() == SpectatorPtr) - { - LOG("Already possessing Spectator"); - return; - } + check(SpectatorPtr.IsValid()); + check(Player.IsValid()); + + // check if already possessing spectator + if (Player.Get()->GetPawn() == SpectatorPtr.Get()) + { + LOG("Already possessing Spectator"); + return; } - if (EgoVehiclePtr) + if (EgoVehiclePtr.IsValid()) { // spawn from EgoVehicle head position - const FVector &EgoLocn = EgoVehiclePtr->GetCameraPosn(); - const FRotator &EgoRotn = EgoVehiclePtr->GetCameraRot(); - SpectatorPtr->SetActorLocationAndRotation(EgoLocn, EgoRotn); + const FVector &EgoLocn = EgoVehiclePtr.Get()->GetCameraPosn(); + const FRotator &EgoRotn = EgoVehiclePtr.Get()->GetCameraRot(); + SpectatorPtr.Get()->SetActorLocationAndRotation(EgoLocn, EgoRotn); } // repossess the ego vehicle - Player->Possess(SpectatorPtr); + Player.Get()->Possess(SpectatorPtr.Get()); 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; - } - } + if (GetEgoVehicle() == nullptr) + return; + + check(EgoVehiclePtr.IsValid()); { // check if autopilot already enabled - if (EgoVehiclePtr->GetAutopilotStatus() == true) + if (EgoVehiclePtr.Get()->GetAutopilotStatus() == true) { LOG("EgoVehicle autopilot already on"); return; } } - EgoVehiclePtr->SetAutopilot(true); + EgoVehiclePtr.Get()->SetAutopilot(true); LOG("Enabling EgoVehicle Autopilot"); } @@ -445,7 +480,7 @@ void ADReyeVRGameMode::SetupReplayer() Replayer->SetSyncMode(bReplaySync); if (bReplaySync) { - LOG_WARN("Replay operating in frame-wise (1:1) synchronous mode (no replay interpolation)"); + LOG("Replay operating in frame-wise (1:1) synchronous mode (no replay interpolation)"); } bRecorderInitiated = true; } @@ -476,7 +511,7 @@ void ADReyeVRGameMode::DrawBBoxes() BBox->Activate(); BBox->MaterialParams.Opacity = 0.1f; FLinearColor Col = FLinearColor::Green; - if (FVector::Distance(EgoVehiclePtr->GetActorLocation(), A->GetActorLocation()) < DistThresh * 100.f) + if (FVector::Distance(GetEgoVehicle()->GetActorLocation(), A->GetActorLocation()) < DistThresh * 100.f) { Col = FLinearColor::Red; } @@ -487,7 +522,7 @@ void ADReyeVRGameMode::DrawBBoxes() 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 + // divide by 100 to get from cm to m, 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 @@ -557,7 +592,7 @@ void ADReyeVRGameMode::SpawnEgoVehicle(const FTransform &SpawnPt) { UCarlaEpisode *Episode = UCarlaStatics::GetCurrentEpisode(GetWorld()); check(Episode != nullptr); - FActorDefinition EgoVehicleDefn = FindDefnInRegistry(Episode, AEgoVehicle::StaticClass()); + FActorDefinition EgoVehicleDefn = FindEgoVehicleDefinition(Episode); FActorDescription DReyeVRDescr; { // create a Description from the Definition to spawn the actor DReyeVRDescr.UId = EgoVehicleDefn.UId; diff --git a/DReyeVR/DReyeVRGameMode.h b/DReyeVR/DReyeVRGameMode.h index 058b5d8..53818dd 100644 --- a/DReyeVR/DReyeVRGameMode.h +++ b/DReyeVR/DReyeVRGameMode.h @@ -3,12 +3,13 @@ #include "Carla/Actor/DReyeVRCustomActor.h" // ADReyeVRCustomActor #include "Carla/Game/CarlaGameModeBase.h" // ACarlaGameModeBase #include "Carla/Sensor/DReyeVRData.h" // DReyeVR:: +#include "DReyeVRPawn.h" // ADReyeVRPawn +#include "DReyeVRUtils.h" // SafePtrGet #include // std::unordered_map #include "DReyeVRGameMode.generated.h" class AEgoVehicle; -class ADReyeVRPawn; UCLASS() class ADReyeVRGameMode : public ACarlaGameModeBase @@ -24,15 +25,12 @@ class ADReyeVRGameMode : public ACarlaGameModeBase virtual void Tick(float DeltaSeconds) override; - ADReyeVRPawn *GetPawn() - { - return DReyeVR_Pawn; - } + APawn *GetSpectator(); + AEgoVehicle *GetEgoVehicle(); + APlayerController *GetPlayer(); + ADReyeVRPawn *GetPawn(); - void SetEgoVehicle(AEgoVehicle *Vehicle) - { - EgoVehiclePtr = Vehicle; - } + void SetEgoVehicle(AEgoVehicle *Ego); // input handling void SetupPlayerInputComponent(); @@ -64,20 +62,21 @@ class ADReyeVRGameMode : public ACarlaGameModeBase 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; + + // TWeakObjectPtr's allow us to check if the underlying object is alive + // in case it was destroyed by someone other than us (ex. garbage collection) + TWeakObjectPtr Player; + TWeakObjectPtr DReyeVR_Pawn; + TWeakObjectPtr SpectatorPtr; + TWeakObjectPtr EgoVehiclePtr; // for toggling bw spectator mode bool bIsSpectating = true; - class APawn *SpectatorPtr = nullptr; - class AEgoVehicle *EgoVehiclePtr = nullptr; // for audio control float EgoVolumePercent; diff --git a/DReyeVR/DReyeVRPawn.cpp b/DReyeVR/DReyeVRPawn.cpp index 2be078c..655e5ea 100644 --- a/DReyeVR/DReyeVRPawn.cpp +++ b/DReyeVR/DReyeVRPawn.cpp @@ -1,5 +1,6 @@ #include "DReyeVRPawn.h" #include "DReyeVRUtils.h" // CreatePostProcessingEffect +#include "EgoVehicle.h" // AEgoVehicle #include "HeadMountedDisplayFunctionLibrary.h" // SetTrackingOrigin, GetWorldToMetersScale #include "HeadMountedDisplayTypes.h" // ESpectatorScreenMode #include "Materials/MaterialInstanceDynamic.h" // UMaterialInstanceDynamic @@ -30,26 +31,28 @@ ADReyeVRPawn::ADReyeVRPawn(const FObjectInitializer &ObjectInitializer) : Super( void ADReyeVRPawn::ReadConfigVariables() { // camera - ReadConfigValue("CameraParams", "FieldOfView", FieldOfView); + GeneralParams.Get("CameraParams", "FieldOfView", FieldOfView); /// NOTE: all the postprocessing params are used in DReyeVRUtils::CreatePostProcessingParams // input scaling - ReadConfigValue("VehicleInputs", "InvertMouseY", InvertMouseY); - ReadConfigValue("VehicleInputs", "ScaleMouseY", ScaleMouseY); - ReadConfigValue("VehicleInputs", "ScaleMouseX", ScaleMouseX); + GeneralParams.Get("VehicleInputs", "InvertMouseY", InvertMouseY); + GeneralParams.Get("VehicleInputs", "ScaleMouseY", ScaleMouseY); + GeneralParams.Get("VehicleInputs", "ScaleMouseX", ScaleMouseX); // HUD - ReadConfigValue("EgoVehicleHUD", "HUDScaleVR", HUDScaleVR); - ReadConfigValue("EgoVehicleHUD", "DrawFPSCounter", bDrawFPSCounter); - ReadConfigValue("EgoVehicleHUD", "DrawFlatReticle", bDrawFlatReticle); - ReadConfigValue("EgoVehicleHUD", "ReticleSize", ReticleSize); - ReadConfigValue("EgoVehicleHUD", "DrawGaze", bDrawGaze); - ReadConfigValue("EgoVehicleHUD", "DrawSpectatorReticle", bDrawSpectatorReticle); - ReadConfigValue("EgoVehicleHUD", "EnableSpectatorScreen", bEnableSpectatorScreen); + GeneralParams.Get("EgoVehicleHUD", "HUDScaleVR", HUDScaleVR); + GeneralParams.Get("EgoVehicleHUD", "DrawFPSCounter", bDrawFPSCounter); + GeneralParams.Get("EgoVehicleHUD", "DrawFlatReticle", bDrawFlatReticle); + GeneralParams.Get("EgoVehicleHUD", "ReticleSize", ReticleSize); + GeneralParams.Get("EgoVehicleHUD", "DrawGaze", bDrawGaze); + GeneralParams.Get("EgoVehicleHUD", "DrawSpectatorReticle", bDrawSpectatorReticle); + GeneralParams.Get("EgoVehicleHUD", "EnableSpectatorScreen", bEnableSpectatorScreen); // wheel hardware - ReadConfigValue("Hardware", "DeviceIdx", WheelDeviceIdx); - ReadConfigValue("Hardware", "LogUpdates", bLogLogitechWheel); + GeneralParams.Get("Hardware", "DeviceIdx", WheelDeviceIdx); + GeneralParams.Get("Hardware", "LogUpdates", bLogLogitechWheel); + GeneralParams.Get("Hardware", "ForceFeedbackMagnitude", SaturationPercentage); + GeneralParams.Get("Hardware", "DeltaInputThreshold", LogiThresh); } void ADReyeVRPawn::ConstructCamera() @@ -180,20 +183,30 @@ void ADReyeVRPawn::InitReticleTexture() void ADReyeVRPawn::InitSpectator() { - if (bIsHMDConnected) + if (!bIsHMDConnected) + return; + // see https://docs.unrealengine.com/4.26/en-US/SharingAndReleasing/XRDevelopment/VR/DevelopVR/VRSpectatorScreen/ + auto SpectatorScreenMode = ESpectatorScreenMode::Disabled; // black window + if (bEnableSpectatorScreen) { - if (bEnableSpectatorScreen) + // draws the left eye view cropped to the entire window + SpectatorScreenMode = ESpectatorScreenMode::SingleEyeCroppedToFill; + if (bDrawSpectatorReticle) { InitReticleTexture(); // generate array of pixel values - check(ReticleTexture); - UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenMode(ESpectatorScreenMode::TexturePlusEye); - UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenTexture(ReticleTexture); - } - else - { - UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenMode(ESpectatorScreenMode::Disabled); + if (ReticleTexture != nullptr) + { + // draws the full screen view of the left eye (same as SingleEyeCroppedToFill) plus a texture overlaid + SpectatorScreenMode = ESpectatorScreenMode::TexturePlusEye; + UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenTexture(ReticleTexture); + } + else + { + LOG_ERROR("Reticle texture is null! Unable to use for spectator screen"); + } } } + UHeadMountedDisplayFunctionLibrary::SetSpectatorScreenMode(SpectatorScreenMode); } void ADReyeVRPawn::TickSpectatorScreen(float DeltaSeconds) @@ -482,6 +495,7 @@ void ADReyeVRPawn::LogitechWheelUpdate() if (LogiUpdate() == false) // update the logitech wheel LOG_WARN("Logitech wheel %d failed to update!", WheelDeviceIdx); DIJOYSTATE2 *WheelState = LogiGetState(WheelDeviceIdx); + ensure(WheelState != nullptr); if (bLogLogitechWheel) LogLogitechPluginStruct(WheelState); /// NOTE: obtained these from LogitechWheelInputDevice.cpp:~111 @@ -494,8 +508,6 @@ void ADReyeVRPawn::LogitechWheelUpdate() // -1 = not pressed. 0 = Top. 0.25 = Right. 0.5 = Bottom. 0.75 = Left. const float Dpad = fabs(((WheelState->rgdwPOV[0] - 32767.0f) / (65535.0f))); - const float LogiThresh = 0.01f; // threshold for analog input "equality" - // weird behaviour: "Pedals will output a value of 0.5 until the wheel/pedals receive any kind of input" // as per https://github.com/HARPLab/LogitechWheelPlugin if (bPedalsDefaulting) @@ -518,13 +530,19 @@ void ADReyeVRPawn::LogitechWheelUpdate() FMath::IsNearlyEqual(BrakePedal, BrakePedalLast, LogiThresh))) { // let the autopilot drive if the user is not putting significant inputs + // ie. if their inputs are close enough to what was previously input + /// TODO: this system might break down if the autopilot is putting in sufficiently + /// strong inputs, since the autopilot controls might might inadvertently + /// be considered as human-input controls which amplifies the input and + /// causes a positive cycle loop (which would be better avoided) } else { - // take over the vehicle control completely - EgoVehicle->SetSteering(WheelRotation); - EgoVehicle->SetThrottle(AccelerationPedal); - EgoVehicle->SetBrake(BrakePedal); + // driver has issued sufficient input to warrant manual takeover (disables autopilot) + EgoVehicle->SetAutopilot(false); + EgoVehicle->AddSteering(WheelRotation); + EgoVehicle->AddThrottle(AccelerationPedal); + EgoVehicle->AddBrake(BrakePedal); } } // save the last values for the wheel & pedals @@ -532,38 +550,53 @@ void ADReyeVRPawn::LogitechWheelUpdate() AccelerationPedalLast = AccelerationPedal; BrakePedalLast = BrakePedal; - // Button presses (turn signals, reverse) - if (WheelState->rgbButtons[0] || WheelState->rgbButtons[1] || // Any of the 4 face pads - WheelState->rgbButtons[2] || WheelState->rgbButtons[3]) + ManageButtonPresses(*WheelState); +} + +void ADReyeVRPawn::ManageButtonPresses(const DIJOYSTATE2 &WheelState) +{ + const bool bABXY_A = static_cast(WheelState.rgbButtons[0]); + const bool bABXY_B = static_cast(WheelState.rgbButtons[2]); + const bool bABXY_X = static_cast(WheelState.rgbButtons[1]); + const bool bABXY_Y = static_cast(WheelState.rgbButtons[3]); + + if (bABXY_A || bABXY_B || bABXY_X || bABXY_Y) EgoVehicle->PressReverse(); else EgoVehicle->ReleaseReverse(); - if (WheelState->rgbButtons[4]) + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_A, bABXY_A); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_B, bABXY_B); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_X, bABXY_X); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_ABXY_Y, bABXY_Y); + + bool bTurnSignalR = static_cast(WheelState.rgbButtons[4]); + bool bTurnSignalL = static_cast(WheelState.rgbButtons[5]); + + if (bTurnSignalR) EgoVehicle->PressTurnSignalR(); else EgoVehicle->ReleaseTurnSignalR(); - if (WheelState->rgbButtons[5]) + if (bTurnSignalL) EgoVehicle->PressTurnSignalL(); else EgoVehicle->ReleaseTurnSignalL(); - // if (WheelState->rgbButtons[23]) // big red button on right side of g923 - - // EgoVehicle VRCamerRoot base position adjustment - if (WheelState->rgdwPOV[0] == 0) // positive in X - EgoVehicle->CameraFwd(); - else if (WheelState->rgdwPOV[0] == 18000) // negative in X - EgoVehicle->CameraBack(); - else if (WheelState->rgdwPOV[0] == 9000) // positive in Y - EgoVehicle->CameraRight(); - else if (WheelState->rgdwPOV[0] == 27000) // negative in Y - EgoVehicle->CameraLeft(); - else if (WheelState->rgbButtons[19]) // positive in Z - EgoVehicle->CameraUp(); - else if (WheelState->rgbButtons[20]) // negative in Z - EgoVehicle->CameraDown(); + // if (WheelState.rgbButtons[23]) // big red button on right side of g923 + + const bool bDPad_Up = (WheelState.rgdwPOV[0] == 0); + const bool bDPad_Right = (WheelState.rgdwPOV[0] == 9000); + const bool bDPad_Down = (WheelState.rgdwPOV[0] == 18000); + const bool bDPad_Left = (WheelState.rgdwPOV[0] == 27000); + const bool bPositive = static_cast(WheelState.rgbButtons[19]); + const bool bNegative = static_cast(WheelState.rgbButtons[20]); + + EgoVehicle->CameraPositionAdjust(bDPad_Up, bDPad_Right, bDPad_Down, bDPad_Left, bPositive, bNegative); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Up, bDPad_Up); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Right, bDPad_Right); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Left, bDPad_Left); + EgoVehicle->UpdateWheelButton(EgoVehicle->Button_DPad_Down, bDPad_Down); } void ADReyeVRPawn::ApplyForceFeedback() const @@ -571,12 +604,14 @@ void ADReyeVRPawn::ApplyForceFeedback() const check(EgoVehicle); // only execute this in Windows, the Logitech plugin is incompatible with Linux - const float Speed = EgoVehicle->GetVelocity().Size(); // get magnitude of self (AActor's) velocity + // const float Speed = EgoVehicle->GetVelocity().Size(); // get magnitude of self (AActor's) velocity /// TODO: move outside this function (in tick()) to avoid redundancy if (bIsLogiConnected && LogiHasForceFeedback(WheelDeviceIdx)) { - const int OffsetPercentage = 0; // "Specifies the center of the spring force effect" - const int SaturationPercentage = 30; // "Level of saturation... comparable to a magnitude" + // actuate the logi wheel to match the autopilot steering + float RawWheel = EgoVehicle->GetWheelSteerAngle(EVehicleWheelLocation::Front_Wheel); + // "Specifies the center of the spring force effect" + const int OffsetPercentage = static_cast(RawWheel * 0.5f); const int CoeffPercentage = 100; // "Slope of the effect strength increase relative to deflection from Offset" LogiPlaySpringForce(WheelDeviceIdx, OffsetPercentage, SaturationPercentage, CoeffPercentage); } @@ -616,10 +651,6 @@ void ADReyeVRPawn::SetupPlayerInputComponent(UInputComponent *PlayerInputCompone check(InputComponent); /// NOTE: an Action is a digital input, an Axis is an analog input - // steering and throttle analog inputs (axes) - PlayerInputComponent->BindAxis("Steer_DReyeVR", this, &ADReyeVRPawn::SetSteeringKbd); - PlayerInputComponent->BindAxis("Throttle_DReyeVR", this, &ADReyeVRPawn::SetThrottleKbd); - PlayerInputComponent->BindAxis("Brake_DReyeVR", this, &ADReyeVRPawn::SetBrakeKbd); /// Mouse X and Y input for looking up and turning PlayerInputComponent->BindAxis("MouseLookUp_DReyeVR", this, &ADReyeVRPawn::MouseLookUp); PlayerInputComponent->BindAxis("MouseTurn_DReyeVR", this, &ADReyeVRPawn::MouseTurn); @@ -631,6 +662,10 @@ void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputCom // this function sets up the direct relay mechanisms to call EgoVehicle input functions check(PlayerInputComponent != nullptr); check(EV != nullptr); + // steering and throttle analog inputs (axes) + PlayerInputComponent->BindAxis("Steer_DReyeVR", EV, &AEgoVehicle::AddSteering); + PlayerInputComponent->BindAxis("Throttle_DReyeVR", EV, &AEgoVehicle::AddThrottle); + PlayerInputComponent->BindAxis("Brake_DReyeVR", EV, &AEgoVehicle::AddBrake); // button actions (press & release) PlayerInputComponent->BindAction("ToggleReverse_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressReverse); PlayerInputComponent->BindAction("ToggleReverse_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseReverse); @@ -638,8 +673,6 @@ void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputCom PlayerInputComponent->BindAction("TurnSignalLeft_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseTurnSignalL); PlayerInputComponent->BindAction("TurnSignalLeft_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressTurnSignalL); PlayerInputComponent->BindAction("TurnSignalRight_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseTurnSignalR); - PlayerInputComponent->BindAction("HoldHandbrake_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressHandbrake); - PlayerInputComponent->BindAction("HoldHandbrake_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseHandbrake); // camera view adjustments PlayerInputComponent->BindAction("NextCameraView_DReyeVR", IE_Pressed, EV, &AEgoVehicle::PressNextCameraView); PlayerInputComponent->BindAction("NextCameraView_DReyeVR", IE_Released, EV, &AEgoVehicle::ReleaseNextCameraView); @@ -657,45 +690,6 @@ void ADReyeVRPawn::SetupEgoVehicleInputComponent(UInputComponent *PlayerInputCom PlayerInputComponent->BindAction("CameraDown_DReyeVR", IE_Pressed, EV, &AEgoVehicle::CameraDown); } -#define CHECK_EGO_VEHICLE(FUNCTION) \ - if (EgoVehicle) \ - FUNCTION; \ - else \ - LOG_ERROR("EgoVehicle is NULL!"); - -void ADReyeVRPawn::SetThrottleKbd(const float ThrottleInput) -{ - if (ThrottleInput != 0) - { - bOverrideInputsWithKbd = true; - CHECK_EGO_VEHICLE(EgoVehicle->SetThrottle(ThrottleInput)) - } -} - -void ADReyeVRPawn::SetBrakeKbd(const float BrakeInput) -{ - if (BrakeInput != 0) - { - bOverrideInputsWithKbd = true; - CHECK_EGO_VEHICLE(EgoVehicle->SetBrake(BrakeInput)) - } -} - -void ADReyeVRPawn::SetSteeringKbd(const float SteeringInput) -{ - if (SteeringInput != 0) - { - bOverrideInputsWithKbd = true; - CHECK_EGO_VEHICLE(EgoVehicle->SetSteering(SteeringInput)) - } - else - { - // so the steering wheel does go to 0 when letting go - if (EgoVehicle != nullptr) - EgoVehicle->VehicleInputs.Steering = 0; - } -} - /// ========================================== /// /// -----------------:INPUT:------------------ /// /// ========================================== /// diff --git a/DReyeVR/DReyeVRPawn.h b/DReyeVR/DReyeVRPawn.h index 6c8fd51..f0153e7 100644 --- a/DReyeVR/DReyeVRPawn.h +++ b/DReyeVR/DReyeVRPawn.h @@ -1,7 +1,6 @@ #pragma once #include "Camera/CameraComponent.h" // UCameraComponent -#include "EgoVehicle.h" // AEgoVehicle #include "Engine/Scene.h" // FPostProcessSettings #include "GameFramework/Pawn.h" // CreatePlayerInputComponent @@ -17,6 +16,8 @@ #include "DReyeVRPawn.generated.h" +class AEgoVehicle; + UCLASS() class ADReyeVRPawn : public APawn { @@ -125,12 +126,15 @@ class ADReyeVRPawn : public APawn void TickLogiWheel(); void DestroyLogiWheel(bool DestroyModule); bool bLogLogitechWheel = false; - int WheelDeviceIdx = 0; // usually leaving as 0 is fine, only use 1 if 0 is taken + float LogiThresh = 0.02f; // threshold for change needed to overtake AI controls + int SaturationPercentage = 30; // "Level of saturation... comparable to a magnitude" + int WheelDeviceIdx = 0; // usually leaving as 0 is fine, only use 1 if 0 is taken #if USE_LOGITECH_PLUGIN struct DIJOYSTATE2 *Old = nullptr; // global "old" struct for the last state void LogLogitechPluginStruct(const struct DIJOYSTATE2 *Now); - void LogitechWheelUpdate(); // for logitech wheel integration - void ApplyForceFeedback() const; // for logitech wheel integration + void LogitechWheelUpdate(); // for logitech wheel integration + void ManageButtonPresses(const DIJOYSTATE2 &WheelState); // for managing button presses + void ApplyForceFeedback() const; // for logitech wheel integration float WheelRotationLast, AccelerationPedalLast, BrakePedalLast; #endif bool bIsLogiConnected = false; // check if Logi device is connected (on BeginPlay) diff --git a/DReyeVR/DReyeVRUtils.h b/DReyeVR/DReyeVRUtils.h index ba7181b..15ab659 100644 --- a/DReyeVR/DReyeVRUtils.h +++ b/DReyeVR/DReyeVRUtils.h @@ -2,149 +2,101 @@ #define DREYEVR_UTIL #include "Carla/Sensor/ShaderBasedSensor.h" // FSensorShader +#include "ConfigFile.h" // ConfigFile class #include "CoreMinimal.h" #include "Engine/Texture2D.h" // UTexture2D #include "HighResScreenshot.h" // FHighResScreenshotConfig #include "ImageWriteQueue.h" // TImagePixelData #include "ImageWriteTask.h" // FImageWriteTask #include // CityScapesPalette -#include // std::ifstream -#include // std::istringstream -#include -#include -/// this is the file where we'll read all DReyeVR specific configs -static const FString ConfigFilePath = - FPaths::Combine(FPaths::ConvertRelativePathToFull(FPaths::ProjectDir()), TEXT("Config"), TEXT("DReyeVRConfig.ini")); +// 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.*") +static const FString DReyeVRCategory("HarpLab"); -struct ParamString +template +T *SafePtrGet(const FString &Name, TWeakObjectPtr &Ptr, const std::function &RemedyFunction) { - 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); + if (Ptr.IsValid()) + return Ptr.Get(); + // object was destroyed! possibly by external process (ex. map change) + if (!Ptr.IsExplicitlyNull()) + { // dangling pointer!! + LOG_WARN("Dangling pointer \"%s\" (%p) is invalid! Attempting to remedy", Ptr.Get(), *Name); } + RemedyFunction(); + // try to remedy + if (Ptr.IsValid()) + return Ptr.Get(); + LOG_ERROR("Unable to remedy (%s)", *Name); + return nullptr; +} - 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) +static FString UE4RefToClassPath(const FString &UE4ReferencePath) { - return Section + "/" + Variable; // encoding the variable alongside its section + // converts (reference) strings of the type "Type'/Game/PATH/asset.asset'" to "/Game/PATH/asset.asset_C" + // for use in ConstructorHelpers::FClassFinder + const FString NoneStr = FString(""); // replace with empty string ("") + const FString SingleQuoteStr = FString("'"); + // find the start position in the string (ignore the type (Blueprint, SkeletalMesh, Skeleton, AnimBP, etc.)) + const int StartPos = UE4ReferencePath.Find(SingleQuoteStr, ESearchCase::CaseSensitive, ESearchDir::FromStart, 0); + FString Ret = UE4ReferencePath.RightChop(StartPos); + Ret.ReplaceInline(*SingleQuoteStr, *NoneStr, ESearchCase::CaseSensitive); + Ret += "_C"; // to force class type suffix + return Ret; } -static std::string CreateVariableName(const FString &Section, const FString &Variable) + +static FString CleanNameForDReyeVR(const FString &RawName) { - return CreateVariableName(std::string(TCHAR_TO_UTF8(*Section)), std::string(TCHAR_TO_UTF8(*Variable))); + // should be equivalent to GetClass()->GetDisplayNameText().ToString() + // for our purposes (spawning different type EgoVehicles) + FString CleanName = RawName; + CleanName.RemoveSpacesInline(); // one word +#define DELETE_INLINE(x) CleanName.ReplaceInline(*FString(x), *FString(""), ESearchCase::CaseSensitive); + DELETE_INLINE("BP_"); // might start w/ BP_XYZ + DELETE_INLINE("BP"); // might start w/ BPXYZ + DELETE_INLINE("_C"); // might end with _C + DELETE_INLINE("Ego"); // default object is EgoVehicle + DELETE_INLINE("SKEL_"); // skeleton class starts with SKEL_ + + return CleanName; } -static void ReadDReyeVRConfig() +static FActorDefinition FindDefnInRegistry(const UCarlaEpisode *Episode, const UClass *ClassType) { - /// TODO: add feature to "hot-reload" new params during runtime - 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) + // 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()) { - std::string Line; - std::string Section = ""; - while (std::getline(ConfigFile, Line)) + if (Defn.Class == ClassType) { - // std::string stdKey = std::string(TCHAR_TO_UTF8(*Key)); - if (Line[0] == '#' || Line[0] == ';') // ignore comments - continue; - std::istringstream iss_Line(Line); - if (Line[0] == '[') // test section - { - std::getline(iss_Line, Section, ']'); - Section = Section.substr(1); // skip leading '[' - continue; - } - std::string Key; - 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 - { - std::string VariableName = CreateVariableName(Section, Key); - bool bHasQuotes = false; - Params[VariableName].DataStr = FString(Value.c_str()).TrimStartAndEnd().TrimQuotes(&bHasQuotes); - } - } + 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 + if (!bFoundDef) { - LOG_ERROR("Unable to open the config file %s", *ConfigFilePath); + LOG_ERROR("Unable to find appropriate definition in registry!"); } - // for (auto &e : Params){ - // LOG_WARN("%s: %s", *FString(e.first.c_str()), *e.second); - // } -} - -static void EnsureConfigsUpdated() -{ - // used to ensure the configs file has been read and contents updated - if (Params.size() == 0) - ReadDReyeVRConfig(); + return FoundDefinition; } -template static void ReadConfigValue(const FString &Section, const FString &Variable, T &Value) +static FActorDefinition FindEgoVehicleDefinition(const UCarlaEpisode *Episode) { - EnsureConfigsUpdated(); - const std::string VariableName = CreateVariableName(Section, Variable); - if (Params.find(VariableName) == Params.end()) - { - LOG_ERROR("No variable matching \"%s\" found for type", *FString(VariableName.c_str())); - return; - } - auto &Param = Params[VariableName]; - Value = Param.DecipherToType(); - if (Param.bIsDirty) + FString LoadVehicle = "TeslaM3"; // default vehicle + if (GeneralParams.Get("EgoVehicle", "VehicleType", LoadVehicle)) { - LOG("Read \"%s\" => %s", *FString(VariableName.c_str()), *Param.DataStr); + LOG("Loading new default EgoVehicle: \"%s\"", *LoadVehicle); } - Param.bIsDirty = false; // has just been read -} - -static FActorDefinition FindDefnInRegistry(const UCarlaEpisode *Episode, const UClass *ClassType) -{ // searches through the registers actors (definitions) to find one with the matching class type check(Episode != nullptr); @@ -152,9 +104,12 @@ static FActorDefinition FindDefnInRegistry(const UCarlaEpisode *Episode, const U bool bFoundDef = false; for (const auto &Defn : Episode->GetActorDefinitions()) { - if (Defn.Class == ClassType) + const auto &LowerId = Defn.Id.ToLower(); // perform string comparisons on lowercase (ignore case) + // contains both the DReyeVR category (HarpLab) and specific EgoVehicle + if (LowerId.Contains(DReyeVRCategory.ToLower()) && LowerId.Contains(LoadVehicle.ToLower())) { - LOG("Found appropriate definition registered at UId: %d as \"%s\"", Defn.UId, *Defn.Id); + LOG("Found appropriate definition for \"%s\" registered at UId: %d as \"%s\"", // + *LoadVehicle, Defn.UId, *Defn.Id); FoundDefinition = Defn; bFoundDef = true; break; // assumes the first is the ONLY one matching this class (Ex. EgoVehicle, EgoSensor) @@ -389,35 +344,27 @@ static size_t GetNumberOfShaders() static FPostProcessSettings CreatePostProcessingParams(const std::vector &Shaders) { // modifying from here: https://docs.unrealengine.com/4.27/en-US/API/Runtime/Engine/Engine/FPostProcessSettings/ - float TmpParam; FPostProcessSettings PP; PP.bOverride_VignetteIntensity = true; - ReadConfigValue("CameraParams", "VignetteIntensity", TmpParam); - PP.VignetteIntensity = TmpParam; + PP.VignetteIntensity = GeneralParams.Get("CameraParams", "VignetteIntensity"); PP.bOverride_ScreenPercentage = true; - ReadConfigValue("CameraParams", "ScreenPercentage", TmpParam); - PP.ScreenPercentage = TmpParam; + PP.ScreenPercentage = GeneralParams.Get("CameraParams", "ScreenPercentage"); PP.bOverride_BloomIntensity = true; - ReadConfigValue("CameraParams", "BloomIntensity", TmpParam); - PP.BloomIntensity = TmpParam; + PP.BloomIntensity = GeneralParams.Get("CameraParams", "BloomIntensity"); PP.bOverride_SceneFringeIntensity = true; - ReadConfigValue("CameraParams", "SceneFringeIntensity", TmpParam); - PP.SceneFringeIntensity = TmpParam; + PP.SceneFringeIntensity = GeneralParams.Get("CameraParams", "SceneFringeIntensity"); PP.bOverride_LensFlareIntensity = true; - ReadConfigValue("CameraParams", "LensFlareIntensity", TmpParam); - PP.LensFlareIntensity = TmpParam; + PP.LensFlareIntensity = GeneralParams.Get("CameraParams", "LensFlareIntensity"); PP.bOverride_GrainIntensity = true; - ReadConfigValue("CameraParams", "GrainIntensity", TmpParam); - PP.GrainIntensity = TmpParam; + PP.GrainIntensity = GeneralParams.Get("CameraParams", "GrainIntensity"); PP.bOverride_MotionBlurAmount = true; - ReadConfigValue("CameraParams", "MotionBlurIntensity", TmpParam); - PP.MotionBlurAmount = TmpParam; + PP.MotionBlurAmount = GeneralParams.Get("CameraParams", "MotionBlurIntensity"); // append shaders to this postprocess effect for (const FSensorShader &ShaderInfo : Shaders) diff --git a/DReyeVR/EgoInputs.cpp b/DReyeVR/EgoInputs.cpp index 215d569..e0958cf 100644 --- a/DReyeVR/EgoInputs.cpp +++ b/DReyeVR/EgoInputs.cpp @@ -54,12 +54,23 @@ void AEgoVehicle::CameraDown() void AEgoVehicle::CameraPositionAdjust(const FVector &Disp) { + if (Disp.Equals(FVector::ZeroVector, 0.0001f)) + return; // preserves adjustment even after changing view CameraPoseOffset.SetLocation(CameraPoseOffset.GetLocation() + Disp); VRCameraRoot->SetRelativeLocation(CameraPose.GetLocation() + CameraPoseOffset.GetLocation()); /// TODO: account for rotation? scale? } +void AEgoVehicle::CameraPositionAdjust(bool bForward, bool bRight, bool bBackwards, bool bLeft, bool bUp, bool bDown) +{ + // add the corresponding directions according to the adjustment booleans + const FVector Disp = FVector::ForwardVector * bForward + FVector::RightVector * bRight + + FVector::BackwardVector * bBackwards + FVector::LeftVector * bLeft + FVector::UpVector * bUp + + FVector::DownVector * bDown; + CameraPositionAdjust(Disp); +} + void AEgoVehicle::PressNextCameraView() { if (!bCanPressNextCameraView) @@ -86,56 +97,59 @@ void AEgoVehicle::ReleasePrevCameraView() void AEgoVehicle::NextCameraView() { - CurrentCameraTransformIdx = (CurrentCameraTransformIdx + 1) % (CameraTransforms.size()); - LOG("Switching to next camera view: \"%s\"", *CameraTransforms[CurrentCameraTransformIdx].first); + if (CameraPoseKeys.Num() == 0) + return; + CurrentCameraTransformIdx = (CurrentCameraTransformIdx + 1) % (CameraPoseKeys.Num()); + const FString &Key = CameraPoseKeys[CurrentCameraTransformIdx]; + LOG("Switching manually to next camera view: \"%s\"", *Key); SetCameraRootPose(CurrentCameraTransformIdx); } void AEgoVehicle::PrevCameraView() { + if (CameraPoseKeys.Num() == 0) + return; if (CurrentCameraTransformIdx == 0) - CurrentCameraTransformIdx = CameraTransforms.size(); + CurrentCameraTransformIdx = CameraPoseKeys.Num(); CurrentCameraTransformIdx--; - LOG("Switching to prev camera view: \"%s\"", *CameraTransforms[CurrentCameraTransformIdx].first); + const FString &Key = CameraPoseKeys[CurrentCameraTransformIdx]; + LOG("Switching manually to prev camera view: \"%s\"", *Key); SetCameraRootPose(CurrentCameraTransformIdx); } -void AEgoVehicle::SetSteering(const float SteeringInput) +void AEgoVehicle::AddSteering(const float SteeringInput) { float ScaledSteeringInput = this->ScaleSteeringInput * SteeringInput; - this->GetVehicleMovementComponent()->SetSteeringInput(ScaledSteeringInput); // UE4 control // assign to input struct - VehicleInputs.Steering = ScaledSteeringInput; + VehicleInputs.Steering += ScaledSteeringInput; } -void AEgoVehicle::SetThrottle(const float ThrottleInput) +void AEgoVehicle::AddThrottle(const float ThrottleInput) { float ScaledThrottleInput = this->ScaleThrottleInput * ThrottleInput; - this->GetVehicleMovementComponent()->SetThrottleInput(ScaledThrottleInput); // UE4 control // apply new light state - FVehicleLightState Lights = this->GetVehicleLightState(); + FVehicleLightState Lights = GetVehicleLightState(); Lights.Reverse = false; Lights.Brake = false; - this->SetVehicleLightState(Lights); + SetVehicleLightState(Lights); // assign to input struct - VehicleInputs.Throttle = ScaledThrottleInput; + VehicleInputs.Throttle += ScaledThrottleInput; } -void AEgoVehicle::SetBrake(const float BrakeInput) +void AEgoVehicle::AddBrake(const float BrakeInput) { float ScaledBrakeInput = this->ScaleBrakeInput * BrakeInput; - this->GetVehicleMovementComponent()->SetBrakeInput(ScaledBrakeInput); // UE4 control // apply new light state - FVehicleLightState Lights = this->GetVehicleLightState(); + FVehicleLightState Lights = GetVehicleLightState(); Lights.Reverse = false; Lights.Brake = true; - this->SetVehicleLightState(Lights); + SetVehicleLightState(Lights); // assign to input struct - VehicleInputs.Brake = ScaledBrakeInput; + VehicleInputs.Brake += ScaledBrakeInput; } void AEgoVehicle::PressReverse() @@ -146,24 +160,27 @@ void AEgoVehicle::PressReverse() bReverse = !bReverse; // negate to toggle bw + (forwards) and - (backwards) - const int CurrentGear = this->GetVehicleMovementComponent()->GetTargetGear(); - 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 + // const int CurrentGear = this->GetVehicleMovementComponent()->GetTargetGear(); + // 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 FVehicleLightState Lights = this->GetVehicleLightState(); Lights.Reverse = this->bReverse; this->SetVehicleLightState(Lights); - LOG("Toggle Reverse"); + // LOG("Toggle Reverse"); // assign to input struct VehicleInputs.ToggledReverse = true; - this->PlayGearShiftSound(); + PlayGearShiftSound(); + + // call to parent + SetReverse(bReverse); } void AEgoVehicle::ReleaseReverse() @@ -234,20 +251,20 @@ void AEgoVehicle::ReleaseTurnSignalL() bCanPressTurnSignalL = true; } -void AEgoVehicle::PressHandbrake() +void AEgoVehicle::TickVehicleInputs() { - if (!bCanPressHandbrake) - return; - bCanPressHandbrake = false; // don't press again until release - GetVehicleMovementComponent()->SetHandbrakeInput(true); // UE4 control - // assign to input struct - VehicleInputs.HoldHandbrake = true; + FVehicleControl LastAppliedControl = GetVehicleControl(); + + int bIncludeLast = static_cast(GetAutopilotStatus()); + FVehicleControl ManualInputs; + // only include LastAppliedControl when autopilot is running (bc it would have flushed earlier this tick) + ManualInputs.Steer = VehicleInputs.Steering + bIncludeLast * LastAppliedControl.Steer; + ManualInputs.Brake = VehicleInputs.Brake + bIncludeLast * LastAppliedControl.Brake; + ManualInputs.Throttle = VehicleInputs.Throttle + bIncludeLast * LastAppliedControl.Throttle; + ManualInputs.bReverse = bReverse; + this->ApplyVehicleControl(ManualInputs, EVehicleInputPriority::User); + // send these inputs to the Carla (parent) vehicle + FlushVehicleControl(); + + VehicleInputs = DReyeVR::UserInputs(); // clear inputs for this frame } - -void AEgoVehicle::ReleaseHandbrake() -{ - GetVehicleMovementComponent()->SetHandbrakeInput(false); // UE4 control - // assign to input struct - VehicleInputs.HoldHandbrake = false; - bCanPressHandbrake = true; -} \ No newline at end of file diff --git a/DReyeVR/EgoSensor.cpp b/DReyeVR/EgoSensor.cpp index 6005ceb..62b106e 100644 --- a/DReyeVR/EgoSensor.cpp +++ b/DReyeVR/EgoSensor.cpp @@ -1,7 +1,7 @@ #include "EgoSensor.h" #include "Carla/Game/CarlaStatics.h" // GetCurrentEpisode -#include "DReyeVRUtils.h" // ReadConfigValue, ComputeClosestToRayIntersection +#include "DReyeVRUtils.h" // GeneralParams.Get, ComputeClosestToRayIntersection #include "EgoVehicle.h" // AEgoVehicle #include "Kismet/GameplayStatics.h" // UGameplayStatics::ProjectWorldToScreen #include "Kismet/KismetMathLibrary.h" // Sin, Cos, Normalize @@ -43,25 +43,25 @@ AEgoSensor::AEgoSensor(const FObjectInitializer &ObjectInitializer) : Super(Obje void AEgoSensor::ReadConfigVariables() { - ReadConfigValue("EgoSensor", "StreamSensorData", bStreamData); - ReadConfigValue("EgoSensor", "MaxTraceLenM", MaxTraceLenM); - ReadConfigValue("EgoSensor", "DrawDebugFocusTrace", bDrawDebugFocusTrace); + GeneralParams.Get("EgoSensor", "StreamSensorData", bStreamData); + GeneralParams.Get("EgoSensor", "MaxTraceLenM", MaxTraceLenM); + GeneralParams.Get("EgoSensor", "DrawDebugFocusTrace", bDrawDebugFocusTrace); // variables corresponding to the action of screencapture during replay - ReadConfigValue("Replayer", "RecordAllShaders", bRecordAllShaders); - ReadConfigValue("Replayer", "RecordAllPoses", bRecordAllPoses); - ReadConfigValue("Replayer", "RecordFrames", bCaptureFrameData); - ReadConfigValue("Replayer", "FileFormatJPG", bFileFormatJPG); - ReadConfigValue("Replayer", "LinearGamma", bFrameCapForceLinearGamma); - ReadConfigValue("Replayer", "FrameWidth", FrameCapWidth); - ReadConfigValue("Replayer", "FrameHeight", FrameCapHeight); - ReadConfigValue("Replayer", "FrameDir", FrameCapLocation); - ReadConfigValue("Replayer", "FrameName", FrameCapFilename); + GeneralParams.Get("Replayer", "RecordAllShaders", bRecordAllShaders); + GeneralParams.Get("Replayer", "RecordAllPoses", bRecordAllPoses); + GeneralParams.Get("Replayer", "RecordFrames", bCaptureFrameData); + GeneralParams.Get("Replayer", "FileFormatJPG", bFileFormatJPG); + GeneralParams.Get("Replayer", "LinearGamma", bFrameCapForceLinearGamma); + GeneralParams.Get("Replayer", "FrameWidth", FrameCapWidth); + GeneralParams.Get("Replayer", "FrameHeight", FrameCapHeight); + GeneralParams.Get("Replayer", "FrameDir", FrameCapLocation); + GeneralParams.Get("Replayer", "FrameName", FrameCapFilename); #if USE_FOVEATED_RENDER // foveated rendering variables - ReadConfigValue("VariableRateShading", "Enabled", bEnableFovRender); - ReadConfigValue("VariableRateShading", "UsingEyeTracking", bUseEyeTrackingVRS); + GeneralParams.Get("VariableRateShading", "Enabled", bEnableFovRender); + GeneralParams.Get("VariableRateShading", "UsingEyeTracking", bUseEyeTrackingVRS); #endif } @@ -89,6 +89,11 @@ void AEgoSensor::BeginDestroy() { Super::BeginDestroy(); + if (RecordingCF != nullptr) + { + delete RecordingCF; + } + DestroyEyeTracker(); LOG("EgoSensor has been destroyed"); @@ -96,7 +101,7 @@ void AEgoSensor::BeginDestroy() void AEgoSensor::ManualTick(float DeltaSeconds) { - if (!bIsReplaying) // only update the sensor with local values if not replaying + if (!ADReyeVRSensor::bIsReplaying) // only update the sensor with local values if not replaying { const float Timestamp = int64_t(1000.f * UGameplayStatics::GetRealTimeSeconds(World)); /// TODO: query the eye tracker hardware asynchronously (not limited to UE4 tick) @@ -105,11 +110,12 @@ void AEgoSensor::ManualTick(float DeltaSeconds) ComputeEgoVars(); // get all necessary ego-vehicle data // Update the internal sensor data that gets handed off to Carla (for recording/replaying/PythonAPI) - GetData()->Update(Timestamp, // TimestampCarla (ms) - EyeSensorData, // EyeTrackerData - EgoVars, // EgoVehicleVariables - FocusInfoData, // FocusData - Vehicle->GetVehicleInputs() // User inputs + const auto &Inputs = Vehicle.IsValid() ? Vehicle.Get()->GetVehicleInputs() : DReyeVR::UserInputs{}; + GetData()->Update(Timestamp, // TimestampCarla (ms) + EyeSensorData, // EyeTrackerData + EgoVars, // EgoVehicleVariables + FocusInfoData, // FocusData + Inputs // User inputs ); TickFoveatedRender(); } @@ -288,7 +294,8 @@ bool AEgoSensor::ComputeGazeTrace(FHitResult &Hit, const ECollisionChannel Trace // Create collision information container. FCollisionQueryParams TraceParam; TraceParam = FCollisionQueryParams(FName("TraceParam"), true); - TraceParam.AddIgnoredActor(Vehicle); // don't collide with the vehicle since that would be useless + if (Vehicle.IsValid()) + TraceParam.AddIgnoredActor(Vehicle.Get()); // don't collide with the vehicle since that would be useless TraceParam.bTraceComplex = true; TraceParam.bReturnPhysicalMaterial = false; Hit = FHitResult(EForceInit::ForceInit); @@ -371,26 +378,40 @@ float AEgoSensor::ComputeVergence(const FVector &L0, const FVector &LDir, const void AEgoSensor::SetEgoVehicle(class AEgoVehicle *NewEgoVehicle) { Vehicle = NewEgoVehicle; - Camera = Vehicle->GetCamera(); - check(Vehicle); -} + check(Vehicle.IsValid()); -void AEgoSensor::SetGame(class ADReyeVRGameMode *GameIn) -{ - DReyeVRGame = GameIn; - check(DReyeVRGame); + // Also check that the ConfigFileData variable can be written to with Vehicle params + check(ConfigFile); // this is a static variable created in the parent (ADReyeVRSensor) + + // track both the VehicleParams and GeneralParams + const auto ConfigFileStr = Vehicle.Get()->GetVehicleParams().Export() + GeneralParams.Export(); + ConfigFile->Set(ConfigFileStr); // track this config file once + + // saved from some previous request to compare, but failed bc no EgoVehicle + if (RecordingCF != nullptr) + { + UpdateData(*RecordingCF, 0.f); + } } void AEgoSensor::ComputeEgoVars() { + if (!Vehicle.IsValid()) + { + LOG_WARN("Invalid EgoVehicle, cannot compute EgoVars"); + return; + } // See DReyeVRData::EgoVariables - EgoVars.VehicleLocation = Vehicle->GetActorLocation(); - EgoVars.VehicleRotation = Vehicle->GetActorRotation(); + auto *Ego = Vehicle.Get(); + auto *Camera = Ego->GetCamera(); + check(Camera); + EgoVars.VehicleLocation = Ego->GetActorLocation(); + EgoVars.VehicleRotation = Ego->GetActorRotation(); EgoVars.CameraLocation = Camera->GetRelativeLocation(); EgoVars.CameraRotation = Camera->GetRelativeRotation(); EgoVars.CameraLocationAbs = Camera->GetComponentLocation(); EgoVars.CameraRotationAbs = Camera->GetComponentRotation(); - EgoVars.Velocity = Vehicle->GetVehicleForwardSpeed(); + EgoVars.Velocity = Ego->GetVehicleForwardSpeed(); } /// ========================================== /// @@ -416,7 +437,6 @@ void AEgoSensor::ConstructFrameCapture() check(CaptureRenderTarget->GetSurfaceWidth() > 0 && CaptureRenderTarget->GetSurfaceHeight() > 0); FrameCap = CreateDefaultSubobject(TEXT("FrameCap")); - FrameCap->SetupAttachment(Camera); FrameCap->PrimitiveRenderMode = ESceneCapturePrimitiveRenderMode::PRM_RenderScenePrimitives; FrameCap->bCaptureOnMovement = false; FrameCap->bCaptureEveryFrame = false; @@ -439,10 +459,13 @@ void AEgoSensor::ConstructFrameCapture() void AEgoSensor::InitFrameCapture() { - // creates the directory for the frame capture to take place if (bCaptureFrameData) { - // create out dir + // initialize frame capture attachment to the ego vehicle + if (FrameCap && Vehicle.IsValid()) + FrameCap->SetupAttachment(Vehicle.Get()->GetCamera()); + + // creates the directory for the frame capture to take place /// TODO: add check for absolute paths FrameCapLocation = FPaths::ConvertRelativePathToFull(FPaths::ProjectDir() + FrameCapLocation); // The returned string has the following format: yyyy.mm.dd-hh.mm.ss @@ -480,25 +503,25 @@ void AEgoSensor::TakeScreenshot() } // capture the screenshot to the directory - if (bCaptureFrameData && FrameCap && Camera && Vehicle) + if (bCaptureFrameData && FrameCap && Vehicle.IsValid()) { for (int i = 0; i < GetNumberOfShaders(); i++) { // apply the postprocessing effect FrameCap->PostProcessSettings = CreatePostProcessingEffect(i); // loop through all camera poses - for (int j = 0; j < Vehicle->GetNumCameraPoses(); j++) + for (int j = 0; j < Vehicle.Get()->GetNumCameraPoses(); j++) { // set this pose - Vehicle->SetCameraRootPose(j); + Vehicle.Get()->SetCameraRootPose(j); // using 5 digits to reach frame 99999 ~ 30m (assuming ~50fps frame capture) // suffix is denoted as _s(hader)X_p(ose)Y_Z.png where X is the shader idx, Y is the pose idx, Z is tick const FString Suffix = FString::Printf(TEXT("_s%d_p%d_%05d.png"), i, j, ScreenshotCount); // apply the camera view (position & orientation) FMinimalViewInfo DesiredView; - Camera->GetCameraView(0, DesiredView); - FrameCap->SetCameraView(DesiredView); // move camera to the Camera view + Vehicle.Get()->GetCamera()->GetCameraView(0, DesiredView); + FrameCap->SetCameraView(DesiredView); // move camera to the camera view // capture the scene and save the screenshot to disk FrameCap->CaptureScene(); // also available: CaptureSceneDeferred() SaveFrameToDisk(*CaptureRenderTarget, FPaths::Combine(FrameCapLocation, FrameCapFilename + Suffix), @@ -510,7 +533,7 @@ void AEgoSensor::TakeScreenshot() } } // set camera pose back to 0 - Vehicle->SetCameraRootPose(0); + Vehicle.Get()->SetCameraRootPose(0); if (!bRecordAllShaders) { // exit after the first shader (rgb) @@ -553,14 +576,41 @@ void AEgoSensor::TickFoveatedRender() /// ----------------:REPLAY:------------------ /// /// ========================================== /// -void AEgoSensor::UpdateData(const DReyeVR::AggregateData &RecorderData, const double Per) +// don't need to override the base ADReyeVRSensor::UpdateData(); + +void AEgoSensor::UpdateData(const DReyeVR::ConfigFileData &RecordedParams, const double Per) { - // call the parent function - ADReyeVRSensor::UpdateData(RecorderData, Per); + if (!Vehicle.IsValid()) + { + // LOG_WARN("Unable to compare ConfigFile bc EgoVehicle is invalid!"); + RecordingCF = new DReyeVR::ConfigFileData(); + (*RecordingCF) = RecordedParams; // save these params for later (ex. SetEgoVehicle) + return; + } + // compare the incoming (recording) ConfigFile with our current (live) one + const std::string RecordingExport = TCHAR_TO_UTF8(*RecordedParams.ToString()); + const struct ConfigFile Recorded = ConfigFile::Import(RecordingExport); + + // includes both the vehicle params and general params + struct ConfigFile LiveConfig; + LiveConfig.Insert(Vehicle.Get()->GetVehicleParams()); + LiveConfig.Insert(GeneralParams); + + bool bPrintWarnings = true; + if (LiveConfig.IsSubset(Recorded, bPrintWarnings)) // don't care if Recorded has entries that we dont + { + LOG("Config file comparison successful!"); + } + else + { + LOG_WARN("Config file comparison failed! This means the recording was performed with a different configuration " + "file than what is currently active. You might want to check that this does not affect the validity " + "of your replay."); + } } void AEgoSensor::UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) { - if (DReyeVRGame) - DReyeVRGame->ReplayCustomActor(RecorderData, Per); + if (Vehicle.IsValid() && Vehicle.Get()->GetGame()) + Vehicle.Get()->GetGame()->ReplayCustomActor(RecorderData, Per); } \ No newline at end of file diff --git a/DReyeVR/EgoSensor.h b/DReyeVR/EgoSensor.h index 31efebf..3e89d4c 100644 --- a/DReyeVR/EgoSensor.h +++ b/DReyeVR/EgoSensor.h @@ -37,9 +37,8 @@ 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 SetGame(class ADReyeVRGameMode *Game); // provides access to ADReyeVRGameMode - void UpdateData(const DReyeVR::AggregateData &RecorderData, const double Per) override; + void UpdateData(const DReyeVR::ConfigFileData &RecorderData, const double Per) override; void UpdateData(const DReyeVR::CustomActorData &RecorderData, const double Per) override; // function where replayer requests a screenshot @@ -56,7 +55,7 @@ class CARLAUE4_API AEgoSensor : public ADReyeVRSensor int64_t TickCount = 0; // how many ticks have been executed void ReadConfigVariables(); - ////////////////:EYETRACKER://////////////// + private: // eye tracker void InitEyeTracker(); void DestroyEyeTracker(); void ComputeDummyEyeData(); // when no hardware sensor is present @@ -76,16 +75,16 @@ class CARLAUE4_API AEgoSensor : public ADReyeVRSensor struct DReyeVR::FocusInfo FocusInfoData; // data from the focus computed from eye gaze std::chrono::time_point ChronoStartTime; // std::chrono time at BeginPlay - ////////////////:EGOVARS://////////////// + private: // ego=vehicle variables void ComputeEgoVars(); - class AEgoVehicle *Vehicle; // the DReyeVR EgoVehicle - struct DReyeVR::EgoVariables EgoVars; // data from vehicle that is getting tracked + TWeakObjectPtr Vehicle; // the DReyeVR EgoVehicle + struct DReyeVR::EgoVariables EgoVars; // data from vehicle that is getting tracked + DReyeVR::ConfigFileData *RecordingCF = nullptr; - ////////////////:FRAMECAPTURE://////////////// + private: // frame capture + size_t ScreenshotCount = 0; void ConstructFrameCapture(); // needs to be called in the constructor void InitFrameCapture(); // needs to be called in BeginPlay - size_t ScreenshotCount = 0; - class UCameraComponent *Camera; // for frame capture views class UTextureRenderTarget2D *CaptureRenderTarget = nullptr; class USceneCaptureComponent2D *FrameCap = nullptr; FString FrameCapLocation; // relative to game dir @@ -99,12 +98,9 @@ class CARLAUE4_API AEgoSensor : public ADReyeVRSensor bool bFileFormatJPG = true; bool bFrameCapForceLinearGamma = true; - ////////////////:FOVEATEDRENDER://////////////// + private: // foveated rendering void TickFoveatedRender(); void ConvertToEyeTrackerSpace(FVector &inVec) const; bool bEnableFovRender = false; bool bUseEyeTrackingVRS = true; - - ////////////////:REPLAY://////////////// - class ADReyeVRGameMode *DReyeVRGame = nullptr; }; \ No newline at end of file diff --git a/DReyeVR/EgoVehicle.cpp b/DReyeVR/EgoVehicle.cpp index 3cf2b83..9b67967 100644 --- a/DReyeVR/EgoVehicle.cpp +++ b/DReyeVR/EgoVehicle.cpp @@ -23,14 +23,14 @@ AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(Ob // this actor ticks AFTER the physics simulation is done PrimaryActorTick.bCanEverTick = true; + PrimaryActorTick.bStartWithTickEnabled = true; + PrimaryActorTick.bAllowTickOnDedicatedServer = true; PrimaryActorTick.TickGroup = TG_PostPhysics; + AIControllerClass = AWheeledVehicleAIController::StaticClass(); // Set up the root position to be the this mesh SetRootComponent(GetMesh()); - // Initialize the rigid body static mesh - ConstructRigidBody(); - // Initialize the camera components ConstructCameraRoot(); @@ -51,36 +51,47 @@ AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(Ob void AEgoVehicle::ReadConfigVariables() { - ReadConfigValue("EgoVehicle", "DashLocation", DashboardLocnInVehicle); - ReadConfigValue("EgoVehicle", "SpeedometerInMPH", bUseMPH); - ReadConfigValue("EgoVehicle", "EnableTurnSignalAction", bEnableTurnSignalAction); - ReadConfigValue("EgoVehicle", "TurnSignalDuration", TurnSignalDuration); + // this matches the BP_XYZ (XYZ) part of the blueprint, or "Vehicle" if just an EgoVehicle + VehicleType = CleanNameForDReyeVR(GetClass()->GetName()); + LOG("Initializing EgoVehicle: \"%s\"", *VehicleType); + if (!VehicleType.Equals("Vehicle", ESearchCase::CaseSensitive)) + { + auto NewParams = ConfigFile(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles"), VehicleType + ".ini")); + if (NewParams.bIsValid()) + VehicleParams = NewParams; + } + + // if the VehicleParams is invalid, use a default + if (!VehicleParams.bIsValid()) + VehicleParams = ConfigFile(FPaths::Combine(CarlaUE4Path, TEXT("Config/EgoVehicles/TeslaM3.ini")), false); + ensure(VehicleParams.bIsValid()); + + GeneralParams.Get("EgoVehicle", "EnableTurnSignalAction", bEnableTurnSignalAction); + GeneralParams.Get("EgoVehicle", "TurnSignalDuration", TurnSignalDuration); // mirrors - auto InitMirrorParams = [](const FString &Name, struct MirrorParams &Params) { + auto InitMirrorParams = [this](const FString &Name, struct MirrorParams &Params) { Params.Name = Name; - ReadConfigValue("Mirrors", Params.Name + "MirrorEnabled", Params.Enabled); - ReadConfigValue("Mirrors", Params.Name + "MirrorTransform", Params.MirrorTransform); - ReadConfigValue("Mirrors", Params.Name + "ReflectionTransform", Params.ReflectionTransform); - ReadConfigValue("Mirrors", Params.Name + "ScreenPercentage", Params.ScreenPercentage); + VehicleParams.Get("Mirrors", Params.Name + "MirrorEnabled", Params.Enabled); + VehicleParams.Get("Mirrors", Params.Name + "MirrorTransform", Params.MirrorTransform); + VehicleParams.Get("Mirrors", Params.Name + "ReflectionTransform", Params.ReflectionTransform); + VehicleParams.Get("Mirrors", Params.Name + "ScreenPercentage", Params.ScreenPercentage); }; InitMirrorParams("Rear", RearMirrorParams); InitMirrorParams("Left", LeftMirrorParams); InitMirrorParams("Right", RightMirrorParams); // rear mirror chassis - ReadConfigValue("Mirrors", "RearMirrorChassisTransform", RearMirrorChassisTransform); + VehicleParams.Get("Mirrors", "RearMirrorChassisTransform", RearMirrorChassisTransform); // steering wheel - ReadConfigValue("SteeringWheel", "InitLocation", InitWheelLocation); - ReadConfigValue("SteeringWheel", "InitRotation", InitWheelRotation); - ReadConfigValue("SteeringWheel", "MaxSteerAngleDeg", MaxSteerAngleDeg); - ReadConfigValue("SteeringWheel", "SteeringScale", SteeringAnimScale); + VehicleParams.Get("SteeringWheel", "MaxSteerAngleDeg", MaxSteerAngleDeg); + VehicleParams.Get("SteeringWheel", "SteeringScale", SteeringAnimScale); // other/cosmetic - ReadConfigValue("EgoVehicle", "DrawDebugEditor", bDrawDebugEditor); + GeneralParams.Get("EgoVehicle", "DrawDebugEditor", bDrawDebugEditor); // inputs - ReadConfigValue("VehicleInputs", "ScaleSteeringDamping", ScaleSteeringInput); - ReadConfigValue("VehicleInputs", "ScaleThrottleInput", ScaleThrottleInput); - ReadConfigValue("VehicleInputs", "ScaleBrakeInput", ScaleBrakeInput); + GeneralParams.Get("VehicleInputs", "ScaleSteeringDamping", ScaleSteeringInput); + GeneralParams.Get("VehicleInputs", "ScaleThrottleInput", ScaleThrottleInput); + GeneralParams.Get("VehicleInputs", "ScaleBrakeInput", ScaleBrakeInput); // replay - ReadConfigValue("Replayer", "CameraFollowHMD", bCameraFollowHMD); + GeneralParams.Get("Replayer", "CameraFollowHMD", bCameraFollowHMD); } void AEgoVehicle::BeginPlay() @@ -101,6 +112,8 @@ void AEgoVehicle::BeginPlay() // get the GameMode script SetGame(Cast(UGameplayStatics::GetGameMode(World))); + BeginThirdPersonCameraInit(); + LOG("Initialized DReyeVR EgoVehicle"); } @@ -110,12 +123,10 @@ void AEgoVehicle::EndPlay(const EEndPlayReason::Type EndPlayReason) if (EndPlayReason == EEndPlayReason::Destroyed) { LOG("DReyeVR EgoVehicle is being destroyed! You'll need to spawn another one!"); - } - - if (GetGame()) - { - GetGame()->SetEgoVehicle(nullptr); - GetGame()->PossessSpectator(); + if (GetGame()) + { + GetGame()->PossessSpectator(); + } } if (this->Pawn) @@ -129,8 +140,10 @@ void AEgoVehicle::BeginDestroy() Super::BeginDestroy(); // destroy all spawned entities - if (EgoSensor) - EgoSensor->Destroy(); + if (EgoSensor.IsValid()) + EgoSensor.Get()->Destroy(); + + DestroySteeringWheel(); LOG("EgoVehicle has been destroyed"); } @@ -161,148 +174,109 @@ void AEgoVehicle::Tick(float DeltaSeconds) // 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) - { - LOG_ERROR("Unable to load skeleton!"); - return; - } - - // 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; - } - - // 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; - } - - // 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 + // Tick vehicle controls + TickVehicleInputs(); } /// ========================================== /// /// ----------------:CAMERA:------------------ /// /// ========================================== /// +template T *AEgoVehicle::CreateEgoObject(const FString &Name, const FString &Suffix) +{ + // create default subobject with this name and (optionally) add a suffix + // https://docs.unrealengine.com/4.26/en-US/API/Runtime/CoreUObject/UObject/UObject/CreateDefaultSubobject/2/ + // see also: https://dev.epicgames.com/community/snippets/0bk/actor-component-creation + // if the blueprint gets corrupted (ex. object details no longer visible), reparent to BaseVehiclePawn then back + T *Ret = UObject::CreateDefaultSubobject(FName(*(Name + Suffix))); + // disabling tick for these objects by default + Ret->SetComponentTickEnabled(false); + Ret->PrimaryComponentTick.bCanEverTick = false; + Ret->PrimaryComponentTick.bStartWithTickEnabled = false; + return Ret; +} + void AEgoVehicle::ConstructCameraRoot() { // Spawn the RootComponent and Camera for the VR camera - VRCameraRoot = CreateDefaultSubobject(TEXT("VRCameraRoot")); + VRCameraRoot = CreateEgoObject("VRCameraRoot"); + check(VRCameraRoot != nullptr); VRCameraRoot->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself VRCameraRoot->SetRelativeLocation(FVector::ZeroVector); VRCameraRoot->SetRelativeRotation(FRotator::ZeroRotator); - // taking this names directly from the [CameraPose] params in DReyeVRConfig.ini + // add first-person driver's seat + CameraTransforms.Add("DriversSeat", VehicleParams.Get("CameraPose", "DriversSeat")); + + SetCameraRootPose("DriversSeat"); +} + +void AEgoVehicle::BeginThirdPersonCameraInit() +{ + // add third-person views + std::vector CameraPoses = { - "DriversSeat", // 1st "ThirdPerson", // 2nd "BirdsEyeView", // 3rd "Front", // 4th }; - for (FString &Key : CameraPoses) + UBoxComponent *Bounds = this->GetVehicleBoundingBox(); + ensure(Bounds != nullptr); + if (Bounds != nullptr) { - FVector Location; - FRotator Rotation; - ReadConfigValue("CameraPose", Key + "Loc", Location); - ReadConfigValue("CameraPose", Key + "Rot", Rotation); - // converting FString to std::string for hashing - FTransform Transform = FTransform(Rotation, Location, FVector::OneVector); - CameraTransforms.push_back(std::make_pair(Key, Transform)); + const FVector BoundingBoxSize = Bounds->GetScaledBoxExtent(); + LOG("Calculated EgoVehicle bounding box: %s", *BoundingBoxSize.ToString()); + for (FString &Key : CameraPoses) + { + FTransform Transform = GeneralParams.Get("CameraPose", Key); + Transform.SetLocation(Transform.GetLocation() * BoundingBoxSize); // scale by bounding box + CameraTransforms.Add(Key, Transform); + } } + CameraTransforms.GenerateKeyArray(CameraPoseKeys); + ensure(CameraPoseKeys.Num() > 0); + // assign the starting camera root pose to the given starting pose - FString StartingPose; - ReadConfigValue("CameraPose", "StartingPose", StartingPose); + FString StartingPose = GeneralParams.Get("CameraPose", "StartingPose"); SetCameraRootPose(StartingPose); } void AEgoVehicle::SetCameraRootPose(const FString &CameraPoseName) { + FTransform NewCameraTransform; // given a string (key), index into the map to obtain the FTransform - FTransform CameraPoseTransform; - bool bFoundMatchingPair = false; - for (std::pair &CamPose : CameraTransforms) + if (CameraTransforms.Contains(CameraPoseName)) { - if (CamPose.first == CameraPoseName) - { - CameraPoseTransform = CamPose.second; - bFoundMatchingPair = true; - break; - } + NewCameraTransform = CameraTransforms[CameraPoseName]; } - ensure(bFoundMatchingPair == true); // yells at you if CameraPoseName was not found - SetCameraRootPose(CameraPoseTransform); + else + { + LOG_WARN("Unable to find camera pose named \"%s\". Defaulting to driver's seat!", *CameraPoseName); + NewCameraTransform = CameraTransforms["DriversSeat"]; + } + SetCameraRootPose(NewCameraTransform); } size_t AEgoVehicle::GetNumCameraPoses() const { - return CameraTransforms.size(); + return CameraTransforms.Num(); } void AEgoVehicle::SetCameraRootPose(size_t CameraPoseIdx) { + if (CameraPoseKeys.Num() == 0) + return; // allow setting the camera root by indexing into CameraTransforms array - CameraPoseIdx = std::min(CameraPoseIdx, CameraTransforms.size() - 1); - SetCameraRootPose(CameraTransforms[CameraPoseIdx].second); + CameraPoseIdx = std::min(CameraPoseIdx, static_cast(CameraPoseKeys.Num() - 1)); + const auto &Key = CameraPoseKeys[CameraPoseIdx]; + const FTransform *NewPose = CameraTransforms.Find(Key); + if (NewPose == nullptr) + { + LOG_ERROR("Unable to find camera pose \"%s\"", *Key); + return; + } + SetCameraRootPose(*NewPose); } void AEgoVehicle::SetCameraRootPose(const FTransform &CameraPoseTransform) @@ -331,6 +305,10 @@ void AEgoVehicle::SetPawn(ADReyeVRPawn *PawnIn) FirstPersonCam->SetRelativeRotation(FRotator::ZeroRotator); } +const FString &AEgoVehicle::GetVehicleType() const +{ + return VehicleType; +} const UCameraComponent *AEgoVehicle::GetCamera() const { ensure(FirstPersonCam != nullptr); @@ -358,9 +336,21 @@ FRotator AEgoVehicle::GetCameraRot() const { return GetCamera() ? GetCamera()->GetComponentRotation() : FRotator::ZeroRotator; } +class AEgoSensor *AEgoVehicle::GetSensor() +{ + // tries to return the EgoSensor pointer if it is safe to do so, else re-spawn it + return SafePtrGet("EgoSensor", EgoSensor, [&](void) { this->InitSensor(); }); +} + const class AEgoSensor *AEgoVehicle::GetSensor() const { - return const_cast(EgoSensor); + // tries to return the EgoSensor pointer if it is safe to do so, else re-spawn it + return const_cast(const_cast(this)->GetSensor()); +} + +const struct ConfigFile &AEgoVehicle::GetVehicleParams() const +{ + return VehicleParams; } /// ========================================== /// @@ -370,17 +360,21 @@ const class AEgoSensor *AEgoVehicle::GetSensor() const void AEgoVehicle::InitAIPlayer() { this->SpawnDefaultController(); // spawns default (AI) controller and gets possessed by it - auto PlayerController = this->GetController(); + auto PlayerController = GetController(); ensure(PlayerController != nullptr); AI_Player = Cast(PlayerController); - ensure(AI_Player != nullptr); + check(AI_Player != nullptr); + SetAutopilot(false); // initially no autopilot enabled } void AEgoVehicle::SetAutopilot(const bool AutopilotOn) { + if (!AI_Player) + return; bAutopilotEnabled = AutopilotOn; AI_Player->SetAutopilot(bAutopilotEnabled); AI_Player->SetStickyControl(bAutopilotEnabled); + // AI_Player->SetActorTickEnabled(bAutopilotEnabled); // want the controller to always tick! } bool AEgoVehicle::GetAutopilotStatus() const @@ -394,6 +388,7 @@ void AEgoVehicle::TickAutopilot() if (AI_Player != nullptr) { bAutopilotEnabled = AI_Player->IsAutopilotEnabled(); + TickAutopilotIndicator(bAutopilotEnabled); } } @@ -416,28 +411,29 @@ void AEgoVehicle::InitSensor() Description.UId = EgoSensorDef.UId; Description.Id = EgoSensorDef.Id; Description.Class = EgoSensorDef.Class; - } - - if (Episode == nullptr) - { - LOG_ERROR("Null Episode in world!"); + // add all the attributes from the definition to the description + for (FActorAttribute A : EgoSensorDef.Attributes) + { + Description.Variations.Add(A.Id, std::move(A)); + } } // 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); + check(EgoSensor.IsValid()); // Attach the EgoSensor as a child to the EgoVehicle - EgoSensor->SetOwner(this); - EgoSensor->AttachToActor(this, FAttachmentTransformRules::KeepRelativeTransform); - EgoSensor->SetEgoVehicle(this); - if (DReyeVRGame) - EgoSensor->SetGame(DReyeVRGame); + EgoSensor.Get()->SetOwner(this); + EgoSensor.Get()->AttachToActor(this, FAttachmentTransformRules::KeepRelativeTransform); + EgoSensor.Get()->SetActorTransform(FTransform::Identity, false, nullptr, ETeleportType::TeleportPhysics); + EgoSensor.Get()->SetEgoVehicle(this); } void AEgoVehicle::ReplayTick() { - const bool bIsReplaying = EgoSensor->IsReplaying(); + if (!EgoSensor.IsValid()) + return; + const bool bIsReplaying = EgoSensor.Get()->IsReplaying(); // need to enable/disable VehicleMesh simulation class USkeletalMeshComponent *VehicleMesh = GetMesh(); if (VehicleMesh) @@ -449,7 +445,7 @@ void AEgoVehicle::ReplayTick() if (bIsReplaying) { // this gets reached when the simulator is replaying data from a carla log - const DReyeVR::AggregateData *Replay = EgoSensor->GetData(); + const DReyeVR::AggregateData *Replay = EgoSensor.Get()->GetData(); // include positional update here, else there is lag/jitter between the camera and the vehicle // since the Carla Replayer tick differs from the EgoVehicle tick @@ -475,22 +471,21 @@ void AEgoVehicle::ReplayTick() void AEgoVehicle::UpdateSensor(const float DeltaSeconds) { - if (EgoSensor == nullptr) // Spawn and attach the EgoSensor + if (!EgoSensor.IsValid()) // Spawn and attach the EgoSensor { // unfortunately World->SpawnActor *sometimes* fails if used in BeginPlay so // calling it once in the tick is fine to avoid this crash. InitSensor(); } - ensure(EgoSensor != nullptr); - if (EgoSensor == nullptr) + if (!EgoSensor.IsValid()) { 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 + EgoSensor.Get()->ManualTick(DeltaSeconds); // Ensures we always get the latest data } /// ========================================== /// @@ -536,18 +531,15 @@ void AEgoVehicle::ConstructMirrors() class USkeletalMeshComponent *VehicleMesh = GetMesh(); /// Rear mirror { - static ConstructorHelpers::FObjectFinder RearSM( - 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"))); + // the rear mirror is interesting bc we have 3 components: the mirror (specular), the mirror chassis + // (what holds the mirror, typically lambertian), and the planar reflection (invisible but "reflection") + // other mirrors currently only use the mirror and planar reflection, as we didn't cut out the chassis for them + RearMirrorSM = CreateEgoObject(RearMirrorParams.Name + "MirrorSM"); + RearReflection = CreateEgoObject(RearMirrorParams.Name + "Refl"); + RearMirrorChassisSM = CreateEgoObject(RearMirrorParams.Name + "MirrorChassisSM"); + RearMirrorParams.Initialize(RearMirrorSM, RearReflection, VehicleMesh); // also add the chassis for this mirror - 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(RearMirrorChassisTransform.GetLocation()); RearMirrorChassisSM->SetRelativeRotation(RearMirrorChassisTransform.Rotator()); @@ -560,20 +552,14 @@ void AEgoVehicle::ConstructMirrors() } /// Left mirror { - 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"))); + LeftMirrorSM = CreateEgoObject(LeftMirrorParams.Name + "MirrorSM"); + LeftReflection = CreateEgoObject(LeftMirrorParams.Name + "Refl"); LeftMirrorParams.Initialize(LeftMirrorSM, LeftReflection, VehicleMesh); } /// Right mirror { - static ConstructorHelpers::FObjectFinder RightSM( - 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"))); + RightMirrorSM = CreateEgoObject(RightMirrorParams.Name + "MirrorSM"); + RightReflection = CreateEgoObject(RightMirrorParams.Name + "Refl"); RightMirrorParams.Initialize(RightMirrorSM, RightReflection, VehicleMesh); } } @@ -582,42 +568,99 @@ void AEgoVehicle::ConstructMirrors() /// ----------------:SOUNDS:------------------ /// /// ========================================== /// +template bool FindSound(const FString &Section, const FString &Variable, UAudioComponent *Out) +{ + if (Out != nullptr) // TODO: check that the key is present + { + const FString PathStr = GeneralParams.Get(Section, Variable); + if (!PathStr.IsEmpty()) + { + ConstructorHelpers::FObjectFinder FoundSound(*PathStr); + if (FoundSound.Succeeded()) + { + Out->SetSound(FoundSound.Object); + return true; + } + } + } + return false; +} + void AEgoVehicle::ConstructEgoSounds() { + // shouldn't override this method in ACarlaWHeeledVehicle because it will be + // used in the constructor and calling virtual methods in constructor is bad: + // https://stackoverflow.com/questions/962132/calling-virtual-functions-inside-constructors + // Initialize ego-centric audio components - // See ACarlaWheeledVehicle::ConstructSounds for all Vehicle sounds - ensureMsgf(EngineRevSound != nullptr, TEXT("Vehicle engine rev should be initialized!")); - ensureMsgf(CrashSound != nullptr, TEXT("Vehicle crash sound should be initialized!")); + { + if (EngineRevSound != nullptr) + { + EngineRevSound->DestroyComponent(); // from the parent class (default sound) + EngineRevSound = nullptr; + } + EgoEngineRevSound = CreateEgoObject("EgoEngineRevSound"); + FindSound("Sound", "DefaultEngineRev", EgoEngineRevSound); + EgoEngineRevSound->SetupAttachment(GetRootComponent()); // attach to self + EgoEngineRevSound->bAutoActivate = true; // start playing on begin + EngineLocnInVehicle = VehicleParams.Get("Sounds", "EngineLocn"); + EgoEngineRevSound->SetRelativeLocation(EngineLocnInVehicle); // location of "engine" in vehicle (3D sound) + EgoEngineRevSound->SetFloatParameter(FName("RPM"), 0.f); // initially idle + EgoEngineRevSound->bAutoDestroy = false; // No automatic destroy, persist along with vehicle + check(EgoEngineRevSound != nullptr); + } + + { + if (CrashSound != nullptr) + { + CrashSound->DestroyComponent(); // from the parent class (default sound) + CrashSound = nullptr; + } + EgoCrashSound = CreateEgoObject("EgoCarCrash"); + FindSound("Sound", "DefaultCrashSound", EgoCrashSound); + EgoCrashSound->SetupAttachment(GetRootComponent()); + EgoCrashSound->bAutoActivate = false; + EgoCrashSound->bAutoDestroy = false; + check(EgoCrashSound != nullptr); + } - static ConstructorHelpers::FObjectFinder GearSound( - TEXT("SoundWave'/Game/DReyeVR/Sounds/GearShift.GearShift'")); - GearShiftSound = CreateDefaultSubobject(TEXT("GearShift")); - GearShiftSound->SetupAttachment(GetRootComponent()); - GearShiftSound->bAutoActivate = false; - GearShiftSound->SetSound(GearSound.Object); + { + GearShiftSound = CreateEgoObject("GearShift"); + FindSound("Sound", "DefaultGearShiftSound", GearShiftSound); + GearShiftSound->SetupAttachment(GetRootComponent()); + GearShiftSound->bAutoActivate = false; + check(GearShiftSound != nullptr); + } + + { + TurnSignalSound = CreateEgoObject("TurnSignal"); + FindSound("Sound", "DefaultTurnSignalSound", TurnSignalSound); + TurnSignalSound->SetupAttachment(GetRootComponent()); + TurnSignalSound->bAutoActivate = false; + check(TurnSignalSound != nullptr); + } - static ConstructorHelpers::FObjectFinder TurnSignalSoundWave( - TEXT("SoundWave'/Game/DReyeVR/Sounds/TurnSignal.TurnSignal'")); - TurnSignalSound = CreateDefaultSubobject(TEXT("TurnSignal")); - TurnSignalSound->SetupAttachment(GetRootComponent()); - TurnSignalSound->bAutoActivate = false; - TurnSignalSound->SetSound(TurnSignalSoundWave.Object); + ConstructEgoCollisionHandler(); } void AEgoVehicle::PlayGearShiftSound(const float DelayBeforePlay) const { - if (this->GearShiftSound) + if (GearShiftSound != nullptr) GearShiftSound->Play(DelayBeforePlay); } void AEgoVehicle::PlayTurnSignalSound(const float DelayBeforePlay) const { - if (this->TurnSignalSound) - this->TurnSignalSound->Play(DelayBeforePlay); + if (TurnSignalSound != nullptr) + TurnSignalSound->Play(DelayBeforePlay); } void AEgoVehicle::SetVolume(const float VolumeIn) { + if (EgoEngineRevSound) + EgoEngineRevSound->SetVolumeMultiplier(VolumeIn); + if (EgoCrashSound) + EgoCrashSound->SetVolumeMultiplier(VolumeIn); if (GearShiftSound) GearShiftSound->SetVolumeMultiplier(VolumeIn); if (TurnSignalSound) @@ -625,6 +668,58 @@ void AEgoVehicle::SetVolume(const float VolumeIn) Super::SetVolume(VolumeIn); } +void AEgoVehicle::TickSounds(float DeltaSeconds) +{ + // Respect the global vehicle volume param + SetVolume(ACarlaWheeledVehicle::Volume); + + if (EgoEngineRevSound) + { + if (!EgoEngineRevSound->IsPlaying()) + EgoEngineRevSound->Play(); // turn on the engine sound if not already on + float RPM = FMath::Clamp(GetVehicleMovementComponent()->GetEngineRotationSpeed(), 0.f, 5650.0f); + EgoEngineRevSound->SetFloatParameter(FName("RPM"), RPM); + } + + // add other sounds that need tick-level granularity here... +} + +void AEgoVehicle::ConstructEgoCollisionHandler() +{ + // using Carla's GetVehicleBoundingBox function + UBoxComponent *Bounds = this->GetVehicleBoundingBox(); + if (Bounds != nullptr) + { + Bounds->SetGenerateOverlapEvents(true); + Bounds->SetCollisionEnabled(ECollisionEnabled::QueryOnly); + Bounds->SetCollisionProfileName(TEXT("DReyeVRTrigger")); + Bounds->OnComponentBeginOverlap.AddDynamic(this, &AEgoVehicle::OnEgoOverlapBegin); + } +} + +void AEgoVehicle::OnEgoOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, + UPrimitiveComponent *OtherComp, int32 OtherBodyIndex, bool bFromSweep, + const FHitResult &SweepResult) +{ + if (OtherActor == nullptr || OtherActor == this) + return; + + // can be more flexible, such as having collisions with static props or people too + if (EnableCollisionForActor(OtherActor)) + { + // move the sound 1m in the direction of the collision + FVector SoundEmitLocation = 100.f * (this->GetActorLocation() - OtherActor->GetActorLocation()).GetSafeNormal(); + SoundEmitLocation.Z = 75.f; // Make the sound emitted not at the ground (75cm off ground) + if (EgoCrashSound != nullptr) + { + EgoCrashSound->SetRelativeLocation(SoundEmitLocation); + EgoCrashSound->Play(0.f); + // have at least 0.5s of buffer between collision audio + CollisionCooldownTime = GetWorld()->GetTimeSeconds() + 0.5f; + } + } +} + /// ========================================== /// /// -----------------:DASH:------------------- /// /// ========================================== /// @@ -632,53 +727,62 @@ void AEgoVehicle::SetVolume(const float VolumeIn) void AEgoVehicle::ConstructDashText() // dashboard text (speedometer, turn signals, gear shifter) { // Create speedometer - Speedometer = CreateDefaultSubobject(TEXT("Speedometer")); - Speedometer->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); - Speedometer->SetRelativeLocation(DashboardLocnInVehicle); - Speedometer->SetRelativeRotation(FRotator(0.f, 180.f, 0.f)); // need to flip it to get the text in driver POV - Speedometer->SetTextRenderColor(FColor::Red); - Speedometer->SetText(FText::FromString("0")); - Speedometer->SetXScale(1.f); - Speedometer->SetYScale(1.f); - Speedometer->SetWorldSize(10); // scale the font with this - Speedometer->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); - Speedometer->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); - SpeedometerScale = CmPerSecondToXPerHour(bUseMPH); + if (VehicleParams.Get("Dashboard", "SpeedometerEnabled")) + { + Speedometer = CreateEgoObject("Speedometer"); + Speedometer->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); + Speedometer->SetRelativeTransform(VehicleParams.Get("Dashboard", "SpeedometerTransform")); + Speedometer->SetTextRenderColor(FColor::Red); + Speedometer->SetText(FText::FromString("0")); + Speedometer->SetXScale(1.f); + Speedometer->SetYScale(1.f); + Speedometer->SetWorldSize(10); // scale the font with this + Speedometer->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); + Speedometer->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + SpeedometerScale = CmPerSecondToXPerHour(GeneralParams.Get("EgoVehicle", "SpeedometerInMPH")); + check(Speedometer != nullptr); + } // Create turn signals - TurnSignals = CreateDefaultSubobject(TEXT("TurnSignals")); - TurnSignals->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); - TurnSignals->SetRelativeLocation(DashboardLocnInVehicle + FVector(0, 11.f, -5.f)); - TurnSignals->SetRelativeRotation(FRotator(0.f, 180.f, 0.f)); // need to flip it to get the text in driver POV - TurnSignals->SetTextRenderColor(FColor::Red); - TurnSignals->SetText(FText::FromString("")); - TurnSignals->SetXScale(1.f); - TurnSignals->SetYScale(1.f); - TurnSignals->SetWorldSize(10); // scale the font with this - TurnSignals->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); - TurnSignals->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + if (VehicleParams.Get("Dashboard", "TurnSignalsEnabled")) + { + TurnSignals = CreateEgoObject("TurnSignals"); + TurnSignals->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); + TurnSignals->SetRelativeTransform(VehicleParams.Get("Dashboard", "TurnSignalsTransform")); + TurnSignals->SetTextRenderColor(FColor::Red); + TurnSignals->SetText(FText::FromString("")); + TurnSignals->SetXScale(1.f); + TurnSignals->SetYScale(1.f); + TurnSignals->SetWorldSize(10); // scale the font with this + TurnSignals->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); + TurnSignals->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + check(TurnSignals != nullptr); + } // Create gear shifter - GearShifter = CreateDefaultSubobject(TEXT("GearShifter")); - GearShifter->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); - GearShifter->SetRelativeLocation(DashboardLocnInVehicle + FVector(0, 15.f, 0)); - GearShifter->SetRelativeRotation(FRotator(0.f, 180.f, 0.f)); // need to flip it to get the text in driver POV - GearShifter->SetTextRenderColor(FColor::Red); - GearShifter->SetText(FText::FromString("D")); - GearShifter->SetXScale(1.f); - GearShifter->SetYScale(1.f); - GearShifter->SetWorldSize(10); // scale the font with this - GearShifter->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); - GearShifter->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + if (VehicleParams.Get("Dashboard", "GearShifterEnabled")) + { + GearShifter = CreateEgoObject("GearShifter"); + GearShifter->AttachToComponent(GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform); + GearShifter->SetRelativeTransform(VehicleParams.Get("Dashboard", "GearShifterTransform")); + GearShifter->SetTextRenderColor(FColor::Red); + GearShifter->SetText(FText::FromString("D")); + GearShifter->SetXScale(1.f); + GearShifter->SetYScale(1.f); + GearShifter->SetWorldSize(10); // scale the font with this + GearShifter->SetVerticalAlignment(EVerticalTextAligment::EVRTA_TextCenter); + GearShifter->SetHorizontalAlignment(EHorizTextAligment::EHTA_Center); + check(GearShifter != nullptr); + } } void AEgoVehicle::UpdateDash() { // Draw text components float XPH; // miles-per-hour or km-per-hour - if (EgoSensor->IsReplaying()) + if (EgoSensor.IsValid() && EgoSensor.Get()->IsReplaying()) { - const DReyeVR::AggregateData *Replay = EgoSensor->GetData(); + const DReyeVR::AggregateData *Replay = EgoSensor.Get()->GetData(); XPH = Replay->GetVehicleVelocity() * SpeedometerScale; // FwdSpeed is in cm/s const auto &ReplayInputs = Replay->GetUserInputs(); if (ReplayInputs.ToggledReverse) @@ -704,10 +808,13 @@ void AEgoVehicle::UpdateDash() XPH = GetVehicleForwardSpeed() * SpeedometerScale; // FwdSpeed is in cm/s } - const FString Data = FString::FromInt(int(FMath::RoundHalfFromZero(XPH))); - Speedometer->SetText(FText::FromString(Data)); + if (Speedometer != nullptr) + { + const FString Data = FString::FromInt(int(FMath::RoundHalfFromZero(XPH))); + Speedometer->SetText(FText::FromString(Data)); + } - if (bEnableTurnSignalAction) + if (bEnableTurnSignalAction && TurnSignals != nullptr) { // Draw the signals float Now = GetWorld()->GetTimeSeconds(); @@ -724,11 +831,11 @@ void AEgoVehicle::UpdateDash() TurnSignals->SetText(FText::FromString(TurnSignalStr)); } - // Draw the gear shifter - if (bReverse) // backwards - GearShifter->SetText(FText::FromString("R")); - else - GearShifter->SetText(FText::FromString("D")); + if (GearShifter != nullptr) + { + // Draw the gear shifter + GearShifter->SetText(bReverse ? FText::FromString("R") : FText::FromString("D")); + } } /// ========================================== /// @@ -737,30 +844,153 @@ void AEgoVehicle::UpdateDash() void AEgoVehicle::ConstructSteeringWheel() { - 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); + const bool bEnableSteeringWheel = VehicleParams.Get("SteeringWheel", "Enabled"); + SteeringWheel = CreateEgoObject("SteeringWheel"); SteeringWheel->SetupAttachment(GetRootComponent()); // The vehicle blueprint itself - SteeringWheel->SetRelativeLocation(InitWheelLocation); - SteeringWheel->SetRelativeRotation(InitWheelRotation); + SteeringWheel->SetRelativeLocation(VehicleParams.Get("SteeringWheel", "InitLocation")); + SteeringWheel->SetRelativeRotation(VehicleParams.Get("SteeringWheel", "InitRotation")); SteeringWheel->SetGenerateOverlapEvents(false); // don't collide with itself SteeringWheel->SetCollisionEnabled(ECollisionEnabled::NoCollision); - SteeringWheel->SetVisibility(true); + SteeringWheel->SetVisibility(bEnableSteeringWheel); +} + +void AEgoVehicle::InitAutopilotIndicator() +{ + bool bEnableAutopilotIndicator = GeneralParams.Get("WheelFace", "EnableAutopilotIndicator"); + if (SteeringWheel == nullptr || World == nullptr || bEnableAutopilotIndicator == false) + return; + AutopilotIndicator = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "AI_Indicator"); + const FVector AutopilotIndicatorLocation = GeneralParams.Get("WheelFace", "AutopilotIndicatorLoc"); + const float AutopilotIndicatorSize = GeneralParams.Get("WheelFace", "AutopilotIndicatorSize"); + AutopilotIndicator->SetActorLocation(AutopilotIndicatorLocation); + check(AutopilotIndicator != nullptr); + AutopilotIndicator->Activate(); + AutopilotIndicator->SetActorScale3D(AutopilotIndicatorSize * FVector::OneVector); + AutopilotIndicator->AttachToComponent(SteeringWheel, FAttachmentTransformRules::KeepRelativeTransform); + AutopilotIndicator->MaterialParams.BaseColor = ButtonNeutralCol; // close to off + AutopilotIndicator->MaterialParams.Emissive = ButtonNeutralCol; // close to off + AutopilotIndicator->UpdateMaterial(); + AutopilotIndicator->SetActorTickEnabled(false); // don't tick these actors (for performance) + AutopilotIndicator->SetActorRecordEnabled(false); // don't need to record these actors either + AutopilotIndicator->GetMesh()->SetCastShadow(false); // don't want shadows (looks weird) + bInitializedAutopilotIndicator = true; +} + +void AEgoVehicle::InitWheelButtons() +{ + bool bEnableWheelFaceButtons = GeneralParams.Get("WheelFace", "EnableWheelButtons"); + if (SteeringWheel == nullptr || World == nullptr || bEnableWheelFaceButtons == false) + return; + // left buttons (dpad) + Button_DPad_Up = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Up"); // top on left + Button_DPad_Right = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Right"); // right on left + Button_DPad_Down = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Down"); // bottom on left + Button_DPad_Left = ADReyeVRCustomActor::CreateNew(SM_CONE, MAT_OPAQUE, World, "DPad_Left"); // left on left + // right buttons (ABXY) + Button_ABXY_Y = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_Y"); // top on right + Button_ABXY_B = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_B"); // right on right + Button_ABXY_A = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_A"); // bottom on right + Button_ABXY_X = ADReyeVRCustomActor::CreateNew(SM_SPHERE, MAT_OPAQUE, World, "ABXY_X"); // left on right + + const FRotator PointLeft(0.f, 0.f, -90.f); + const FRotator PointRight(0.f, 0.f, 90.f); + const FRotator PointUp(0.f, 0.f, 0.f); + const FRotator PointDown(0.f, 0.f, 180.f); + + const FVector LeftCenter = GeneralParams.Get("WheelFace", "ABXYLocation"); + const FVector RightCenter = GeneralParams.Get("WheelFace", "DpadLocation"); + + // increase to separate the buttons more + const float ButtonDist = GeneralParams.Get("WheelFace", "QuadButtonSpread"); + + Button_DPad_Up->SetActorLocation(LeftCenter + ButtonDist * FVector::UpVector); + Button_DPad_Up->SetActorRotation(PointUp); + Button_DPad_Right->SetActorLocation(LeftCenter + ButtonDist * FVector::RightVector); + Button_DPad_Right->SetActorRotation(PointRight); + Button_DPad_Down->SetActorLocation(LeftCenter + ButtonDist * FVector::DownVector); + Button_DPad_Down->SetActorRotation(PointDown); + Button_DPad_Left->SetActorLocation(LeftCenter + ButtonDist * FVector::LeftVector); + Button_DPad_Left->SetActorRotation(PointLeft); + + // (spheres don't need rotation) + Button_ABXY_Y->SetActorLocation(RightCenter + ButtonDist * FVector::UpVector); + Button_ABXY_B->SetActorLocation(RightCenter + ButtonDist * FVector::RightVector); + Button_ABXY_A->SetActorLocation(RightCenter + ButtonDist * FVector::DownVector); + Button_ABXY_X->SetActorLocation(RightCenter + ButtonDist * FVector::LeftVector); + + // for applying the same properties on these actors + auto WheelButtons = {Button_ABXY_A, Button_ABXY_B, Button_ABXY_X, Button_ABXY_Y, + Button_DPad_Up, Button_DPad_Down, Button_DPad_Left, Button_DPad_Right}; + for (auto *Button : WheelButtons) + { + check(Button != nullptr); + Button->Activate(); + Button->SetActorScale3D(0.015f * FVector::OneVector); + Button->AttachToComponent(SteeringWheel, FAttachmentTransformRules::KeepRelativeTransform); + Button->MaterialParams.BaseColor = ButtonNeutralCol; + Button->MaterialParams.Emissive = ButtonNeutralCol; + Button->UpdateMaterial(); + Button->SetActorTickEnabled(false); // don't tick these actors (for performance) + Button->SetActorRecordEnabled(false); // don't need to record these actors either + Button->GetMesh()->SetCastShadow(false); // don't want shadows (looks weird) + } + bInitializedButtons = true; +} + +void AEgoVehicle::UpdateWheelButton(ADReyeVRCustomActor *Button, bool bEnabled) +{ + if (Button == nullptr) + return; + Button->MaterialParams.BaseColor = bEnabled ? ButtonPressedCol : ButtonNeutralCol; + Button->MaterialParams.Emissive = bEnabled ? ButtonPressedCol : ButtonNeutralCol; + Button->UpdateMaterial(); +} + +void AEgoVehicle::TickAutopilotIndicator(bool bAutopilotEnabled) +{ + if (AutopilotIndicator == nullptr) + return; + const FLinearColor On = FLinearColor(0.537, 0.812, 0.941); // baby blue + const FLinearColor Off = 0.1f * FLinearColor(0.537, 0.812, 0.941); // baby blue (off) + AutopilotIndicator->MaterialParams.BaseColor = bAutopilotEnabled ? On : Off; + AutopilotIndicator->MaterialParams.Emissive = 500.f * (bAutopilotEnabled ? On : Off); + AutopilotIndicator->UpdateMaterial(); +} + +void AEgoVehicle::DestroySteeringWheel() +{ + auto WheelButtons = {Button_ABXY_A, Button_ABXY_B, Button_ABXY_X, Button_ABXY_Y, + Button_DPad_Up, Button_DPad_Down, Button_DPad_Left, Button_DPad_Right}; + for (auto *Button : WheelButtons) + { + if (Button) + { + Button->Deactivate(); + Button->Destroy(); + } + } } void AEgoVehicle::TickSteeringWheel(const float DeltaTime) { + if (!SteeringWheel) + return; + if (!bInitializedButtons) + InitWheelButtons(); + if (!bInitializedAutopilotIndicator) + InitAutopilotIndicator(); const FRotator CurrentRotation = SteeringWheel->GetRelativeRotation(); - const float RawSteering = GetVehicleInputs().Steering; // this is scaled in SetSteering - const float TargetAngle = (RawSteering / ScaleSteeringInput) * SteeringAnimScale; FRotator NewRotation = CurrentRotation; - if (Pawn && Pawn->GetIsLogiConnected()) + if (Pawn && Pawn->GetIsLogiConnected() && !GetAutopilotStatus()) { + // make the virtual wheel rotation follow the physical steering wheel + const float RawSteering = GetVehicleInputs().Steering; // this is scaled in SetSteering + const float TargetAngle = (RawSteering / ScaleSteeringInput) * SteeringAnimScale; NewRotation.Roll = TargetAngle; } - else + else if (GetMesh() && Cast(GetMesh()->GetAnimInstance()) != nullptr) { + // use the animation (front wheels) steer angle for the steering wheel float WheelAngleDeg = GetWheelSteerAngle(EVehicleWheelLocation::Front_Wheel); // float MaxWheelAngle = GetMaximumSteerAngle(); float DeltaAngle = 10.f * (2.0f * WheelAngleDeg - CurrentRotation.Roll); @@ -782,7 +1012,7 @@ void AEgoVehicle::SetGame(ADReyeVRGameMode *Game) { DReyeVRGame = Game; check(DReyeVRGame != nullptr); - DReyeVRGame->SetEgoVehicle(this); + check(DReyeVRGame->GetEgoVehicle() == this); DReyeVRGame->GetPawn()->BeginEgoVehicle(this, World); LOG("Successfully assigned GameMode & controller pawn"); @@ -807,10 +1037,10 @@ void AEgoVehicle::DebugLines() const { #if WITH_EDITOR - if (bDrawDebugEditor) + if (bDrawDebugEditor && EgoSensor.IsValid()) { // Calculate gaze data (in world space) using eye tracker data - const DReyeVR::AggregateData *Data = EgoSensor->GetData(); + const DReyeVR::AggregateData *Data = EgoSensor.Get()->GetData(); // Compute World positions and orientations const FRotator &WorldRot = FirstPersonCam->GetComponentRotation(); const FVector &WorldPos = FirstPersonCam->GetComponentLocation(); diff --git a/DReyeVR/EgoVehicle.h b/DReyeVR/EgoVehicle.h index bf56ad2..90faf0c 100644 --- a/DReyeVR/EgoVehicle.h +++ b/DReyeVR/EgoVehicle.h @@ -12,7 +12,7 @@ #include "Components/SceneComponent.h" // USceneComponent #include "CoreMinimal.h" // Unreal functions #include "DReyeVRGameMode.h" // ADReyeVRGameMode -#include "DReyeVRUtils.h" // ReadConfigValue +#include "DReyeVRUtils.h" // GeneralParams.Get #include "EgoSensor.h" // AEgoSensor #include "FlatHUD.h" // ADReyeVRHUD #include "ImageUtils.h" // CreateTexture2D @@ -47,6 +47,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle void SetVolume(const float VolumeIn); // Getters + const FString &GetVehicleType() const; FVector GetCameraOffset() const; FVector GetCameraPosn() const; FVector GetNextCameraPosn(const float DeltaSeconds) const; @@ -55,6 +56,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle UCameraComponent *GetCamera(); const DReyeVR::UserInputs &GetVehicleInputs() const; const class AEgoSensor *GetSensor() const; + const struct ConfigFile &GetVehicleParams() const; // autopilot API void SetAutopilot(const bool AutopilotOn); @@ -71,6 +73,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle void SetCameraRootPose(const FString &PoseName); // index into named FTransform void SetCameraRootPose(size_t PoseIdx); // index into ordered FTransform const FTransform &GetCameraRootPose() const; + void BeginThirdPersonCameraInit(); void NextCameraView(); void PrevCameraView(); @@ -80,33 +83,40 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override; virtual void BeginDestroy() override; + // custom configuration file for vehicle-specific parameters + struct ConfigFile VehicleParams; + // World variables class UWorld *World; private: - void ConstructRigidBody(); + template T *CreateEgoObject(const FString &Name, const FString &Suffix = ""); + FString VehicleType; // initially empty (set in GetVehicleType()) - ////////////////:CAMERA://////////////// - void ConstructCameraRoot(); // needs to be called in the constructor - UPROPERTY(Category = Camera, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + private: // camera + UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class USceneComponent *VRCameraRoot; UPROPERTY(Category = Camera, EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UCameraComponent *FirstPersonCam; - FTransform CameraPose, CameraPoseOffset; // camera pose (location & rotation) and manual offset - std::vector> CameraTransforms; // collection of named transforms from params - size_t CurrentCameraTransformIdx = 0; + void ConstructCameraRoot(); // needs to be called in the constructor + FTransform CameraPose, CameraPoseOffset; // camera pose (location & rotation) and manual offset + TMap CameraTransforms; // collection of named transforms from params + TArray CameraPoseKeys; // to iterate through them + size_t CurrentCameraTransformIdx = 0; // to index in CameraPoseKeys which indexes into CameraTransforms bool bCameraFollowHMD = true; // disable this (in params) to replay without following the player's HMD (replay-only) - ////////////////:SENSOR://////////////// + private: // sensor + class AEgoSensor *GetSensor(); void ReplayTick(); void InitSensor(); - class AEgoSensor *EgoSensor; // custom sensor helper that holds logic for extracting useful data + // custom sensor helper that holds logic for extracting useful data + TWeakObjectPtr EgoSensor; // EgoVehicle should have exclusive access (TODO: unique ptr?) void UpdateSensor(const float DeltaTime); - ///////////////:DREYEVRPAWN:///////////// + private: // pawn class ADReyeVRPawn *Pawn = nullptr; - ////////////////:MIRRORS://////////////// + private: // mirrors void ConstructMirrors(); struct MirrorParams { @@ -135,19 +145,20 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle class UStaticMeshComponent *RearMirrorChassisSM; FTransform RearMirrorChassisTransform; - ////////////////:AICONTROLLER://////////////// + private: // AI controller class AWheeledVehicleAIController *AI_Player = nullptr; void InitAIPlayer(); bool bAutopilotEnabled = false; void TickAutopilot(); - ////////////////:INPUTS://////////////// + private: // inputs /// NOTE: since there are so many functions here, they are defined in EgoInputs.cpp struct DReyeVR::UserInputs VehicleInputs; // struct for user inputs - // Vehicle control functions - void SetSteering(const float SteeringInput); - void SetThrottle(const float ThrottleInput); - void SetBrake(const float BrakeInput); + // Vehicle control functions (additive for multiple input modalities (kbd/logi)) + void AddSteering(float SteeringInput); + void AddThrottle(float ThrottleInput); + void AddBrake(float BrakeInput); + void TickVehicleInputs(); bool bReverse; // "button presses" should have both a "Press" and "Release" function @@ -169,10 +180,6 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle void ReleaseTurnSignalR(); float RightSignalTimeToDie; // how long until the blinkers go out bool bCanPressTurnSignalR = true; - // handbrake - void PressHandbrake(); - void ReleaseHandbrake(); - bool bCanPressHandbrake = true; // Camera control functions (offset by some amount) void CameraPositionAdjust(const FVector &Disp); @@ -182,6 +189,7 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle void CameraRight(); void CameraUp(); void CameraDown(); + void CameraPositionAdjust(bool bForward, bool bRight, bool bBackwards, bool bLeft, bool bUp, bool bDown); // changing camera views void PressNextCameraView(); @@ -196,18 +204,29 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle float ScaleThrottleInput; float ScaleBrakeInput; - ////////////////:SOUNDS://////////////// - void ConstructEgoSounds(); // needs to be called in the constructor + private: // sounds UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UAudioComponent *GearShiftSound; // nice for toggling reverse UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UAudioComponent *TurnSignalSound; // good for turn signals + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *EgoEngineRevSound; // driver feedback on throttle + UPROPERTY(Category = "Audio", EditAnywhere, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) + class UAudioComponent *EgoCrashSound; // crashing with another actor + void ConstructEgoSounds(); // needs to be called in the constructor + virtual void TickSounds(float DeltaSeconds) override; - ////////////////:LEVEL://////////////// + // manually overriding these from ACarlaWheeledVehicle + void ConstructEgoCollisionHandler(); // needs to be called in the constructor + UFUNCTION() + void OnEgoOverlapBegin(UPrimitiveComponent *OverlappedComp, AActor *OtherActor, UPrimitiveComponent *OtherComp, + int32 OtherBodyIndex, bool bFromSweep, const FHitResult &SweepResult); + + private: // gamemode/level void TickGame(float DeltaSeconds); class ADReyeVRGameMode *DReyeVRGame; - ////////////////:DASH://////////////// + private: // dashboard // Text Render components (Like the HUD but part of the mesh and works in VR) void ConstructDashText(); // needs to be called in the constructor UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) @@ -218,22 +237,33 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle UPROPERTY(Category = "Dash", EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UTextRenderComponent *GearShifter; void UpdateDash(); - FVector DashboardLocnInVehicle{110, 0, 105}; // can change via params - bool bUseMPH; - float SpeedometerScale; // scale from CM/s to MPH or KPH depending on bUseMPH + float SpeedometerScale = CmPerSecondToXPerHour(true); // scale from CM/s to MPH or KPH (default MPH) - ////////////////:STEERINGWHEEL://////////////// - void ConstructSteeringWheel(); // needs to be called in the constructor + private: // steering wheel UPROPERTY(Category = Steering, EditDefaultsOnly, BlueprintReadWrite, meta = (AllowPrivateAccess = "true")) class UStaticMeshComponent *SteeringWheel; + void ConstructSteeringWheel(); // needs to be called in the constructor + void DestroySteeringWheel(); void TickSteeringWheel(const float DeltaTime); - FVector InitWheelLocation; - FRotator InitWheelRotation; float MaxSteerAngleDeg; float MaxSteerVelocity; float SteeringAnimScale; + bool bWheelFollowAutopilot = true; // disable steering during autopilot and follow AI + // wheel face buttons + void InitWheelButtons(); + void UpdateWheelButton(ADReyeVRCustomActor *Button, bool bEnabled); + class ADReyeVRCustomActor *Button_ABXY_A, *Button_ABXY_B, *Button_ABXY_X, *Button_ABXY_Y; + class ADReyeVRCustomActor *Button_DPad_Up, *Button_DPad_Down, *Button_DPad_Left, *Button_DPad_Right; + bool bInitializedButtons = false; + const FLinearColor ButtonNeutralCol = 0.2f * FLinearColor::White; + const FLinearColor ButtonPressedCol = 1.5f * FLinearColor::White; + // wheel face autopilot indicator + void InitAutopilotIndicator(); + void TickAutopilotIndicator(bool); + class ADReyeVRCustomActor *AutopilotIndicator; + bool bInitializedAutopilotIndicator = false; - ////////////////:OTHER://////////////// + private: // other void DebugLines() const; bool bDrawDebugEditor = false; -}; +}; \ No newline at end of file diff --git a/Docs/Figures/EgoVehicle/ActorTick.jpg b/Docs/Figures/EgoVehicle/ActorTick.jpg new file mode 100644 index 0000000..3eb39e8 Binary files /dev/null and b/Docs/Figures/EgoVehicle/ActorTick.jpg differ diff --git a/Docs/Figures/EgoVehicle/AnimGraph.jpg b/Docs/Figures/EgoVehicle/AnimGraph.jpg new file mode 100644 index 0000000..23455c2 Binary files /dev/null and b/Docs/Figures/EgoVehicle/AnimGraph.jpg differ diff --git a/Docs/Figures/EgoVehicle/AssignAnim.jpg b/Docs/Figures/EgoVehicle/AssignAnim.jpg new file mode 100644 index 0000000..60efe3e Binary files /dev/null and b/Docs/Figures/EgoVehicle/AssignAnim.jpg differ diff --git a/Docs/Figures/EgoVehicle/CameraReposition.jpg b/Docs/Figures/EgoVehicle/CameraReposition.jpg new file mode 100644 index 0000000..ff3fc8d Binary files /dev/null and b/Docs/Figures/EgoVehicle/CameraReposition.jpg differ diff --git a/Docs/Figures/EgoVehicle/CopyAnim.jpg b/Docs/Figures/EgoVehicle/CopyAnim.jpg new file mode 100644 index 0000000..8ddd4f1 Binary files /dev/null and b/Docs/Figures/EgoVehicle/CopyAnim.jpg differ diff --git a/Docs/Figures/EgoVehicle/CopyHere.jpg b/Docs/Figures/EgoVehicle/CopyHere.jpg new file mode 100644 index 0000000..cc5ba2b Binary files /dev/null and b/Docs/Figures/EgoVehicle/CopyHere.jpg differ diff --git a/Docs/Figures/EgoVehicle/CopyRef.jpg b/Docs/Figures/EgoVehicle/CopyRef.jpg new file mode 100644 index 0000000..d654425 Binary files /dev/null and b/Docs/Figures/EgoVehicle/CopyRef.jpg differ diff --git a/Docs/Figures/EgoVehicle/CreateAnim.jpg b/Docs/Figures/EgoVehicle/CreateAnim.jpg new file mode 100644 index 0000000..60af08e Binary files /dev/null and b/Docs/Figures/EgoVehicle/CreateAnim.jpg differ diff --git a/Docs/Figures/EgoVehicle/CreateAnimBP.jpg b/Docs/Figures/EgoVehicle/CreateAnimBP.jpg new file mode 100644 index 0000000..fd62951 Binary files /dev/null and b/Docs/Figures/EgoVehicle/CreateAnimBP.jpg differ diff --git a/Docs/Figures/EgoVehicle/EditClassSettings.jpg b/Docs/Figures/EgoVehicle/EditClassSettings.jpg new file mode 100644 index 0000000..2da7921 Binary files /dev/null and b/Docs/Figures/EgoVehicle/EditClassSettings.jpg differ diff --git a/Docs/Figures/EgoVehicle/PasteAnim.jpg b/Docs/Figures/EgoVehicle/PasteAnim.jpg new file mode 100644 index 0000000..175811c Binary files /dev/null and b/Docs/Figures/EgoVehicle/PasteAnim.jpg differ diff --git a/Docs/Figures/EgoVehicle/Reparent.jpg b/Docs/Figures/EgoVehicle/Reparent.jpg new file mode 100644 index 0000000..cabb435 Binary files /dev/null and b/Docs/Figures/EgoVehicle/Reparent.jpg differ diff --git a/Docs/Figures/EgoVehicle/SM_Mirror.jpg b/Docs/Figures/EgoVehicle/SM_Mirror.jpg new file mode 100644 index 0000000..f117ae2 Binary files /dev/null and b/Docs/Figures/EgoVehicle/SM_Mirror.jpg differ diff --git a/Docs/Figures/EgoVehicle/SM_Wheel.jpg b/Docs/Figures/EgoVehicle/SM_Wheel.jpg new file mode 100644 index 0000000..3f9ceff Binary files /dev/null and b/Docs/Figures/EgoVehicle/SM_Wheel.jpg differ diff --git a/Docs/CustomActor.md b/Docs/Tutorials/CustomActor.md similarity index 87% rename from Docs/CustomActor.md rename to Docs/Tutorials/CustomActor.md index 7929171..80645bd 100644 --- a/Docs/CustomActor.md +++ b/Docs/Tutorials/CustomActor.md @@ -21,9 +21,9 @@ We are often interested in spawning arbitrary "AR-like" (Augmented reality) elem # Usage -Using these CustomActors is designed to be straightforward and cooperate with UE4/Carla's notion of [AActors](https://docs.unrealengine.com/5.0/en-US/API/Runtime/Engine/GameFramework/AActor/). You can see how we define all the core data for these actors (and what gets recorded/replayed) in [`DReyeVRData.h`](../Carla/Sensor/DReyeVRData.h)`::CustomActorData` +Using these CustomActors is designed to be straightforward and cooperate with UE4/Carla's notion of [AActors](https://docs.unrealengine.com/5.0/en-US/API/Runtime/Engine/GameFramework/AActor/). You can see how we define all the core data for these actors (and what gets recorded/replayed) in [`DReyeVRData.h`](../../Carla/Sensor/DReyeVRData.h)`::CustomActorData` -We have several basic 3D shapes ready for simple CustomActor usage. Theoretically you can use any static mesh. To access these types (or add your own) you should check out the references in [`DReyeVRCustomActor.h`](../Carla/Actor/DReyeVRCustomActor.h): +We have several basic 3D shapes ready for simple CustomActor usage. Theoretically you can use any static mesh. To access these types (or add your own) you should check out the references in [`DReyeVRCustomActor.h`](../../Carla/Actor/DReyeVRCustomActor.h): ```c++ #define MAT_OPAQUE "Material'/Game/DReyeVR/Custom/OpaqueParamMaterial.OpaqueParamMaterial'" #define MAT_TRANSLUCENT "Material'/Game/DReyeVR/Custom/TranslucentParamMaterial.TranslucentParamMaterial'" @@ -48,7 +48,7 @@ UWorld *World = GetWorld(); ADReyeVRCustomActor *A = ADReyeVRCustomActor::CreateNew(PathToSM, PathToMaterial, World, Name); ``` -Implementation wise, the custom actors are all managed by a "global" table (`static std::unordered_map`) that indexes the actors by their `Name` therefore it is critical that they all have unique names. This is often easy to do when spawning many since UE4 `AActor`s themselves have unique names enumerated by their spawn order. To further understand how we use the global table, check out `ADReyeVRCustomActor::ActiveCustomActors` in [`DReyevRCustomActor.h`](../Carla/Actor/DReyeVRCustomActor.h) +Implementation wise, the custom actors are all managed by a "global" table (`static std::unordered_map`) that indexes the actors by their `Name` therefore it is critical that they all have unique names. This is often easy to do when spawning many since UE4 `AActor`s themselves have unique names enumerated by their spawn order. To further understand how we use the global table, check out `ADReyeVRCustomActor::ActiveCustomActors` in [`DReyevRCustomActor.h`](../../Carla/Actor/DReyeVRCustomActor.h) ## Activate/deactivate a custom actor @@ -94,12 +94,12 @@ A->MaterialParams.Anisotropy = 0.5f; Note that in order to use the `Opacity` property, the material needs to have a translucent blend mode. So far we only have two material types, opaque and translucent, each with their own set of available properties as follows: | OpaqueParamMaterial | TranslucentParamMaterial | | --- | --- | -| ![OpaqueMaterial](Figures/Actor/OpaqueParamMaterial.jpg) | ![OpaqueMaterial](Figures/Actor/TranslucentParamMaterial.jpg) | +| ![OpaqueMaterial](../Figures/Actor/OpaqueParamMaterial.jpg) | ![OpaqueMaterial](../Figures/Actor/TranslucentParamMaterial.jpg) | ## Bounding Box Example -As an example of the CustomActor bounding boxes in action, checkout [`LevelScript.cpp::DrawBBoxes`](../DReyeVR/LevelScript.cpp) where some simple logic for drawing translucent bounding boxes is held (coloured based on distance to EgoVehicle). To enable this function, you'll need to manually enable it by removing the `#if 0` and corresponding `#endif` around the function body. +As an example of the CustomActor bounding boxes in action, checkout [`LevelScript.cpp::DrawBBoxes`](../../DReyeVR/LevelScript.cpp) where some simple logic for drawing translucent bounding boxes is held (coloured based on distance to EgoVehicle). To enable this function, you'll need to manually enable it by removing the `#if 0` and corresponding `#endif` around the function body. Here is what it might look like in action: -![BboxExample](Figures/Actor/Bbox.jpg) \ No newline at end of file +![BboxExample](../Figures/Actor/Bbox.jpg) \ No newline at end of file diff --git a/Docs/Tutorials/CustomEgo.md b/Docs/Tutorials/CustomEgo.md new file mode 100644 index 0000000..b69b85d --- /dev/null +++ b/Docs/Tutorials/CustomEgo.md @@ -0,0 +1,129 @@ +# How to add your own EgoVehicle + +A guide from how to add your own custom EgoVehicle from an existing Carla vehicle that you can then use in DReyeVR. Showcasing the minimal required steps to add an **ambulance** to be the new DReyeVR EgoVehicle. + +## Prerequisites: +- You should have DReyeVR installed and functioning correctly +- You should probably take a look at [Model.md](Model.md) in case you want to modify the static mesh of your new vehicle: + - Ex. creating high-poly mirror meshes + - Ex. detatching the steering wheel for use as a dynamic prop (moves with the animation) + +## 1. Choose which vehicle to add +1. Since the DReyeVR EgoVehicle is a child-instance of the `ACarlaWheeledVehicle`, you should use a Carla vehicle for the base class of your desired Vehicle. For this tutorial we will use the Ambulance as an example, but any Carla vehicle should do fine. + - For Vehicle `XYZ` + - The blueprint files are located in `Unreal/CarlaUE4/Content/Carla/Blueprints/Vehicles/XYZ/BP_XYZ.uasset` + - The static mesh files are located in `Unreal/CarlaUE4/Content/Carla/Static/Vehicles/XWheeled/XYZ/` +2. Once you have decided on a vehicle, create this structure by copying (in Unreal Editor) the blueprint file. + - Do the same with any other mesh components that you'll want to add. + - You'll want the file structure to match the existing EgoVehicles: + ``` + CarlaUE4/Content/DReyeVR/ + ├── EgoVehicle + │   ├── Extra + │   ├── Jeep + │   ├── Mustang66 + │   ├── Ambulance # <-- your new EgoVehicle + │   ├── TeslaM3 # <-- default for DReyeVR + │   └── Vespa + ... + ``` + - Inside your `XYZ/` folder, you'll want to copy your new BP_XYZ asset (do this from the editor so that cached paths can be updated) and create any additional folders in here that you might want (ex. `Mesh`, `Mirrors`, `SteeringWheel`, `Tires`, are a few examples). + - It is best to perform these asset file modifications within the Editor. You can copy the files from within the content browser to other folders by click+dragging to get this pop-up: + + ![CopyHere](../Figures/EgoVehicle/CopyHere.jpg) + +**NOTE**: If you want to edit the vehicle mesh at all, this is where you'd want to do it. You will probably want to build off the existing static meshes in the `Static` directory. + +## 2. Reparent the vehicle blueprint +(For the sake of this tutorial, we'll assume the `XYZ=Ambulance`) +1. Open the `Content/DReyeVR/EgoVehicle/Ambulance/BP_Ambulance` asset you just copied from the content browser +2. Select `Class Defaults` then in the top right (`Class Options`) select the `Parent Class` and search for `EgoVehicle` to reparent (as in the figure below). This effectively reorganizes the blueprint's base class from `BaseVehiclePawn` (the Carla default) to `EgoVehicle` (the DReyeVR C++ class, which still inherits from BaseVehiclePawn). + - There will be a warning pop-up regarding data loss, you should proceed (it is purely additive). + - **NOTE** if the blueprint ever gets corrupted, you should first try reparenting back to the `BaseVehiclePawn` (the original parent) and then back to the DReyeVR `EgoVehicle`. + - ![EditClass](../Figures/EgoVehicle/EditClassSettings.jpg) + - Demonstrating class setting button, used to edit this BP's class instance + - ![Reparent](../Figures/EgoVehicle/Reparent.jpg) + - Demonstrating the reparenting button, select the dropdown and search for a compatible class to reparent with `BaseVehiclePawn` (Carla) or `EgoVehicle` (DReyeVR). +3. Now this vehicle is technically a DReyeVR EgoVehicle! + +## 3. Add the new config file and code +Now, to actually register this new blueprint with DReyeVR and have it available to spawn you'll need to add two bits to the code: + +1. Add the name of your new vehicle (for example `"Ambulance"` for the `BP_Ambulance` blueprint we inherited) to the list of available EgoVehicles in [`DReyeVRFactory.h`](../../DReyeVR/DReyeVRFactory.h). + ```c++ + // place the names of all your new custom EgoVehicle types here: + /// IMPORTANT: make sure these match the ConfigFile AND Blueprint!! + // We expect Config/EgoVehicle/XYZ.ini and Content/DReyeVR/EgoVehicles/XYZ/BP_XYZ.uasset + const std::vector VehicleTypes = { + "TeslaM3", // Tesla Model 3 (Default) + "Mustang66", // Mustang66 + "Jeep", // JeepWranglerRubicon + "Vespa" // Vespa (2WheeledVehicles) + "Ambulance", // <-- the new vehicle! (for this tutorial) + // add more here + }; + ``` +2. Add a new config file (to `Unreal/CarlaUE4/Config/EgoVehicles/`) that is used to parameterize this vehicle. This allows DReyeVR to know where to place things such as the camera root location (driver's seat), mirrors, steering wheel, etc. and this [`ConfigFile`](../../DReyeVR/ConfigFile.h) can be extended to support many run-time combinations. + - You'll need to make sure the config file has the EXACT same name as your new EgoVehicle (this is how they are read). We recommend copying an existing config file (default is `TeslaM3.ini` and renaming as follows): + ``` + CarlaUE4/Config/ + ├── ... + ├── DReyeVRConfig.ini + ├── ... + ├── EgoVehicles/ + │   ├── Jeep.ini + │   ├── Mustang66.ini + │   ├── Ambulance.ini # <-- your new file! + │   ├── TeslaM3.ini + │   └── Vespa.ini + ├── ... + ... + ``` + - Then you'll probably want to edit some of the contents of this file to match the EgoVehicle specifications which you can get from the Editor. For instance, the following figure shows that we are going to want to move the VRCameraRoot (head position) to (`108, -40, 158`). + - ![CameraRepos](../Figures/EgoVehicle/CameraReposition.jpg) + - You'll probably also want to move the dashboard elements around to whatever fits your preference. + - **IMPORTANT** You also need to enable the `Start with Tick Enabled` for the Blueprint (`BP_Ambulance` in the Components list) because by default they are disabled for Carla vehicles: + - ![ActorTick](../Figures/EgoVehicle/ActorTick.jpg) + - You should also notice that assets such as the SteeringWheel & Mirrors don't have any assigned static mesh. You can access these by clicking the component (on the left hierarchy) and assigning a new static mesh (on the right details pane). This bakes the asset directly in the blueprint file, so this only needs to be done once. + | Example: Mirrors | Example: Steering wheel | + | --- | --- | + | ![Mirrors](../Figures/EgoVehicle/SM_Mirror.jpg) | ![Wheel](../Figures/EgoVehicle/SM_Wheel.jpg) + - Now, open the `Ambulance.ini` file you just created and begin updating the fields (mostly transforms) to match the parameters you care about. Importantly, for the `[Blueprint]::Path` entry, you'll get this path by right-clicking on the Blueprint in the content viewer and selecting `Copy Reference`. + - ![CopyRef](../Figures/EgoVehicle/CopyRef.jpg) + - Note that transforms are encoded as follows + ```ini + # Format: Location XYZ in CM | Rotation Roll/Pitch/Yaw in Degrees | Scale XYZ percent (1=100%) + ExampleTransform=(X=0.0, Y=0.0, Z=3.0 | R=-45, P=90.0, Y=0 | X=1, Y=1, Z=1) + ``` + +## 4. Set the new vehicle to be the DReyeVR default +In the `DReyeVRConfig.ini` general configuration file (for non-vehicle specific parameters) you should set what Vehicle to spawn in by default. This takes the name of the vehicles, which for this example is `Ambulance`. + +```ini +[EgoVehicle] +VehicleType="Ambulance" +``` + +And thats it! You should now be able to relaunch `make launch` and when you press Play you'll start in your new EgoVehicle. + + +## 4. [Optional] Create a new animation +Sometimes, especially when modifying the meshes in blender and exporting/importing them back into Unreal Engine, the vanilla animation asset can get somewhat mangled and not work properly. You will know if the animation is failing if the tires (and steering wheel, if you added one) are not turning while the EgoVehicle is moving. + +See Carla's corresponding documentation [here](https://carla.readthedocs.io/en/latest/tuto_A_add_vehicle/#import-and-configure-the-vehicle). + +**NOTE** This only works for 4WheeledVehicles as of testing. 2WheeledVehicles are more complicated and not covered in this tutorial. + +### Steps to create a new animation blueprint for Carla/DReyeVR +1. Create a new Animation Blueprint in the Ambulance/Mesh directory (if you have one, else make a new folder `Mesh/` inside `Ambulance`). +- ![CreateAnim](../Figures/EgoVehicle/CreateAnim.jpg) +2. Make sure the parent of the animation mesh is set to `VehicleAnimInstance` and the preview skeleton is set to the skeletal mesh of your new vehicle (ex. `SK_Ambulance_Skeleton`) +- ![CreateAnimBP](../Figures/EgoVehicle/CreateAnimBP.jpg) +3. Name your new asset to something like `Anim_Ambulance` and open it up. Open the AnimationGraph in the bottom right as shown: +- ![AnimGraph](../Figures/EgoVehicle/AnimGraph.jpg) +4. Open another nearby animation blueprint (ex. `Content/DReyeVR/EgoVehicle/TeslaM3/Mesh/Animation_model3`) and open its AnimationGraph to copy the first three blueprint nodes that connect to the Output Pose as follows: +- ![CopyAnim](../Figures/EgoVehicle/CopyAnim.jpg) +5. Then, back in `Anim_Ambulance`, paste the three nodes you just copied and connect them to the Output Pose: +- ![PasteAnim](../Figures/EgoVehicle/PasteAnim.jpg) +6. Finally, go back to the vehicle blueprint (BP_Ambulance) and in the components section select Mesh, then in the (right) details panel change the animation class to your new `Anim_Ambulance` like this: +- ![AssignAnim](../Figures/EgoVehicle/AssignAnim.jpg) diff --git a/Docs/LODs.md b/Docs/Tutorials/LODs.md similarity index 95% rename from Docs/LODs.md rename to Docs/Tutorials/LODs.md index 41a0d0b..73abc63 100644 --- a/Docs/LODs.md +++ b/Docs/Tutorials/LODs.md @@ -8,7 +8,7 @@ Ever noticed how in major video games/3d programs most of the models/textures de Here's an example of the `SM_Tesla` static mesh provided by Carla | LOD 0 (14,406 triangles) | LOD 1 (3,601 triangles) | LOD 2 (1,799 triangles) | LOD 3 (864 triangles) | | ------------------------------ | ------------------------------ | ------------------------------ | ------------------------------ | -| ![LOD0](Figures/LODs/lod0.jpg) | ![LOD0](Figures/LODs/lod1.jpg) | ![LOD0](Figures/LODs/lod2.jpg) | ![LOD0](Figures/LODs/lod3.jpg) | +| ![LOD0](../Figures/LODs/lod0.jpg) | ![LOD0](../Figures/LODs/lod1.jpg) | ![LOD0](../Figures/LODs/lod2.jpg) | ![LOD0](../Figures/LODs/lod3.jpg) | ## Okay so what? While the default LOD settings are pretty good in Carla, this works because **Carla was not designed for VR** and expects to be run on a flat screen. However, we are using Carla in a VR setting, and it quickly becomes much more pronounced when models transform into lower/higher quality forms. This can be very distracting and immersion-breaking for the person in the headset. @@ -29,13 +29,13 @@ In order to actually access the LOD's for every blueprint, we're actually going For example, for the `SM_TeslaM3_v2` skeletal mesh (note there is also a `SM_Tesla` static mesh, the naming scheme is unfortunately not very consistent), head over to `Content/Carla/Static/Vehicles/4Wheeled/Tesla/` in the Content Browser to see the following folder layout: -![TeslaContent](Figures/LODs/tesla_content.jpg) +![TeslaContent](../Figures/LODs/tesla_content.jpg) Notice how the model underlined in **pink** is the skeletal mesh we are interested in. Double click it to open it in the Editor. Then, in the left, in the `Asset Details` pane (highlighted below in **red**) you can see the LOD Picker settings is currently set to Auto (LOD0) this will automatically compute and assign the LOD for this mesh based on your distance. You can see the current LOD settings in action in the top left of the preview window (highlighted below in **yellow**). -![TeslaSkeletal](Figures/LODs/tesla_skeletal.jpg) +![TeslaSkeletal](../Figures/LODs/tesla_skeletal.jpg) From the LOD picker you could check the `"Custom"` box and edit the individual LOD settings manually, but this is a lot of tedious work that would need to be applied to **every** static mesh individually. In this guide we'll try to avoid tedious work. @@ -48,7 +48,7 @@ If you don't have an existing LODSettings asset (we've provided one in [`Tools/L | LODSettings pre application | LODSettings post application | | ---------------------------------------------- | ----------------------------------------------- | -| ![LODSettings1](Figures/LODs/lod_settings.jpg) | ![LODSettings1](Figures/LODs/lod_settings2.jpg) | +| ![LODSettings1](../Figures/LODs/lod_settings.jpg) | ![LODSettings1](../Figures/LODs/lod_settings2.jpg) | Now you should be able to open up the newly created `LODSettings` asset (`SM_Vehicle_LODSettings`) in the editor and edit all the important LOD parameters from there. Here is where the fine-tuning for screen-size takes place as you can manually tune when transitions happen. ### NOTE @@ -66,7 +66,7 @@ Something to keep in mind is that different vehicles even have different number This should look something like the following (with LODGroups collapsed): - + Theoretically we should be able to have this class completely in C++ since it is a [`USkeletalMeshLODSettings`](https://docs.unrealengine.com/4.26/en-US/API/Runtime/Engine/Engine/USkeletalMeshLODSettings/) class. But it is fairly low on the priority list. @@ -81,7 +81,7 @@ The steps we recommend are as follows: 2. In the bottom right (View Options) uncheck the `Folders` option 3. In the top left click the `Filters` and check the `SkeletalMesh` option - Now you should see this (notice all pink underlined): - ![AllSkeletalMeshes](Figures/LODs/all_skeletal_meshes.jpg) + ![AllSkeletalMeshes](../Figures/LODs/all_skeletal_meshes.jpg) 4. Now select all the meshes **EXCEPT for the following** - Windows: 1. SM_Cybertruck_v2 @@ -91,14 +91,14 @@ The steps we recommend are as follows: 2. SK_ChargetCop 3. SK_lincolnv5 4. SK_MercedesCCC - ![AllSkeletalMeshesSelected](Figures/LODs/all_skeletal_meshes_selected.jpg) + ![AllSkeletalMeshesSelected](../Figures/LODs/all_skeletal_meshes_selected.jpg) - We are still unsure why, but these particular vehicles cause a segmentation fault (something to do with their vertex makeup) upon this application. You will need to manually set the LOD parameters for individual custom LOD's for each of them (ie. do NOT use the `SM_Vehicle_LODSettings.uasset` at all) 5. Right click any of the highlighted vehicles -> `Asset Actions` -> `Bulk Edit via Property Matrix` - ![BulkEditMatrix](Figures/LODs/bulk_edit_matrix.jpg) + ![BulkEditMatrix](../Figures/LODs/bulk_edit_matrix.jpg) 6. In the `Bulk Edit` window that opens up, verify all the correct skeletal meshes on the left, then in `LODSettings` on the right, click the 3x3 grid icon (Pick asset) and choose the newly created `SM_Vehicle_LODSettings.uasset` asset. 1. To apply this to all the selected skeletal meshes, go to the top bar -> `File` -> `Save` 2. The end result should look something like this: - ![BulkEdit](Figures/LODs/bulk_edit.jpg) + ![BulkEdit](../Figures/LODs/bulk_edit.jpg) As mentioned in step 4, some particular vehicles cause a seg-fault after giving them this `LODSettings`. We are still investigating why exactly but for now its safer to just manually go into each vehicle and tune the individual `LOD` settings after checking `Custom` and seeing the `LOD0`, `LOD1`, `LOD2`, ... etc. options. diff --git a/Docs/Model.md b/Docs/Tutorials/Model.md similarity index 90% rename from Docs/Model.md rename to Docs/Tutorials/Model.md index 52448b4..c884047 100644 --- a/Docs/Model.md +++ b/Docs/Tutorials/Model.md @@ -37,34 +37,34 @@ For steps 1 & 2, we will be using the free & open source Blender program for the First, go to the static mesh file you wish to export, in our case we wanted to export `$CARLA_ROOT/Unreal/CarlaUE4/Content/Carla/Static/Vehicles/4Wheeled/Tesla/SM_TeslaM3_v2.uasset` (notice these files should have a pink underline to indicate they are the full static mesh files). ### One LOD -I recommend using the highest LOD ([Level-Of-Detail](../LODS.md)) setting for this export, since this vehicle will be so close to the camera all the time it is pointless to have multiple LOD's, and it makes it simpler for the import to blender. +I recommend using the highest LOD ([Level-Of-Detail](../../LODS.md)) setting for this export, since this vehicle will be so close to the camera all the time it is pointless to have multiple LOD's, and it makes it simpler for the import to blender. To do this, simply enter the static mesh by double clicking it, and on the left "Asset Details" pane, down in "LOD Settings" drag the "Number of LODs" slider down to 1, then click "Apply Changes" as follows. -- ![LODs](Figures/Model/LOD1.jpg) +- ![LODs](../Figures/Model/LOD1.jpg) ### Export to blender Now, back in the `Content Browser` you can right click the file then select `Asset Actions -> Export` and designate a place for the resulting `.FBX` file to be exported. -- ![Export](Figures/Model/Export.jpg) +- ![Export](../Figures/Model/Export.jpg) ### Model in Blender Now, open a fresh Blender window and delete the default spawned cube. Then go to `File -> Import -> FBX (.fbx)` and select the file you just created. You should now be presented with a simple Blender window with the vehicle like this: -- ![BlenderSolid](Figures/Model/BlenderSolid.jpg) +- ![BlenderSolid](../Figures/Model/BlenderSolid.jpg) In order to toggle moving around using `WASD` controls, press `shift + ` `. Move inside the vehicle where you can find the steering wheel. The easiest way (I've found) to efficiently extract the steering wheel it so use the wireframe-mode to select all vertices, even those that aren't visible in the solid render. To go to wireframe mode press `z` then select `wireframe` (should be the left-most option). Then you should see something like this: -- ![WireframeWheel](Figures/Model/WireframeWheel.jpg) +- ![WireframeWheel](../Figures/Model/WireframeWheel.jpg) Then, to actually select the proper vertices, we're going to need to change from `Object Mode` to `Edit Mode` in the top left corner of the viewport. Then we'll need to position our camera in such a way to minimize unwanted vertices being selected, and use whatever selection technique we want (I like the lasso selection) to select the entire steering wheel like this: -- ![SelectedWheel](Figures/Model/SelectedWheel.jpg) +- ![SelectedWheel](../Figures/Model/SelectedWheel.jpg) NOTE: if you have excess vertices selected, you can always undo those with `shift+click` on individual vertices. Then, you should be able to move the entire bunch out of the vehicle (or duplicate them all with `shift+d` and clean up the original) to have something like this: | Wireframe | Rendered | | --- | --- | -| ![WireFrameGotWheel](Figures/Model/WheelOut.jpg) | ![SolidOut](Figures/Model/VehicleAndWheel.jpg) | +| ![WireFrameGotWheel](../Figures/Model/WheelOut.jpg) | ![SolidOut](../Figures/Model/VehicleAndWheel.jpg) | Finally, you should then be able to export the individual selections (need to export both the just-wheel and the just-vehicle models) by selecting all the vertices the same way (in wireframe) and deleting them (then undo-ing the deletion of course). Then selecting `File -> Export -> FBX(.fbx)` for best compatibility. Do this for both the Vehicle mesh as well as the steering wheel (I moved the steering wheel to the origin when exporting but I'm not sure this is necessary). @@ -83,7 +83,7 @@ In this animation blueprint, ensure the following: | Reparent | Animation | | --- | --- | -| ![Reparent](Figures/Model/AnimClassOption.jpg) | ![AnimGraph](Figures/Model/AnimGraph.jpg) | +| ![Reparent](../Figures/Model/AnimClassOption.jpg) | ![AnimGraph](../Figures/Model/AnimGraph.jpg) | Now you are done with the animation blueprint. @@ -97,7 +97,7 @@ Then finally, you can delete the newly imported PhysicsAsset file since it is no And in `BP_EgoVehicle_DReyeVR`, you can finally edit the `Mesh (Inherited) -> Details -> Mesh` field to use the new SM we just updated (pink underline). Since this clears the `Animation` section, you'll also need to update the `Mesh (Inherited) -> Animation -> Anim Class` field to use the new animation class we just made. Now the DReyeVR EgoVehicle should be fully drivable and operates just as it did before, but now with no steering wheel in the driver's seat! -![NoWheel](Figures/Model/NoWheel.jpg) +![NoWheel](../Figures/Model/NoWheel.jpg) ## 3. Re-attach the steering wheel dynamically ### Import to UE4 @@ -110,16 +110,16 @@ To get rotations of the wheel to be in the Roll axis of the wheel itself (not it This will allow you to create a plain simple static mesh (cyan underline) from the skeletal mesh (pink underline) as follows: | Rotated Skeletal Mesh | Resulting Directory | | --- | --- | -| ![RotWheel](Figures/Model/WheelRot.jpg) | ![SelectedWheel](Figures/Model/SelectSMWheel.jpg) | +| ![RotWheel](../Figures/Model/WheelRot.jpg) | ![SelectedWheel](../Figures/Model/SelectSMWheel.jpg) | ### Import in code 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/DReyeVR/EgoVehicle/model3/SteeringWheel/Wheel_StaticMeshl_model3.Wheel_StaticMeshl_model3'"` +- `"StaticMesh'/Game/DReyeVR/EgoVehicle/TeslaM3/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 (See [EgoVehicle::ConstructSteeringWheel & EgoVehicle::TickSteeringWheel](../DReyeVR/EgoVehicle.cpp)) +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/SetupVR.md b/Docs/Tutorials/SetupVR.md similarity index 100% rename from Docs/SetupVR.md rename to Docs/Tutorials/SetupVR.md diff --git a/Docs/Signs.md b/Docs/Tutorials/Signs.md similarity index 85% rename from Docs/Signs.md rename to Docs/Tutorials/Signs.md index ab3d412..040d5e5 100644 --- a/Docs/Signs.md +++ b/Docs/Tutorials/Signs.md @@ -3,7 +3,7 @@ ## What is this? It is often useful to have participants in an experiment know what directions to take in a natural manner without manual intervention. In Carla this is not a problem since all the drivers are AI controllers, but for humans we can't simply ingest a text file denoting waypoints and directions. This is where in-environment directional signs can be of use. Unfortunately, Carla does not provide any (since this is not a problem for them) and there were enough steps to warrant a guide, so here you go. -This guide will show you how to create your own custom signs and place them in any Carla level. +This guide will show you how to create your own custom signs and place them in any Carla level (*Technically, the guide can work to add any custom props in Carla, not just signs*) - The steps are as follows: 1. Create the sign textures (rgb/normals) 2. Create the sign mesh/material @@ -16,19 +16,19 @@ Sign textures can be found in Carla in the `carla/Unreal/CarlaUE4/Content/Carla/ For example, you should see a directory that looks like this: -![SignDirectory](Figures/Signs/directory.jpg) +![SignDirectory](../Figures/Signs/directory.jpg) Notice how all the models have a corresponding directory (some are cut off in the screenshot). These are where the static meshes and textures are defined so they can be used on these sign-shaped blueprints. - For the rest of this guide, we'll focus on using the `NoTurn` directory that looks like this when opened in the content browser: -![NoTurnDir](Figures/Signs/no_turn_dir.jpg) +![NoTurnDir](../Figures/Signs/no_turn_dir.jpg) - From left to right these are the **Material Instance** (`M_` prefix), **Static Mesh** (`SM_` prefix), **Texture RGB** (`__0` suffix), and **Texture Normals** (`_n` suffix) ## Step 1: Creating the sign textures The "NO TURN" sign serves as a good baseline for creating our custom signs, though any signs can be used as a starting point. -Now, you can screenshot the image (or find its source file in Details->File Path) to get a `.jpg` of the desired texture, then clear out the original text ("NO TURN") so it is a blank canvas. For your convenience we have a blank "NO TURN" sign already provided in [`Content/Static/DefaultSign.jpg`](../Content/Static/DefaultSign.jpg) +Now, you can screenshot the image (or find its source file in Details->File Path) to get a `.jpg` of the desired texture, then clear out the original text ("NO TURN") so it is a blank canvas. For your convenience we have a blank "NO TURN" sign already provided in [`Content/Static/DefaultSign.jpg`](../../Content/Static/DefaultSign.jpg) - Notice how the bottom right corner of these images has is a small gray-ish region. This is actually for the rear of the sign so that when it is applied on to the models, the rear has this metallic surface. - This means we want to do most of our sign content editing in the region within the black perimeter @@ -40,7 +40,7 @@ Next, you'll want GIMP to create the normals map for you. This can be done easil For example, if we wanted our sign to say "RIGHT TO CITY A", then after this process you should see something that looks like this: -![SignTextures](Figures/Signs/textures_no_turn.jpg) +![SignTextures](../Figures/Signs/textures_no_turn.jpg) Now we are done with image manipulation and using GIMP. @@ -61,7 +61,7 @@ Now back in UE4, it'll be easiest if you duplicate the `TrafficSign/NoTurn/` dir | | | | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------ | -| Now, in your new custom directory, you can easily reimport a new `.jpg` source file by clicking the `Reimport` button at the top.

Locate your rgb `.jpg` image for the `SM_noTurn` reimport, and use the normals `.jpg` image for the `SM_noTurn_n` reimport. | Reimport | +| Now, in your new custom directory, you can easily reimport a new `.jpg` source file by clicking the `Reimport` button at the top.

Locate your rgb `.jpg` image for the `SM_noTurn` reimport, and use the normals `.jpg` image for the `SM_noTurn_n` reimport. | Reimport | Feel free to rename the `SM_noTurn_*` asset files **within the editor** (right click in content browser -> rename) and keep the naming scheme. Something like `SM_RightCityA` and `SM_RightCityA_n`. @@ -69,19 +69,19 @@ Feel free to rename the `SM_noTurn_*` asset files **within the editor** (right c Now, you should make sure that the **Material** (`M_noTurns`) asset file is updated with the new textures. This may occur automatically, but just in case you should open it up in the editor and select the newly created `SM_RightCityA` and `SM_RightCityA_n` as the Texture parameter values for `SpeedSign_d` and `SpeedSign_n` respectively. - To do this, click the dropdown menu box which say `SM_noTurn` and `SM_noTurn_n` and search for the new `RightCityA` variants - The parameters should then look something like this - ![Parameters](Figures/Signs/parameters.jpg) + ![Parameters](../Figures/Signs/parameters.jpg) Save it and rename it (**in the editor**) as well: `M_RightCityA` should suffice. Now, finally open up the `SM_noTurn_` (static mesh) asset file and ensure it uses our newly created `M_RightCityA` material by editing the Material element in the Material Slots: - Similarly to before, this is done in the Details pane by clicking the dropdown, searching for "RightCity", and selecting our new material - ![SignMaterial](Figures/Signs/material.jpg) + ![SignMaterial](../Figures/Signs/material.jpg) Save it and rename it (always **in the editor**): `SM_RightCityA_` works. At this point you should have a `RightCityA` directory that looks like the following: -![RightCityDir](Figures/Signs/rightcity_directory.jpg) +![RightCityDir](../Figures/Signs/rightcity_directory.jpg) ## Step 3: Applying the new materials onto a blueprint @@ -94,7 +94,7 @@ In the Details pane you should again see a `Static Mesh` component that is still Now it should look like this: -![SignBP](Figures/Signs/bp.jpg) +![SignBP](../Figures/Signs/bp.jpg) ## Step 4: Placing the new sign in the world @@ -104,7 +104,7 @@ The end result should look pretty decent, here's an example of our new sign in ` | Front of the sign | Rear of the sign | | ------------------------------------------- | ----------------------------------------- | -| ![FrontSign](Figures/Signs/right_front.jpg) | ![RearSign](Figures/Signs/right_rear.jpg) | +| ![FrontSign](../Figures/Signs/right_front.jpg) | ![RearSign](../Figures/Signs/right_rear.jpg) | Notice how both the front and rear look good, this is because the rear is given the metallic region from the bottom-right of the texture. @@ -147,3 +147,9 @@ world.spawn_actor(bp[0], transform) # should succeed with no errors - This is supported within the editor by placing both actors into the world, selecting both, then using the Window -> Developer -> MergeActors button as described in [this guide](https://docs.unrealengine.com/4.27/en-US/Basics/Actors/Merging/). - We have already provided a baseline with the [`Content/DReyeVR_Signs/FullSign/`](Content/DReyeVR_Signs/FullSign/) directory where we combined the signs with the poles as a single static mesh. - With this baseline, assuming you have a compatible material (using the same sign template as ours) you can just update the material for the sign component without further modification. + + +# Automatic Sign Placement +When using our [scenario-runner fork](https://github.com/HARPLab/scenario_runner/tree/DReyeVR-0.9.13), there is logic to enable spawning the corresponding directional signs automatically according to the route features (straight, turn left, turn right, and goal). The logic for this can be found in the [route_scenario's nav sign code](https://github.com/HARPLab/scenario_runner/blob/3b5e60f15fd97de00332f80610051f9f39d7db8c/srunner/scenarios/route_scenario.py#L284-L355). Since this is automatically applied to all routes, you can disable it manually by commenting the `self._setup_nav_signs(self.route)` method call. + +There is also a file method in case you want to manually place signs for specific routes (see [here](https://github.com/HARPLab/scenario_runner/blob/DReyeVR-0.9.13/srunner/data/all_routes_signs.json)), but we found that the automatic sign placement works fine most of the time and is much more convenient. So the automatic method is recommended and you don't have to do anything to enable it. \ No newline at end of file diff --git a/Docs/Sounds.md b/Docs/Tutorials/Sounds.md similarity index 94% rename from Docs/Sounds.md rename to Docs/Tutorials/Sounds.md index cfe17b5..11b5ffe 100644 --- a/Docs/Sounds.md +++ b/Docs/Tutorials/Sounds.md @@ -21,7 +21,7 @@ One of the best feedback mechanisms for a user applying throttle is the roar of - For all these tracks, we'll start with a sole TripleOscillator playing a constant C2 octave (4 beats should be fine). | Configuration | Visually | | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | --------------------------------------------------------- | - | PM value for OSC1+OSC2
PM value for OSC2+OSC3
OSC1 volume of 60
OSC1 CRS of -4
OSC1 to use triangle wave
OSC2 CRS of -24
OSC3 CRS of -24

Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) | ![TripleOscillator](Figures/Sounds/triple_oscillator.jpg) | + | PM value for OSC1+OSC2
PM value for OSC2+OSC3
OSC1 volume of 60
OSC1 CRS of -4
OSC1 to use triangle wave
OSC2 CRS of -24
OSC3 CRS of -24

Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) | ![TripleOscillator](../Figures/Sounds/triple_oscillator.jpg) | - Then we'll want to amplify this effect by adding an LMMS-type Amplifier from the FX-Mixer window and crank the volume to the max. 1. This works for the idle engine sound, nothing more to do here. The remaining drive sounds will gradually increase their CRS values. 2. For Drive1 change OSC1 CRS to 0, OSC2 CRS to -20, OSC3 CRS to -20. @@ -38,7 +38,7 @@ One of the best feedback mechanisms for a user applying throttle is the roar of 1. When looping, you'll probably hear a sudden snap/click sound on every repeat, this is due to wave discontinuities 3. We'll want to find where the sound starts/ends and make sure the wave approximately matches so as to have a continuous transition between repetitions. 1. This can be done by finding patterns from the beginning and cutting off the minimum amount from the track such that a new pattern would fit in as soon as the track ended. -![Audacity](Figures/Sounds/audacity_wave.jpg) +![Audacity](../Figures/Sounds/audacity_wave.jpg) Image source: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) 1. After you cut all the tracks to be seamlessly loopable, export them to new `.wav`'s and these are ready to be taken in to the UE4 and used as vehicle noises. ### Applying the sounds in UE4 @@ -49,7 +49,7 @@ Image source: [ContinueBreak](https://continuebreak.com/articles/generating-sett 2. Attach a **Continuous Modulator** node to each output from the Looping Wave Player's 1. The parameters for these Continuous Modulators define the range of input/output for these tracks (value min/max) 2. **NOTE** all the params have the same name `"RPM"` it is very important this is consistent as it will be used in the `C++` code - ![SoundCue](Figures/Sounds/sound_cue.jpg) + ![SoundCue](../Figures/Sounds/sound_cue.jpg) - Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) - These are the recommended parameter values from the guide. @@ -78,7 +78,7 @@ Image source: [ContinueBreak](https://continuebreak.com/articles/generating-sett 2. Change the **Falloff Distance** 3000 2. Back in the **Sound Cue** asset from step 2, scroll down in the Details pane and use the newly created **Sound Attenuation** asset as its Attenuation Settings: - ![SoundAttenuation](Figures/Sounds/sound_attenuation.jpg) + ![SoundAttenuation](../Figures/Sounds/sound_attenuation.jpg) - Image credits: [ContinueBreak](https://continuebreak.com/articles/generating-setting-basic-engine-sounds-ue4-part-12/) ## Other vehicle noises @@ -89,13 +89,13 @@ Generally, adding sounds can get complicated like the above, or they can be very - Similarly, adding sounds for **turn-signals** is essentially the same: - Just need to import the sounds, find them in code, and play them on our desired events -To see how we implemented our audio components in DReyeVR (for both the ego-vehicle as well as the baseline CarlaWheeledVehicle) check out [`EgoVehicle.h`](../DReyeVR/EgoVehicle.h) and [`CarlaWheeledVehicle.h`](../Carla/Vehicle/CarlaWheeledVehicle.h) +To see how we implemented our audio components in DReyeVR (for both the ego-vehicle as well as the baseline CarlaWheeledVehicle) check out [`EgoVehicle.h`](../../DReyeVR/EgoVehicle.h) and [`CarlaWheeledVehicle.h`](../../Carla/Vehicle/CarlaWheeledVehicle.h) ## Ambient noise in the World It's also doable (and fairly easy) to have ambient noise in the world that attenuates based on the distance to the source. For reference, our provided Town03 has sound cues like this: -![WorldSound](Figures/Sounds/sound_selected.jpg) +![WorldSound](../Figures/Sounds/sound_selected.jpg) Notice that once you drag & drop the sounds into the world, make sure to enable the **Override Attenuation** checkbox so you can edit the attenuation function, shape, and radius. - The Inner Radius denotes the region where the volume is maximized @@ -113,17 +113,17 @@ Our general strategy for simple ambient noise in the world follows these basic r For custom tuning the attenuation parameters, see the `Details` pane after spawning an AmbientSound instance. It is also recommended to see this [Unreal Engine documentation on Audio Attenuation](https://docs.unrealengine.com/en-US/WorkingWithMedia/Audio/DistanceModelAttenuation/index.html) | Example attenuation parameter settings | Bird sounds selected | | --- | --- | -| ![BirdAttenuation](Figures/Sounds/bird_attenuation.jpg) | ![BirdAttenuation](Figures/Sounds/bird_selected.jpg)
In the World Outliner simply searching for "Sound" returns all AmbientSound instances | +| ![BirdAttenuation](../Figures/Sounds/bird_attenuation.jpg) | ![BirdAttenuation](../Figures/Sounds/bird_selected.jpg)
In the World Outliner simply searching for "Sound" returns all AmbientSound instances | For reference, our birds ambient noise for Town03 looks like the following: -![BirdAttenuation](Figures/Sounds/bird_world.jpg) +![BirdAttenuation](../Figures/Sounds/bird_world.jpg) It is difficult to see the orange lines denoting our attenuation spheres, but all three are selected and displayed (generally over all grassy patches). We also added other custom sounds such as slight water splashing (works well with the fountain in the middle). Additionally, some maps are surrounded by water, this poses a challenge because often the coasts are very curvy and keeping a 3D sound spatialization only works if the sound is general enough to be emitting from the general body of water. This works great for the fountain where the water is symmetric, but require more granularly placed AmbientSounds in the world as follows (Town04): -![WaterWorld](Figures/Sounds/water_world.jpg) +![WaterWorld](../Figures/Sounds/water_world.jpg) It is more tedious to place these smaller & more granular sound components in the world, but they make for a much better experience and are relatively quick to edit (just copy & paste & move around). diff --git a/Docs/Usage.md b/Docs/Usage.md index fb9e9c8..7c240f8 100644 --- a/Docs/Usage.md +++ b/Docs/Usage.md @@ -136,6 +136,7 @@ cd $CARLA_ROOT/PythonAPI/examples/ # saves output (stdout) to recorder.txt ./show_recorder_file_info.py -a -f /PATH/TO/RECORDER-FILE > recorder.txt ``` + - With this `recorder.txt` file (which holds a human-readable dump of the entire recording log) you can parse this file into useful python data structures (numpy arrays/pandas dataframes) by using our [DReyeVR parser](https://github.com/harplab/dreyevr-parser). ## Replaying Begin a replay session through the PythonAPI as follows: ```bash @@ -152,6 +153,8 @@ Begin a replay session through the PythonAPI as follows: To get accurate screenshots for every frame of the recording, see below with [synchronized replay frame capture](#synchronized-replay-frame-capture) +**NOTE** We use custom config files for global and vehicle parameters in the simulator (see [below](Usage.md#using-our-custom-config-file)) and we also store these parameters in the recording file so that we can verify they are the same as the replay. For instance, we will automatically compare the recording's parameters versus the live parameters when performing a replay. Then if we detect any differences, we will print these as warnings so you can be aware. For instance, if you recorded with a particular vehicle and replay the simulator with a different vehicle loaded, we will let you know that the replay may be inaccurate and you are in uncharted territory. + ## Scenarios It is usually ideal to have curated experiments in the form of scenarios parsed through [ScenarioRunner](https://carla-scenariorunner.readthedocs.io/en/latest/). @@ -228,7 +231,7 @@ Summary: # Using our custom config file Throughout development, we found that modifying even small things in DReyeVR have a LONG cycle time for recompilation/re-linking/re-cooking/etc. so we wanted an approach that could greatly ease this burden while still providing flexibility. -This is why we developed the [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) param file and associated helper functions in [`DReyeVRUtils.h`](../DReyeVR/DReyeVRUtils.h) so we could simply read the file at runtime and modify small params from the internal code without recompilation. +This is why we developed the [`ConfigFile`](../DReyeVR/ConfigFile.h) class and corresponding [`DReyeVRConfig.ini`](../Configs/DReyeVRConfig.ini) (and per-vehicle) "params" so we could read the file at runtime to set variables in the simulator without recompilation. The procedure to use our params API is simple: ```c++ @@ -242,35 +245,45 @@ class CARLAUE4_API AEgoVehicle : public ACarlaWheeledVehicle float MyFavouriteNumber; // <--Your new param } ``` -Then, in that class' constructor (typically) or BeginPlay, or technically anywhere in the source, since this occurs at runtime (but you usually don't want to use uninitialized data members) + +Then, choose which type of config file this variable falls into, currently we have two kinds of primary config files: simulator-wide `GeneralParams`, and per-vehicle `VehicleParams`. + +The `GeneralParams` can be thought of as a global simulator-wide configuration file that can be accessed from anywhere, while the `VehicleParams` are specifically for a particular EgoVehicle (such as locations/specifications) that can be found in [`Config/EgoVehicles/`](../Config/EgoVehicles/) that matches the available DReyeVR EgoVehicles. To learn more about these see [EgoVehicle.md](EgoVehicles.md). + +(For general params) +```ini +[MyFavourites] +Number=867.5309 # You can also write comments! +``` +Then, anywhere you want, you can get the parameter by specifying both the section and variable name: ```c++ -// ex: EgoVehicle.cpp: -AEgoVehicle::AEgoVehicle(const FObjectInitializer &ObjectInitializer) : Super(ObjectInitializer) +void AEgoVehicle::SomeFunction() { - // don't modify, just note this is called in the constructor - ReadConfigVariables(); + // can use this format to assign directly into a variable + MyFavouriteNumber = GeneralParams.Get("MyFavourites", "Number"); + + // or pass the variable by reference and get whether or not the Get operation was successful + bool bSuccess = GeneralParams.Get("MyFavourites", "Number", MyFavouriteNumber); - ... // existing code } +``` -void AEgoVehicle::ReadConfigVariables() -{ - ... // existing code +If you are using vehicle-specific params, then this needs to be in the context of some EgoVehicle +```c++ - // ReadConfigValue("YourSectionHeader", "YourVariableName", Variable); - ReadConfigValue("MyFavourites", "Number", MyFavouriteNumber); +void SomeClass::SomeOtherFunction(AEgoVehicle *Vehicle){ + // VehicleParams is a public member of + const ConfigFile &VehicleSpecificParams = Vehicle->GetVehicleParams(); + int VehicleParam = VehicleSpecificParams.Get("VehicleParamSection", "VariableName"); } ``` -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 # 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. +Another useful feature we built-in is to import, export, and compare the config files. This is useful because we can track the config file(s) that were used while a particular example was recorded, then if you are trying to replay this scenario with *different* configuration parameters (ex. using a different vehicle, or with mirrors enabled when they werent in the recording), some warnings will be presented when comparing (diff) the recorded config file (saved in the .log file) and the live one (what is currently running). + # Synchronized replay frame capture ## 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. @@ -302,13 +315,14 @@ python start_replaying.py -f /PATH/TO/RECORDING/FILE # windows # Other guides We have written other guides as well that serve more particular needs: - See [`F.A.Q. wiki`](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) for our Frequently Asked Questions wiki page. -- See [`Docs/SetupVR.md`](SetupVR.md) to learn how to quickly and minimally set up VR with Carla -- See [`Docs/Sounds.md`](Sounds.md) to see how we added custom sounds and how you can add your own custom sounds -- See [`Docs/Signs.md`](Signs.md) to add custom in-world directional signs and dynamically spawn them into the world at runtime +- See [`SetupVR.md`](Tutorials/SetupVR.md) to learn how to quickly and minimally set up VR with Carla +- See [`Sounds.md`](Tutorials/Sounds.md) to see how we added custom sounds and how you can add your own custom sounds +- See [`Signs.md`](Tutorials/Signs.md) to add custom in-world directional signs and dynamically spawn them into the world at runtime - See [`Shaders/README.md`](../Shaders/README.md) to view our post-processing shaders and learn how to use them -- See [`Docs/CustomActor.md`](CustomActor.md) to use our CustomActor classes to use fully-recordable 3D dynamic elements in your scene -- See [`Docs/Model.md`](Model.md) to see how we added a responsive steering wheel to the vehicle mesh -- See [`Docs/LODs.md`](LODs.md) to learn how we tune the Level-Of-Detail modes for vehicles for a more enjoyable VR experience +- See [`CustomActor.md`](Tutorials/CustomActor.md) to use our CustomActor classes to use fully-recordable 3D dynamic elements in your scene +- See [`Model.md`](Tutorials/Model.md) to see how we added a responsive steering wheel to the vehicle mesh +- See [`CustomEgo.md`](Tutorials/CustomEgo.md) to add your own custom EgoVehicle model to DReyeVR +- See [`LODs.md`](Tutorials/LODs.md) to learn how we tune the Level-Of-Detail modes for vehicles for a more enjoyable VR experience # Quirks: diff --git a/PythonAPI/examples/DReyeVR_AI.py b/PythonAPI/examples/DReyeVR_AI.py index 8bd7da6..4506d9a 100755 --- a/PythonAPI/examples/DReyeVR_AI.py +++ b/PythonAPI/examples/DReyeVR_AI.py @@ -1,30 +1,10 @@ -#!/usr/bin/env python - -import glob -import os -import sys import time - -try: - sys.path.append( - glob.glob( - "../carla/dist/carla-*%d.%d-%s.egg" - % ( - sys.version_info.major, - sys.version_info.minor, - "win-amd64" if os.name == "nt" else "linux-x86_64", - ) - )[0] - ) -except IndexError: - pass - -import carla - import argparse from numpy import random from DReyeVR_utils import find_ego_vehicle +import carla + def set_DReyeVR_autopilot(world, traffic_manager): DReyeVR_vehicle = find_ego_vehicle(world) diff --git a/PythonAPI/examples/DReyeVR_logging.py b/PythonAPI/examples/DReyeVR_logging.py index 890b85e..c0c0159 100755 --- a/PythonAPI/examples/DReyeVR_logging.py +++ b/PythonAPI/examples/DReyeVR_logging.py @@ -1,10 +1,7 @@ -#!/usr/bin/env python - import argparse import numpy as np import time import sys -import glob import os from DReyeVR_utils import DReyeVRSensor @@ -16,20 +13,6 @@ String = None print("Rospy not initialized. Unable to use ROS for logging") -try: - sys.path.append( - glob.glob( - "../carla/dist/carla-*%d.%d-%s.egg" - % ( - sys.version_info.major, - sys.version_info.minor, - "win-amd64" if os.name == "nt" else "linux-x86_64", - ) - )[0] - ) -except IndexError: - pass - import carla diff --git a/PythonAPI/examples/DReyeVR_utils.py b/PythonAPI/examples/DReyeVR_utils.py index cb8198c..604e9ea 100644 --- a/PythonAPI/examples/DReyeVR_utils.py +++ b/PythonAPI/examples/DReyeVR_utils.py @@ -1,51 +1,75 @@ +from typing import Optional, Any, Dict, List +import carla import numpy as np -from typing import Any, Dict, List, Optional - -import sys -import glob -import os - -try: - sys.path.append( - glob.glob( - "../carla/dist/carla-*%d.%d-%s.egg" - % ( - sys.version_info.major, - sys.version_info.minor, - "win-amd64" if os.name == "nt" else "linux-x86_64", - ) - )[0] - ) -except IndexError: - pass +import time -import carla +import sys, os +sys.path.append(os.path.join(os.getenv("CARLA_ROOT"), "PythonAPI")) +import examples # calls ./__init__.py to add all the necessary things to path def find_ego_vehicle(world: carla.libcarla.World) -> Optional[carla.libcarla.Vehicle]: - DReyeVR_vehicle = None - 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? + DReyeVR_vehicles: str = "harplab.dreyevr_vehicle.*" + ego_vehicles_in_world = list(world.get_actors().filter(DReyeVR_vehicles)) + if len(ego_vehicles_in_world) >= 1: + print( + f"Found a DReyeVR EgoVehicle in the world ({ego_vehicles_in_world[0].id})" + ) + return ego_vehicles_in_world[0] + + DReyeVR_vehicle: Optional[carla.libcarla.Vehicle] = None + available_ego_vehicles = world.get_blueprint_library().filter(DReyeVR_vehicles) + if len(available_ego_vehicles) == 1: + bp = available_ego_vehicles[0] + print(f'Spawning only available EgoVehicle: "{bp.id}"') 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) + print( + f"Found {len(available_ego_vehicles)} available EgoVehicles. Which one to use?" + ) + for i, ego in enumerate(available_ego_vehicles): + print(f"\t[{i}] - {ego.id}") + print() + ego_choice = f"Pick EgoVehicle to spawn [0-{len(available_ego_vehicles) - 1}]: " + i: int = int(input(ego_choice)) + assert 0 <= i < len(available_ego_vehicles) + bp = available_ego_vehicles[i] + i: int = 0 + spawn_pts = world.get_map().get_spawn_points() + while DReyeVR_vehicle is None: + print(f'Spawning DReyeVR EgoVehicle: "{bp.id}" at {spawn_pts[i]}') + DReyeVR_vehicle = world.spawn_actor(bp, transform=spawn_pts[i]) + i = (i + 1) % len(spawn_pts) return DReyeVR_vehicle def find_ego_sensor(world: carla.libcarla.World) -> Optional[carla.libcarla.Sensor]: - sensor = None - 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 + def get_world_sensors() -> list: + return list(world.get_actors().filter("harplab.dreyevr_sensor.*")) + + ego_sensors: list = get_world_sensors() + if len(ego_sensors) == 0: + # no EgoSensors found in world, trying to spawn EgoVehicle (which spawns an EgoSensor) + if find_ego_vehicle(world) is None: # tries to spawn an EgoVehicle + raise Exception( + "No EgoVehicle (nor EgoSensor) found in the world! EgoSensor needs EgoVehicle as parent" + ) + # in case we had to spawn the EgoVehicle, this effect is not instant and might take some time + # to account for this, we allow some time (max_wait_sec) to continuously ping the server for + # an updated actor list with the EgoSensor in it. + + start_t: float = time.time() + # maximum time to keep checking for EgoSensor spawning after EgoVehicle + maximum_wait_sec: float = 10.0 # might take a while to spawn EgoVehicle (esp in VR) + while len(ego_sensors) == 0 and time.time() - start_t < maximum_wait_sec: + # EgoVehicle should now be present, so we can try again + ego_sensors = get_world_sensors() + time.sleep(0.1) # tick to allow the server some time to breathe + if len(ego_sensors) == 0: + raise Exception("Unable to find EgoSensor in the world!") + assert len(ego_sensors) > 0 # should have spawned with EgoVehicle at least + if len(ego_sensors) > 1: + print("[WARN] There are >1 EgoSensors in the world! Defaulting to first") + return ego_sensors[0] # always return the first one? class DReyeVRSensor: @@ -77,7 +101,7 @@ def spawn(cls, world: carla.libcarla.World): # TODO: check if dreyevr sensor already exsists, then use it # spawn a DReyeVR sensor and begin listening if find_ego_sensor(world) is None: - bp = [x for x in world.get_blueprint_library().filter("sensor.dreyevr*")] + bp = list(world.get_blueprint_library().filter("harplab.dreyevr_sensor.*")) try: bp = bp[0] except IndexError: diff --git a/PythonAPI/examples/__init__.py b/PythonAPI/examples/__init__.py new file mode 100644 index 0000000..9cb5c4f --- /dev/null +++ b/PythonAPI/examples/__init__.py @@ -0,0 +1,28 @@ +import os, sys, glob +from typing import List + +CARLA_ROOT: str = os.getenv("CARLA_ROOT") +if CARLA_ROOT is None: + raise Exception("Unable to find CARLA_ROOT in environment variable!") + +"""Add Carla PythonAPI .egg file""" +egg_dir: str = os.path.join(CARLA_ROOT, "PythonAPI", "carla", "dist") +carla_eggs: List[str] = glob.glob(os.path.join(egg_dir, f"carla-*.egg")) +for egg in carla_eggs: + sys.path.append(egg) +if len(carla_eggs) == 0: + print(f'No PythonAPI .egg file in "{egg_dir}"') + print("Make sure you built PythonAPI and an .egg was produced!") + +"""Add all Carla paths required by module""" +# see https://carla-scenariorunner.readthedocs.io/en/latest/getting_scenariorunner/#update-from-source +sys.path.extend( + [ + os.path.join(CARLA_ROOT, "PythonAPI", "carla", "agents"), + os.path.join(CARLA_ROOT, "PythonAPI", "carla"), + os.path.join(CARLA_ROOT, "PythonAPI", "examples"), + os.path.join(CARLA_ROOT, "PythonAPI"), + ] +) + +print("Carla import successful!") diff --git a/PythonAPI/examples/schematic_mode.py b/PythonAPI/examples/schematic_mode.py index fdd6340..d62f10d 100755 --- a/PythonAPI/examples/schematic_mode.py +++ b/PythonAPI/examples/schematic_mode.py @@ -1,25 +1,5 @@ -#!/usr/bin/env python - - -import glob -import os -import sys from typing import Any, Dict -try: - sys.path.append( - glob.glob( - "../carla/dist/carla-*%d.%d-%s.egg" - % ( - sys.version_info.major, - sys.version_info.minor, - "win-amd64" if os.name == "nt" else "linux-x86_64", - ) - )[0] - ) -except IndexError: - pass - from DReyeVR_utils import DReyeVRSensor, find_ego_vehicle import no_rendering_mode from no_rendering_mode import ( diff --git a/PythonAPI/examples/start_recording.py b/PythonAPI/examples/start_recording.py index b1e0f8a..4e43245 100755 --- a/PythonAPI/examples/start_recording.py +++ b/PythonAPI/examples/start_recording.py @@ -78,14 +78,6 @@ def main(): client.set_timeout(2.0) world = client.get_world() blueprints = world.get_blueprint_library().filter('vehicle.*') - # never spawn another dreyevr vehicle! - blueprints = [x for x in blueprints if "dreyevr" not in x.id] - assert blueprints is not None - - # NO FIXED TIMESTEP (DEBUG ONLY) - settings = world.get_settings() - settings.fixed_delta_seconds = 0.0 - world.apply_settings(settings) spawn_points = world.get_map().get_spawn_points() random.shuffle(spawn_points) @@ -146,7 +138,6 @@ def main(): else: while True: world.wait_for_tick() - # time.sleep(0.1) finally: diff --git a/README.md b/README.md index f09c7eb..295c8e9 100644 --- a/README.md +++ b/README.md @@ -13,7 +13,6 @@ This project extends the [`Carla`](https://github.com/carla-simulator/carla/tree If you have questions, hopefully our [F.A.Q. wiki page](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) and [issues page](https://github.com/HARPLab/DReyeVR/issues?q=is%3Aissue+is%3Aclosed) 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) with Unreal Engine 4.26 -- (upcoming DReyeVR versions will support the newer Carla versions) ## Highlights ### Ego Vehicle @@ -25,13 +24,15 @@ Fully drivable **virtual reality (VR) ego-vehicle** with [SteamVR integration](h | [HTC Vive Pro Eye](https://business.vive.com/us/product/vive-pro-eye-office/) | :white_check_mark: | :white_check_mark: | Windows, Linux | | [Quest 2](https://www.oculus.com/quest-2/) | :white_check_mark: | :x: | Windows | - While we haven't tested other headsets, they should still work for basic VR usage (not eye tracking) if supported by SteamVR. + - Eye tracking is currently **ONLY** supported on the HTC Vive Pro Eye since we use [SRanipal](https://forum.htc.com/topic/5641-sranipal-faq/) for the eye-tracker SDK. We are happy to support more devices through contributions for adding other SDKs. - Vehicle controls: - Generic keyboard WASD + mouse - Support for Logitech Steering wheel with this open source [LogitechWheelPlugin](https://github.com/HARPLab/LogitechWheelPlugin) - Includes force-feedback with the steering wheel. - We used a [Logitech G923 Racing Wheel & Pedals](https://www.logitechg.com/en-us/products/driving/driving-force-racing-wheel.html) - Full list of supported devices can be found [here](https://github.com/HARPLab/LogitechWheelPlugin/blob/master/README.md) though we can't guarantee out-of-box functionality without testing. -- Realistic (and parameterizable) rear & side view mirrors (WARNING: very performance intensive) +- Realistic (and parameterizable) rear & side view mirrors + - WARNING: very performance intensive - Vehicle dashboard: - Speedometer (in miles-per-hour by default) - Gear indicator @@ -105,14 +106,10 @@ See [`Docs/Install.md`](Docs/Install.md) to: ## Documentation & Guides - See [`F.A.Q. wiki`](https://github.com/HARPLab/DReyeVR/wiki/Frequently-Asked-Questions) for our Frequently Asked Questions wiki page. +- See [`Install.md`](Docs/Install.md) to install and build DReyeVR - See [`Usage.md`](Docs/Usage.md) to learn how to use our provided DReyeVR features - See [`Development.md`](Docs/Development.md) to get started with DReyeVR development and add new features -- See [`Sounds.md`](Docs/Sounds.md) to use our custom sounds to CARLA and create your own -- See [`CustomActor.md`](Docs/CustomActor.md) to use our CustomActor API and spawn "Overlay" actors -- See [`Model.md`](Docs/Model.md) to learn how we added a dynamic steering wheel to the ego vehicle -- See [`Signs.md`](Docs/Signs.md) to add custom in-world directional signs and spawn them -- See [`LODs.md`](Docs/LODs.md) to learn about LOD modes for tuning your VR experience - +- See [`Docs/Tutorials/`](Docs/Tutorials/) to view several DReyeVR tutorials such as customizing the EgoVehicle, adding custom signs/props and more. ## Citation If you use our work, please cite the corresponding [paper](https://arxiv.org/abs/2201.01931): diff --git a/Scripts/Paths/DReyeVR.csv b/Scripts/Paths/DReyeVR.csv index b3214cf..71d0ceb 100644 --- a/Scripts/Paths/DReyeVR.csv +++ b/Scripts/Paths/DReyeVR.csv @@ -3,6 +3,7 @@ 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/EgoVehicles/*,Unreal/CarlaUE4/Config/EgoVehicles/ Config/Default.Package.json,Unreal/CarlaUE4/Content/Carla/Config/ Config/CarlaUE4.uproject,Unreal/CarlaUE4/ Content,Unreal/CarlaUE4/