25 return 0.2989 * Color.R + 0.587 * Color.G + 0.114 * Color.B;
29 : Super(ObjectInitializer)
33 TEXT(
"Material'/Carla/PostProcessingMaterials/PhysicLensDistortion.PhysicLensDistortion'"));
35 RandomEngine = CreateDefaultSubobject<URandomEngine>(TEXT(
"RandomEngine"));
40 constexpr bool bEnableModifyingPostProcessEffects =
true;
44 Cp.
Id = TEXT(
"positive_threshold");
50 Cm.
Id = TEXT(
"negative_threshold");
56 Sigma_Cp.
Id = TEXT(
"sigma_positive_threshold");
62 Sigma_Cm.
Id = TEXT(
"sigma_negative_threshold");
68 Refractory_Period.
Id = TEXT(
"refractory_period_ns");
74 Use_Log.
Id = TEXT(
"use_log");
80 Log_EPS.
Id = TEXT(
"log_eps");
85 Definition.Variations.Append({ Cp, Cm, Sigma_Cp, Sigma_Cm, Refractory_Period, Use_Log, Log_EPS });
92 Super::Set(Description);
100 "negative_threshold",
105 "sigma_positive_threshold",
110 "sigma_negative_threshold",
115 "refractory_period_ns",
134 if (!HasActorBegunPlay() || IsPendingKill())
145 TArray<FColor> RawImage;
162 auto Buff =
Stream.PopBufferFromPool();
169 #if defined(WITH_ROS2)
171 if (ROS2->IsEnabled())
173 TRACE_CPUPROFILER_EVENT_SCOPE_STR(
"ROS2 Send");
180 if (WidthOpt.has_value())
181 W = FCString::Atoi(*WidthOpt->Value);
183 if (HeightOpt.has_value())
184 H = FCString::Atoi(*HeightOpt->Value);
186 if (FovOpt.has_value())
187 Fov = FCString::Atof(*FovOpt->Value);
188 AActor* ParentActor = GetAttachParentActor();
191 FTransform LocalTransformRelativeToParent = GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform());
192 ROS2->ProcessDataFromDVS(
Stream.
GetSensorType(), StreamId, LocalTransformRelativeToParent, BufView, W, H, Fov,
this);
201 if (events.size() > 0)
203 TRACE_CPUPROFILER_EVENT_SCOPE_STR(
"ADVSCamera Stream Send");
205 Stream.Send(*
this, BufView);
212 if (image.Num() != (this->GetImageHeight() * this->GetImageWidth()))
219 for (
size_t i = 0; i < image.Num(); ++i)
228 if (image.Num() != (this->GetImageHeight() * this->GetImageWidth()))
235 for (
size_t i = 0; i < image.Num(); ++i)
247 if (this->
last_image.Num() != (this->GetImageHeight() * this->GetImageWidth()))
266 static constexpr float tolerance = 1e-6;
282 if (std::fabs (it - itdt) > tolerance)
284 const float pol = (itdt >= it) ? +1.0 : -1.0;
291 constexpr float minimum_contrast_threshold = 0.01;
292 C = std::max(minimum_contrast_threshold, C);
294 float curr_cross = prev_cross;
295 bool all_crossings =
false;
299 curr_cross += pol * C;
301 if ((pol > 0 && curr_cross > it && curr_cross <= itdt)
302 || (pol < 0 && curr_cross < it && curr_cross >= itdt))
304 const std::uint64_t edt = (curr_cross - it) * delta_t_ns / (itdt - it);
310 if (t >= last_stamp_at_xy)
312 const std::uint64_t dt = t - last_stamp_at_xy;
327 all_crossings =
true;
329 }
while (!all_crossings);
341 std::sort(events.begin(), events.end(), [](const ::carla::sensor::data::DVSEvent& it1, const ::carla::sensor::data::DVSEvent& it2){return it1.t < it2.t;});
static float FColorToGrayScaleFloat(FColor Color)
std::vector<::carla::sensor::data::DVSEvent > DVSEventArray
ADVSCamera(const FObjectInitializer &ObjectInitializer)
TArray< float > prev_image
dvs::Config config
DVS simulation configuration
void Set(const FActorDescription &ActorDescription) override
TArray< double > last_event_timestamp
Image containing time of last event in seconds
ADVSCamera::DVSEventArray Simulation(float DeltaTime)
static FActorDefinition GetSensorDefinition()
void ImageToLogGray(const TArray< FColor > &image)
TArray< float > last_image
Images containing last (current) and previous image
void ImageToGray(const TArray< FColor > &image)
TArray< float > ref_values
Image containing the last reference value to trigger event
virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override
std::int64_t current_time
Current time in nanoseconds
bool ReadPixels(TArray< FColor > &BitMap) const
Use for debugging purposes only.
void EnablePostProcessingEffects(bool Enable=true)
UTextureRenderTarget2D * CaptureRenderTarget
Render target necessary for scene capture.
void EnqueueRenderSceneImmediate()
Immediate enqueues render commands of the scene at the current time.
uint32 GetImageHeight() const
uint32 GetImageWidth() const
void WaitForRenderThreadToFinish()
Blocks until the render thread has finished all it's tasks.
boost::optional< FActorAttribute > GetAttribute(const FString Name)
auto GetToken() const
Return the token that allows subscribing to this sensor's stream.
FAsyncDataStream GetDataStream(const SensorT &Self)
Return the FDataStream associated with this sensor.
URandomEngine * RandomEngine
Random Engine used to provide noise for sensor output.
const UCarlaEpisode & GetEpisode() const
bool AddPostProcessingMaterial(const FString &Path)
Load the UMaterialInstanceDynamic at the given Path and append it to the list of shaders with Weight.
static int32 RetrieveActorAttributeToInt(const FString &Id, const TMap< FString, FActorAttribute > &Attributes, int32 Default)
static FActorDefinition MakeCameraDefinition(const FString &Id, bool bEnableModifyingPostProcessEffects=false)
static float RetrieveActorAttributeToFloat(const FString &Id, const TMap< FString, FActorAttribute > &Attributes, float Default)
static bool RetrieveActorAttributeToBool(const FString &Id, const TMap< FString, FActorAttribute > &Attributes, bool Default)
float GetNormalDistribution(float Mean, float StandardDeviation)
static std::shared_ptr< BufferView > CreateFrom(Buffer &&buffer)
static std::shared_ptr< ROS2 > GetInstance()
static Buffer Serialize(Sensor &sensor, Args &&... args)
Serialize the arguments provided into a Buffer by calling to the serializer registered for the given ...
Serializes a stream endpoint.
const auto & get_stream_id() const
std::shared_ptr< BufferView > SharedBufferView
constexpr std::int64_t secToNanosec(double seconds)
constexpr double nanosecToSecTrunc(std::int64_t nanoseconds)
A definition of a Carla Actor with all the variation and attributes.
A description of a Carla Actor with all its variation.
TMap< FString, FActorAttribute > Variations
User selected variations of the actor.
Definition of an actor variation.
TArray< FString > RecommendedValues
bool bRestrictToRecommended
std::uint64_t refractory_period_ns