CARLA
Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Types | Private Attributes | List of all members
ADVSCamera Class Reference

Sensor that produce Dynamic Vision Events. More...

#include <DVSCamera.h>

+ Inheritance diagram for ADVSCamera:
+ Collaboration diagram for ADVSCamera:

Public Member Functions

 ADVSCamera (const FObjectInitializer &ObjectInitializer)
 
void Set (const FActorDescription &ActorDescription) override
 
- Public Member Functions inherited from AShaderBasedSensor
bool AddPostProcessingMaterial (const FString &Path)
 Load the UMaterialInstanceDynamic at the given Path and append it to the list of shaders with Weight. More...
 
void AddShader (const FSensorShader &Shader)
 Add a post-processing shader. More...
 
 AShaderBasedSensor (const FObjectInitializer &ObjectInitializer)
 
void Set (const FActorDescription &ActorDescription) override
 
void SetFloatShaderParameter (uint8_t ShaderIndex, const FName &ParameterName, float Value)
 
- Public Member Functions inherited from ASceneCaptureSensor
bool ArePostProcessingEffectsEnabled () const
 
 ASceneCaptureSensor (const FObjectInitializer &ObjectInitializer)
 
void Enable16BitFormat (bool Enable=false)
 
void EnablePostProcessingEffects (bool Enable=true)
 
void EnqueueRenderSceneImmediate ()
 Immediate enqueues render commands of the scene at the current time. More...
 
float GetAperture () const
 
int GetBladeCount () const
 
float GetBloomIntensity () const
 
USceneCaptureComponent2DGetCaptureComponent2D ()
 
UTextureRenderTarget2D * GetCaptureRenderTarget ()
 
float GetChromAberrIntensity () const
 
float GetChromAberrOffset () const
 
float GetDepthBlurAmount () const
 
float GetDepthBlurRadius () const
 
float GetDepthOfFieldMinFstop () const
 
float GetExposureCalibrationConstant () const
 
float GetExposureCompensation () const
 
float GetExposureMaxBrightness () const
 
EAutoExposureMethod GetExposureMethod () const
 
float GetExposureMinBrightness () const
 
float GetExposureSpeedDown () const
 
float GetExposureSpeedUp () const
 
float GetFilmBlackClip () const
 
float GetFilmShoulder () const
 
float GetFilmSlope () const
 
float GetFilmToe () const
 
float GetFilmWhiteClip () const
 
float GetFocalDistance () const
 
float GetFOVAngle () const
 
uint32 GetImageHeight () const
 
uint32 GetImageWidth () const
 
float GetISO () const
 
float GetLensFlareIntensity () const
 
float GetMotionBlurIntensity () const
 
float GetMotionBlurMaxDistortion () const
 
float GetMotionBlurMinObjectScreenSize () const
 
float GetShutterSpeed () const
 
float GetTargetGamma () const
 
float GetWhiteTemp () const
 
float GetWhiteTint () const
 
bool Is16BitFormatEnabled () const
 
bool ReadPixels (TArray< FColor > &BitMap) const
 Use for debugging purposes only. More...
 
void SaveCaptureToDisk (const FString &FilePath) const
 Use for debugging purposes only. More...
 
void SetAperture (float Aperture)
 
void SetBladeCount (int Count)
 
void SetBloomIntensity (float Intensity)
 
void SetChromAberrIntensity (float Intensity)
 
void SetChromAberrOffset (float ChromAberrOffset)
 
void SetDepthBlurAmount (float Amount)
 
void SetDepthBlurRadius (float Radius)
 
void SetDepthOfFieldMinFstop (float MinFstop)
 
void SetExposureCalibrationConstant (float Constant)
 
void SetExposureCompensation (float Compensation)
 
void SetExposureMaxBrightness (float Brightness)
 
void SetExposureMethod (EAutoExposureMethod Method)
 
void SetExposureMinBrightness (float Brightness)
 
void SetExposureSpeedDown (float Speed)
 
void SetExposureSpeedUp (float Speed)
 
void SetFilmBlackClip (float BlackClip)
 
void SetFilmShoulder (float Shoulder)
 
void SetFilmSlope (float Slope)
 
void SetFilmToe (float Toe)
 
void SetFilmWhiteClip (float WhiteClip)
 
void SetFocalDistance (float Distance)
 
void SetFOVAngle (float FOVAngle)
 
void SetImageSize (uint32 Width, uint32 Height)
 
void SetISO (float ISO)
 
void SetLensFlareIntensity (float Intensity)
 
void SetMotionBlurIntensity (float Intensity)
 
void SetMotionBlurMaxDistortion (float MaxDistortion)
 
void SetMotionBlurMinObjectScreenSize (float ScreenSize)
 
void SetShutterSpeed (float Speed)
 
void SetTargetGamma (float InTargetGamma)
 
void SetWhiteTemp (float Temp)
 
void SetWhiteTint (float Tint)
 
void WaitForRenderThreadToFinish ()
 Blocks until the render thread has finished all it's tasks. More...
 
