Skip to content

Commit

Permalink
Merge pull request #111 from HARPLab/dev
Browse files Browse the repository at this point in the history
Backend overhaul (+Custom EgoVehicles + better autopilot + Auto sign placements)
  • Loading branch information
ajdroid committed Jun 3, 2023
2 parents 76da276 + 0f0ab1d commit c9e3f20
Show file tree
Hide file tree
Showing 107 changed files with 2,344 additions and 1,145 deletions.
20 changes: 19 additions & 1 deletion CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -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"`
Expand Down Expand Up @@ -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
13 changes: 6 additions & 7 deletions Carla/Actor/DReyeVRCustomActor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<UStaticMesh>(nullptr, *Path);
Expand Down Expand Up @@ -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)
Expand Down
21 changes: 19 additions & 2 deletions Carla/Actor/DReyeVRCustomActor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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);
Expand All @@ -47,14 +57,21 @@ class CARLA_API ADReyeVRCustomActor : public AActor // abstract class

static std::unordered_map<std::string, class ADReyeVRCustomActor *> 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);

Expand Down
32 changes: 23 additions & 9 deletions Carla/Recorder/CarlaRecorder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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())
Expand Down Expand Up @@ -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<DReyeVR::AggregateData>(ADReyeVRSensor::Data));

TArray<AActor *> 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<ADReyeVRCustomActor>(A);
if (CustomActor != nullptr && CustomActor->IsActive())
ADReyeVRCustomActor *CustomActor = ActiveCAs.second;
if (CustomActor != nullptr && CustomActor->IsActive() && CustomActor->GetShouldRecord())
{
DReyeVRCustomActorData.Add(DReyeVRDataRecorder<DReyeVR::CustomActorData>(&(CustomActor->GetInternals())));
}
Expand Down Expand Up @@ -427,6 +432,7 @@ void ACarlaRecorder::Clear(void)
TrafficLightTimes.Clear();
DReyeVRAggData.Clear();
DReyeVRCustomActorData.Clear();
DReyeVRConfigFileData.Clear();
Weathers.Clear();
}

Expand Down Expand Up @@ -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);

Expand Down
7 changes: 5 additions & 2 deletions Carla/Recorder/CarlaRecorder.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand All @@ -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
Expand Down Expand Up @@ -205,6 +207,7 @@ class CARLA_API ACarlaRecorder : public AActor
CarlaRecorderWeathers Weathers;
DReyeVRDataRecorders<DReyeVR::AggregateData, DREYEVR_PACKET_ID> DReyeVRAggData;
DReyeVRDataRecorders<DReyeVR::CustomActorData, DREYEVR_CUSTOM_ACTOR_PACKET_ID> DReyeVRCustomActorData;
DReyeVRDataRecorders<DReyeVR::ConfigFileData, DREYEVR_CONFIG_FILE_PACKET_ID> DReyeVRConfigFileData;

// replayer
CarlaReplayer Replayer;
Expand Down
21 changes: 21 additions & 0 deletions Carla/Recorder/CarlaRecorderQuery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -604,6 +604,27 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
else
SkipPacket();
break;

// DReyeVR data (ConfigFileData)
case static_cast<char>(CarlaRecorderPacketId::DReyeVRConfigFile):
if (bShowAll)
{
ReadValue<uint16_t>(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<char>(CarlaRecorderPacketId::FrameEnd):
// do nothing, it is empty
Expand Down
1 change: 1 addition & 0 deletions Carla/Recorder/CarlaRecorderQuery.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,7 @@ class CarlaRecorderQuery
// custom DReyeVR packets
DReyeVRDataRecorder<DReyeVR::AggregateData> DReyeVRAggDataInstance;
DReyeVRDataRecorder<DReyeVR::CustomActorData> DReyeVRCustomActorDataInstance;
DReyeVRDataRecorder<DReyeVR::ConfigFileData> DReyeVRConfigFileDataInstance;

// read next header packet
bool ReadHeader(void);
Expand Down
Loading

0 comments on commit c9e3f20

Please sign in to comment.