Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 7 additions & 3 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
## DReyeVR 0.1.2 (for Carla 0.9.13)
## 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"`

## DReyeVR 0.1.2
- Update documentation to refer to CarlaUnreal UE4 fork rather than HarpLab fork
- Apply patches for installation of zlib (broken link) and xerces (broken link & `-Dtranscoder=windows` flag) and PythonAPI
- Fix crash on BeginPlay when EgoVehicle blueprint is already present in map (before world start)
- Prefer building PythonAPI with `python` rather than Windows built-in `py -3` (good if using conda) but fallback if `python` is not available

## DReyeVR 0.1.1 (for Carla 0.9.13)
## DReyeVR 0.1.1
- Update documentation, add developer-centric in-depth documentation
- Adding missing includes for TrafficSign RoadInfoSignal in SignComponent
- Replacing `DReyeVRData.inl` with `DReyeVRData.cpp` and corresponding virtual classes
Expand All @@ -15,7 +19,7 @@
- Fix bug with spectator being reenacted by Carla, preferring to use our own ASpectator
- Automatically possess spectator pawn when EgoVehicle is destroyed. Can re-spawn EgoVehicle by pressing 1.

## DReyeVR 0.1.0 (for Carla 0.9.13)
## DReyeVR 0.1.0
- Replace existing `LevelScript` (`ADReyeVRLevel`) with `GameMode` (`ADReyeVRGameMode`). This allows us to not need to carry the (large) map blueprint files (ue4 binary) and we can use the vanilla Carla maps without modification. By default we spawn the EgoVehicle in the first of the recommended Carla locations, but this default behavior can be changed in the PythonAPI. For instance, you can delay spawning the EgoVehicle until via PythonAPI where you can specify the spawn transform. Existing functionality is preserved using `find_ego_vehicle` and `find_ego_sensor` which spawn the DReyeVR EgoVehicle if it does not exist in the world.
- Added `ADReyeVRFactory` as the Carla-esque spawning and registry functionality so the `EgoVehicle` and `EgoSensor` are spawned with the same "Factory" mechanisms as existing Carla vehicles/sensors/props/etc.
- Renamed DReyeVR-specific actors to be addressible in PythonAPI as `"harplab.dreyevr_$X.$id"` such as `"harplab.dreyevr_vehicle.model3"` and `"harplab.dreyevr_sensor.ego_sensor"`. Avoids conflicts with existing Carla PythonAPI scripts that may filter on `"vehicle.*"`.
Expand Down
127 changes: 74 additions & 53 deletions Carla/Recorder/CarlaReplayer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -291,6 +295,70 @@ 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<DReyeVR::AggregateData>(double Per, double DeltaTime)
{
uint16_t Total;
// read number of DReyeVR entries
ReadValue<uint16_t>(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<DReyeVR::AggregateData> Instance;
Instance.Read(File);
Helper.ProcessReplayerDReyeVR<DReyeVR::AggregateData>(GetEgoSensor(), Instance.Data, Per);
}
}

template<>
void CarlaReplayer::ProcessDReyeVR<DReyeVR::CustomActorData>(double Per, double DeltaTime)
{
uint16_t Total;
ReadValue<uint16_t>(File, Total); // read number of events
CustomActorsVisited.clear();
for (uint16_t i = 0; i < Total; ++i)
{
struct DReyeVRDataRecorder<DReyeVR::CustomActorData> Instance;
Instance.Read(File);
Helper.ProcessReplayerDReyeVR<DReyeVR::CustomActorData>(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;
Expand Down Expand Up @@ -401,18 +469,18 @@ void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime)
ProcessWeather();
break;

// DReyeVR eye logging data
// DReyeVR ego sensor data
case static_cast<char>(CarlaRecorderPacketId::DReyeVR):
if (bFrameFound)
ProcessDReyeVRData<DReyeVRDataRecorder<DReyeVR::AggregateData>>(Per, Time, true);
ProcessDReyeVR<DReyeVR::AggregateData>(Per, Time);
else
SkipPacket();
break;

// DReyeVR eye logging data
// DReyeVR custom actor data
case static_cast<char>(CarlaRecorderPacketId::DReyeVRCustomActor):
if (bFrameFound)
ProcessDReyeVRData<DReyeVRDataRecorder<DReyeVR::CustomActorData>>(Per, Time, false);
ProcessDReyeVR<DReyeVR::CustomActorData>(Per, Time);
else
SkipPacket();
break;
Expand Down Expand Up @@ -647,49 +715,6 @@ void CarlaReplayer::ProcessWeather(void)
}
}

