12#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
16#include "DVSCamera.generated.h"
32 ADVSCamera(
const FObjectInitializer& ObjectInitializer);
38 virtual void AddProcessingToFrameBuffer(TArray<FColor>& buffer)
override;
50 UFUNCTION(BlueprintCallable)
57 UFUNCTION(BlueprintCallable, BlueprintPure)
60 return DVSCameraParameters;
63 UFUNCTION(BlueprintPure)
64 UTopic* GetDVSTopic()
const
69 UFUNCTION(BlueprintPure)
70 FString GetDVSTopicName()
const
75 Name = DvsTopic->GetTopicName();
85 return StructToString(DVSCameraParameters);
93 void CreateROSTopic()
override;
116 virtual void EndPlay(
const EEndPlayReason::Type EndPlayReason)
override;
130 void ImageToGray(const TArray<FColor>& Buffer);
136 void ImageToLogGray(const TArray<FColor>& Buffer);
141 void SendRawDVSImageDataToROS();
147 void DVSWindowClosedCallback(const TSharedRef<SWindow>& Window);
153 void UpdateDVSWindowOutput(const TArray<FColor>& Buffer);
160 float FColorToGrayScaleFloat(const FColor& Color);
165 void ChangeParametersInternal();
169 std::vector<
DVSEvent> SimulateDVS(const TArray<FColor>& Buffer);
172 TArray<
double> LastEventTimestamp;
175 TArray<
float> PreviousImage;
178 TArray<
float> LastImage;
181 TArray<
float> RefValues;
183 std::int64_t CurrentTime;
195 UTopic* DvsTopic =
nullptr;
198 TArray<FColor> DVSOutput;
200 bool SetParentParameters = false;
202 bool ParametersChanged = false;
206 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> PointCloudMessage;
208 FOnWindowClosed OnDVSWindowClosed;
210 static TArray<int32> ApprovedWidths;
217 inline constexpr std::int64_t SecToNanoSec(
double seconds)
219 return static_cast<std::int64_t
>(seconds * 1e9);
229 return static_cast<double>(nanoseconds) / 1e9;
virtual ESensorTypes GetSensorType() const override
virtual FString GetParametersAsString() const override
constexpr double NanoSecToSecTrunc(std::int64_t nanoseconds)