- Public Member Functions inherited from ASensor
 ASensor (const FObjectInitializer &ObjectInitializer)
 
boost::optional< FActorAttributeGetAttribute (const FString Name)
 
const UCarlaEpisodeGetEpisode () const
 
URandomEngineGetRandomEngine ()
 
int32 GetSeed () const
 
auto GetToken () const
 Return the token that allows subscribing to this sensor's stream. More...
 
bool IsStreamReady ()
 
FDataStream MoveDataStream ()
 
virtual void OnFirstClientConnected ()
 
virtual void OnLastClientDisconnected ()
 
void PostPhysTickInternal (UWorld *World, ELevelTick TickType, float DeltaSeconds)
 
void SetDataStream (FDataStream InStream)
 Replace the FDataStream associated with this sensor. More...
 
void SetEpisode (const UCarlaEpisode &InEpisode)
 
void SetSeed (int32 InSeed)
 
void Tick (const float DeltaTime) final
 

Static Public Member Functions

static FActorDefinition GetSensorDefinition ()
 

Protected Member Functions

void ImageToGray (const TArray< FColor > &image)
 
void ImageToLogGray (const TArray< FColor > &image)
 
virtual void PostPhysTick (UWorld *World, ELevelTick TickType, float DeltaTime) override
 
ADVSCamera::DVSEventArray Simulation (float DeltaTime)
 
- Protected Member Functions inherited from AShaderBasedSensor
void SetUpSceneCaptureComponent (USceneCaptureComponent2D &SceneCapture) override
 
- Protected Member Functions inherited from ASceneCaptureSensor
virtual void BeginPlay () override
 
void CaptureSceneExtended ()
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
virtual void PrePhysTick (float DeltaSeconds) override
 
virtual void SendGBufferTextures (FGBufferRequest &GBuffer)
 
template<typename T >
void SendGBufferTexturesInternal (T &Self, FGBufferRequest &GBufferData)
 
- Protected Member Functions inherited from ASensor
void EndPlay (EEndPlayReason::Type EndPlayReason) override
 
template<typename SensorT >
FAsyncDataStream GetDataStream (const SensorT &Self)
 Return the FDataStream associated with this sensor. More...
 
void PostActorCreated () override
 

Private Types

using DVSEventArray = std::vector<::carla::sensor::data::DVSEvent >
 

Private Attributes

dvs::Config config
 DVS simulation configuration. More...
 
std::int64_t current_time
 Current time in nanoseconds. More...
 
TArray< double > last_event_timestamp
 Image containing time of last event in seconds. More...
 
TArray< float > last_image
 Images containing last (current) and previous image. More...
 
TArray< float > prev_image
 
TArray< float > ref_values
 Image containing the last reference value to trigger event. More...
 

Additional Inherited Members

- Public Attributes inherited from ASceneCaptureSensor
struct {
   FCameraGBufferUint8   CustomDepth
 
   FCameraGBufferUint8   CustomStencil
 
   FCameraGBufferUint8   GBufferA
 
   FCameraGBufferUint8   GBufferB
 
   FCameraGBufferUint8   GBufferC
 
   FCameraGBufferUint8   GBufferD
 
   FCameraGBufferUint8   GBufferE
 
   FCameraGBufferUint8   GBufferF
 
   FCameraGBufferUint8   SceneColor
 
   FCameraGBufferUint8   SceneDepth
 
   FCameraGBufferUint8   SceneStencil
 
   FCameraGBufferUint8   SSAO
 
