Fixed DVS to work with the new rendering pipeline

This commit is contained in:
Marc Garcia Puig 2020-12-18 16:56:47 +01:00 committed by bernat
parent 726a5383af
commit 861b95e853
5 changed files with 49 additions and 22 deletions

View File

@ -13,6 +13,11 @@
#include "Carla/Util/RandomEngine.h"
#include "Carla/Sensor/DVSCamera.h"
static float FColorToGrayScaleFloat(FColor Color)
{
return 0.2989 * Color.R + 0.587 * Color.G + 0.114 * Color.B;
}
ADVSCamera::ADVSCamera(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer)
{
@ -117,23 +122,33 @@ void ADVSCamera::Set(const FActorDescription &Description)
void ADVSCamera::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime)
{
check(CaptureRenderTarget != nullptr);
if (!HasActorBegunPlay() || IsPendingKill())
{
return;
}
/// Immediate enqueues render commands of the scene at the current time.
EnqueueRenderSceneImmediate();
WaitForRenderThreadToFinsih();
//Super (ASceneCaptureSensor) Capture the Scene in a (UTextureRenderTarget2D) CaptureRenderTarge from the CaptureComponent2D
/** Read the image **/
TArray<FColor> image;
this->ReadPixels(image);
TArray<FColor> RawImage;
this->ReadPixels(RawImage);
/** Convert image to gray scale **/
if (this->config.use_log)
{
this->imageToLogGray(image, this->last_image);
this->ImageToLogGray(RawImage);
}
else
{
this->imageToGray(image, this->last_image);
this->ImageToGray(RawImage);
}
/** DVS Simulator **/
ADVSCamera::DVSEventArray events = this->simulation(DeltaTime);
ADVSCamera::DVSEventArray events = this->Simulation(DeltaTime);
if (events.size() > 0)
{
@ -144,39 +159,39 @@ void ADVSCamera::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTim
}
}
void ADVSCamera::imageToGray(const TArray<FColor> &image, TArray<float> &gray)
void ADVSCamera::ImageToGray(const TArray<FColor> &image)
{
/** Sanity check **/
if (image.Num() != (this->GetImageHeight() * this->GetImageWidth()))
return;
/** Reserve HxW elements **/
gray.SetNumUninitialized(image.Num());
last_image.SetNumUninitialized(image.Num());
/** Convert image to gray raw image values **/
for (size_t i = 0; i<image.Num(); ++i)
for (size_t i = 0; i < image.Num(); ++i)
{
gray[i] = 0.2989*image[i].R + 0.5870*image[i].G + 0.1140*image[i].B;
last_image[i] = FColorToGrayScaleFloat(image[i]);
}
}
void ADVSCamera::imageToLogGray(const TArray<FColor> &image, TArray<float> &gray)
void ADVSCamera::ImageToLogGray(const TArray<FColor> &image)
{
/** Sanity check **/
if (image.Num() != (this->GetImageHeight() * this->GetImageWidth()))
return;
/** Reserve HxW elements **/
gray.SetNumUninitialized(image.Num());
last_image.SetNumUninitialized(image.Num());
/** Convert image to gray raw image values **/
for (size_t i = 0; i<image.Num(); ++i)
for (size_t i = 0; i < image.Num(); ++i)
{
gray[i] = std::log(this->config.log_eps + ((0.2989*image[i].R + 0.5870*image[i].G + 0.1140*image[i].B)/255.0));
last_image[i] = std::log(this->config.log_eps + (FColorToGrayScaleFloat(image[i]) / 255.0));
}
}
ADVSCamera::DVSEventArray ADVSCamera::simulation (float DeltaTime)
ADVSCamera::DVSEventArray ADVSCamera::Simulation (float DeltaTime)
{
/** Array of events **/
ADVSCamera::DVSEventArray events;

View File

@ -50,17 +50,16 @@ public:
void Set(const FActorDescription &ActorDescription) override;
protected:
// void PrePhysTick(float DeltaTime) override;
virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override;
void imageToGray(const TArray<FColor> &image, TArray<float> &gray);
void imageToLogGray(const TArray<FColor> &image, TArray<float> &gray);
ADVSCamera::DVSEventArray simulation (float DeltaTime);
void ImageToGray(const TArray<FColor> &image);
void ImageToLogGray(const TArray<FColor> &image);
ADVSCamera::DVSEventArray Simulation (float DeltaTime);
private:
/// Images containing last (current) and previous image
TArray<float> last_image, prev_image;
/// Image containing the last reference vaklue to trigger event
/// Image containing the last reference value to trigger event
TArray<float> ref_values;
/// Image containing time of last event in seconds

View File

@ -91,8 +91,8 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor)
return;
}
// Creates an snapshot of the scene, requieres bCaptureEveryFrame = false
Sensor.GetCaptureComponent2D()->CaptureScene();
/// Blocks until the render thread has finished all it's tasks.
Sensor.EnqueueRenderSceneImmediate();
// Enqueue a command in the render-thread that will write the image buffer to
// the data stream. The stream is created in the capture thus executed in the
@ -120,5 +120,5 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor)
);
// Blocks until the render thread has finished all it's tasks
FlushRenderingCommands();
Sensor.WaitForRenderThreadToFinsih();
}

View File

@ -454,6 +454,11 @@ float ASceneCaptureSensor::GetChromAberrOffset() const
return CaptureComponent2D->PostProcessSettings.ChromaticAberrationStartOffset;
}
void ASceneCaptureSensor::EnqueueRenderSceneImmediate() {
// Creates an snapshot of the scene, requieres bCaptureEveryFrame = false.
CaptureComponent2D->CaptureScene();
}
void ASceneCaptureSensor::BeginPlay()
{
using namespace SceneCaptureSensor_local_ns;

View File

@ -277,6 +277,14 @@ public:
return CaptureComponent2D;
}
/// Immediate enqueues render commands of the scene at the current time.
void EnqueueRenderSceneImmediate();
/// Blocks until the render thread has finished all it's tasks.
void WaitForRenderThreadToFinsih() {
FlushRenderingCommands();
}
protected:
virtual void BeginPlay() override;