template <typename T> void CarlaReplayer::ProcessDReyeVRData(double Per, double DeltaTime, bool bShouldBeOnlyOne)
{
uint16_t Total;
// custom DReyeVR packets

// read Total DReyeVR events
ReadValue<uint16_t>(File, Total); // read number of events

Visited.clear();
for (uint16_t i = 0; i < Total; ++i)
{
T DReyeVRDataInstance;
DReyeVRDataInstance.Read(File);
Helper.ProcessReplayerDReyeVRData<T>(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;
Expand Down Expand Up @@ -823,12 +848,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++;
Expand Down
7 changes: 5 additions & 2 deletions Carla/Recorder/CarlaReplayer.h
Original file line number Diff line number Diff line change
Expand Up @@ -168,8 +168,11 @@ class CARLA_API CarlaReplayer
void ProcessWeather(void);

// DReyeVR recordings
template <typename T> void ProcessDReyeVRData(double Per, double DeltaTime, bool bShouldBeOnlyOne);
std::unordered_set<std::string> Visited = {};
template <typename T>
void ProcessDReyeVR(double Per, double DeltaTime);
std::unordered_set<std::string> CustomActorsVisited = {};
class ADReyeVRSensor *GetEgoSensor(); // (safe) getter for EgoSensor
TWeakObjectPtr<class ADReyeVRSensor> EgoSensor;

// For restarting the recording with the same params
struct LastReplayStruct
Expand Down
18 changes: 9 additions & 9 deletions Carla/Recorder/CarlaReplayerHelper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T> void CarlaReplayerHelper::ProcessReplayerDReyeVRData(const T &DReyeVRDataInstance, const double Per)
template <typename T>
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)
Expand Down
4 changes: 3 additions & 1 deletion Carla/Recorder/CarlaReplayerHelper.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
class UCarlaEpisode;
class FCarlaActor;
struct FActorDescription;
class ADReyeVRSensor; // fwd for DReyeVR (avoid header conflict)

class CarlaReplayerHelper
{
Expand Down Expand Up @@ -75,7 +76,8 @@ class CarlaReplayerHelper
bool ProcessReplayerFinish(bool bApplyAutopilot, bool bIgnoreHero, std::unordered_map<uint32_t, bool> &IsHero);

// update the DReyeVR ego sensor and custom types
template <typename T> void ProcessReplayerDReyeVRData(const T &DReyeVRDataInstance, const double Per);
template <typename T>
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);
Expand Down
52 changes: 20 additions & 32 deletions DReyeVR/DReyeVRFactory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "Carla/Actor/ActorBlueprintFunctionLibrary.h" // UActorBlueprintFunctionLibrary
#include "Carla/Actor/VehicleParameters.h" // FVehicleParameters
#include "Carla/Game/CarlaEpisode.h" // UCarlaEpisode
#include "DReyeVRGameMode.h" // ADReyeVRGameMode
#include "EgoSensor.h" // AEgoSensor
#include "EgoVehicle.h" // AEgoVehicle

Expand Down Expand Up @@ -63,46 +64,28 @@ void ADReyeVRFactory::MakeVehicleDefinition(const FVehicleParameters &Parameters
Definition = MakeGenericDefinition(CATEGORY, TEXT("DReyeVR_Vehicle"), Parameters.Model);
Definition.Class = Parameters.Class;

FActorVariation ActorRole;
{
ActorRole.Id = TEXT("role_name");
ActorRole.Type = EActorAttributeType::String;
ActorRole.RecommendedValues = {TEXT("ego_vehicle")}; // assume this is the CARLA "hero"
ActorRole.bRestrictToRecommended = false;
}
Definition.Variations.Emplace(ActorRole);

FActorVariation StickyControl;
{
StickyControl.Id = TEXT("sticky_control");
StickyControl.Type = EActorAttributeType::Bool;
StickyControl.bRestrictToRecommended = false;
StickyControl.RecommendedValues.Emplace(TEXT("false"));
}
Definition.Variations.Emplace(StickyControl);
FActorAttribute ActorRole;
ActorRole.Id = "role_name";
ActorRole.Type = EActorAttributeType::String;
ActorRole.Value = "hero";
Definition.Attributes.Emplace(ActorRole);

FActorAttribute ObjectType;
{
ObjectType.Id = TEXT("object_type");
ObjectType.Type = EActorAttributeType::String;
ObjectType.Value = Parameters.ObjectType;
}
ObjectType.Id = "object_type";
ObjectType.Type = EActorAttributeType::String;
ObjectType.Value = Parameters.ObjectType;
Definition.Attributes.Emplace(ObjectType);

FActorAttribute NumberOfWheels;
{
NumberOfWheels.Id = TEXT("number_of_wheels");
NumberOfWheels.Type = EActorAttributeType::Int;
NumberOfWheels.Value = FString::FromInt(Parameters.NumberOfWheels);
}
NumberOfWheels.Id = "number_of_wheels";
NumberOfWheels.Type = EActorAttributeType::Int;
NumberOfWheels.Value = FString::FromInt(Parameters.NumberOfWheels);
Definition.Attributes.Emplace(NumberOfWheels);

FActorAttribute Generation;
{
Generation.Id = TEXT("generation");
Generation.Type = EActorAttributeType::Int;
Generation.Value = FString::FromInt(Parameters.Generation);
}
Generation.Id = "generation";
Generation.Type = EActorAttributeType::Int;
Generation.Value = FString::FromInt(Parameters.Generation);
Definition.Attributes.Emplace(Generation);
}

Expand Down Expand Up @@ -156,6 +139,11 @@ FActorSpawnResult ADReyeVRFactory::SpawnActor(const FTransform &SpawnAtTransform
// EgoVehicle needs the special EgoVehicleBPClass since they depend on the EgoVehicle Blueprint
return World->SpawnActor<AEgoVehicle>(EgoVehicleBPClass, SpawnAtTransform, SpawnParameters);
});

// update the GameMode's EgoVehicle in case it was spawned by someone else
auto *Game = Cast<ADReyeVRGameMode>(UGameplayStatics::GetGameMode(World));
if (Game != nullptr)
Game->SetEgoVehicle(Cast<AEgoVehicle>(SpawnedActor));
}
else if (ActorDescription.Class == AEgoSensor::StaticClass())
{
Expand Down
Loading