   FCameraGBufferUint8   Velocity
 
CameraGBuffers
 
- Protected Attributes inherited from ASceneCaptureSensor
bool bEnable16BitFormat = false
 Whether to change render target format to PF_A16B16G16R16, offering 16bit / channel. More...
 
bool bEnablePostProcessingEffects = true
 Whether to render the post-processing effects present in the scene. More...
 
USceneCaptureComponent2D_CARLACaptureComponent2D = nullptr
 Scene capture component. More...
 
UTextureRenderTarget2D * CaptureRenderTarget = nullptr
 Render target necessary for scene capture. More...
 
uint32 ImageHeight = 600u
 Image height in pixels. More...
 
uint32 ImageWidth = 800u
 Image width in pixels. More...
 
float TargetGamma = 2.4f
 
- Protected Attributes inherited from ASensor
bool bIsActive = false
 
URandomEngineRandomEngine = nullptr
 Random Engine used to provide noise for sensor output. More...
 
int32 Seed = 123456789
 Seed of the pseudo-random engine. More...
 

Detailed Description

Sensor that produce Dynamic Vision Events.

Definition at line 43 of file DVSCamera.h.

Member Typedef Documentation

◆ DVSEventArray

Definition at line 46 of file DVSCamera.h.

Constructor & Destructor Documentation

◆ ADVSCamera()

ADVSCamera::ADVSCamera ( const FObjectInitializer &  ObjectInitializer)

Definition at line 28 of file DVSCamera.cpp.

References AShaderBasedSensor::AddPostProcessingMaterial(), ASceneCaptureSensor::EnablePostProcessingEffects(), and ASensor::RandomEngine.

+ Here is the call graph for this function:

Member Function Documentation

◆ GetSensorDefinition()

FActorDefinition ADVSCamera::GetSensorDefinition ( )
static

Definition at line 38 of file DVSCamera.cpp.

References Bool, FActorVariation::bRestrictToRecommended, Float, FActorVariation::Id, Int, UActorBlueprintFunctionLibrary::MakeCameraDefinition(), FActorVariation::RecommendedValues, and FActorVariation::Type.

+ Here is the call graph for this function:

◆ ImageToGray()

void ADVSCamera::ImageToGray ( const TArray< FColor > &  image)
protected

Sanity check

Reserve HxW elements

Convert image to gray raw image values

Definition at line 209 of file DVSCamera.cpp.

References FColorToGrayScaleFloat(), ASceneCaptureSensor::GetImageHeight(), ASceneCaptureSensor::GetImageWidth(), and last_image.

Referenced by PostPhysTick().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ ImageToLogGray()

void ADVSCamera::ImageToLogGray ( const TArray< FColor > &  image)
protected

Sanity check

Reserve HxW elements

Convert image to gray raw image values

Definition at line 225 of file DVSCamera.cpp.

References config, FColorToGrayScaleFloat(), ASceneCaptureSensor::GetImageHeight(), ASceneCaptureSensor::GetImageWidth(), last_image, carla::logging::log(), and dvs::Config::log_eps.

Referenced by PostPhysTick().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

◆ PostPhysTick()

void ADVSCamera::PostPhysTick ( UWorld *  World,
ELevelTick  TickType,
float  DeltaTime 
)
overrideprotectedvirtual

Immediate enqueues render commands of the scene at the current time.

Read the image

Convert image to gray scale

DVS Simulator

Send the events

Reimplemented from ASceneCaptureSensor.

Definition at line 130 of file DVSCamera.cpp.

References ASceneCaptureSensor::CaptureRenderTarget, config, carla::BufferView::CreateFrom(), ASceneCaptureSensor::EnqueueRenderSceneImmediate(), carla::streaming::detail::token_type::get_stream_id(), ASensor::GetAttribute(), ASensor::GetDataStream(), carla::ros2::ROS2::GetInstance(), FDataStreamTmpl< T >::GetSensorType(), ASensor::GetToken(), ImageToGray(), ImageToLogGray(), ASceneCaptureSensor::ReadPixels(), carla::sensor::CompositeSerializer< Items >::Serialize(), Simulation(), ASensor::Stream, dvs::Config::use_log, and ASceneCaptureSensor::WaitForRenderThreadToFinish().

+ Here is the call graph for this function:

◆ Set()

void ADVSCamera::Set ( const FActorDescription ActorDescription)
overridevirtual

◆ Simulation()

ADVSCamera::DVSEventArray ADVSCamera::Simulation ( float  DeltaTime)
protected

Array of events

Sanity check

Check initialization

Set the first rendered image

Resizes array to given number of elements. New elements will be zeroed.

Reset current time

delta time in nanoseconds

Loop along the image size

Dropping event because time since last event < refractory_period_ns

Update current time

Definition at line 241 of file DVSCamera.cpp.

References config, dvs::Config::Cp, current_time, ASensor::GetEpisode(), ASceneCaptureSensor::GetImageHeight(), ASceneCaptureSensor::GetImageWidth(), URandomEngine::GetNormalDistribution(), last_event_timestamp, last_image, dvs::nanosecToSecTrunc(), prev_image, ASensor::RandomEngine, ref_values, dvs::Config::refractory_period_ns, dvs::secToNanosec(), dvs::Config::sigma_Cm, dvs::Config::sigma_Cp, and sort().

Referenced by PostPhysTick().

+ Here is the call graph for this function:
+ Here is the caller graph for this function:

Member Data Documentation

◆ config

dvs::Config ADVSCamera::config
private

DVS simulation configuration.

Definition at line 73 of file DVSCamera.h.

Referenced by ImageToLogGray(), PostPhysTick(), Set(), and Simulation().

◆ current_time

std::int64_t ADVSCamera::current_time
private

Current time in nanoseconds.

Definition at line 70 of file DVSCamera.h.

Referenced by Simulation().

◆ last_event_timestamp

TArray<double> ADVSCamera::last_event_timestamp
private

Image containing time of last event in seconds.

Definition at line 67 of file DVSCamera.h.

Referenced by Simulation().

◆ last_image

TArray<float> ADVSCamera::last_image
private

Images containing last (current) and previous image.

Definition at line 61 of file DVSCamera.h.

Referenced by ImageToGray(), ImageToLogGray(), and Simulation().

◆ prev_image

TArray<float> ADVSCamera::prev_image
private

Definition at line 61 of file DVSCamera.h.

Referenced by Simulation().

◆ ref_values

TArray<float> ADVSCamera::ref_values
private

Image containing the last reference value to trigger event.

Definition at line 64 of file DVSCamera.h.

Referenced by Simulation().


The documentation for this class was generated from the following files: