Agrarsense
DVSCamera.h
Go to the documentation of this file.
1// Copyright (c) 2023 FrostBit Software Lab at the Lapland University of Applied Sciences
2//
3// This work is licensed under the terms of the MIT license.
4// For a copy, see <https://opensource.org/licenses/MIT>.
5
6#pragma once
7
10#include "DVSEvent.h"
11
12#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
13
14#include <iostream>
15
16#include "DVSCamera.generated.h"
17
21UCLASS()
22class AGRARSENSE_API ADVSCamera : public ACamera
23{
24 GENERATED_BODY()
25
26public:
27
32 ADVSCamera(const FObjectInitializer& ObjectInitializer);
33
38 virtual void AddProcessingToFrameBuffer(TArray<FColor>& buffer) override;
39
44 virtual ESensorTypes GetSensorType() const override { return ESensorTypes::DVSCamera; }
45
50 UFUNCTION(BlueprintCallable)
51 void ChangeDVSCameraParameters(FDVSCameraParameters NewParameters);
52
57 UFUNCTION(BlueprintCallable, BlueprintPure)
58 FDVSCameraParameters GetDVSCameraParameters() const
59 {
60 return DVSCameraParameters;
61 }
62
63 UFUNCTION(BlueprintPure)
64 UTopic* GetDVSTopic() const
65 {
66 return DvsTopic;
67 }
68
69 UFUNCTION(BlueprintPure)
70 FString GetDVSTopicName() const
71 {
72 FString Name;
73 if (DvsTopic)
74 {
75 Name = DvsTopic->GetTopicName();
76 }
77 return Name;
78 }
79
83 virtual FString GetParametersAsString() const override
84 {
85 return StructToString(DVSCameraParameters);
86 }
87
88protected:
89
93 void CreateROSTopic() override;
94
95private:
96
97 friend class USensorFactory;
98
103 void DVSInit(FDVSCameraParameters Parameters, bool SimulateSensor = true);
104
110 void Init(FCameraBaseParameters parameters, bool SimulateSensor = true) override;
111
116 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
117
123 UFUNCTION()
124 void OnMainCameraWindowResized(ACamera* Camera, FCameraBaseParameters Params);
125
130 void ImageToGray(const TArray<FColor>& Buffer);
131
136 void ImageToLogGray(const TArray<FColor>& Buffer);
137
141 void SendRawDVSImageDataToROS();
142
147 void DVSWindowClosedCallback(const TSharedRef<SWindow>& Window);
148
153 void UpdateDVSWindowOutput(const TArray<FColor>& Buffer);
154
160 float FColorToGrayScaleFloat(const FColor& Color);
161
165 void ChangeParametersInternal();
166
167 std::vector<DVSEvent> EventArray;
168
169 std::vector<DVSEvent> SimulateDVS(const TArray<FColor>& Buffer);
170
171 UPROPERTY()
172 TArray<double> LastEventTimestamp;
173
174 UPROPERTY()
175 TArray<float> PreviousImage;
176
177 UPROPERTY()
178 TArray<float> LastImage;
179
180 UPROPERTY()
181 TArray<float> RefValues;
182
183 std::int64_t CurrentTime;
184
185 FDVSCameraParameters TempDVSCameraParameters;
186
187 FDVSCameraParameters DVSCameraParameters;
188
194 UPROPERTY()
195 UTopic* DvsTopic = nullptr;
196
197 UPROPERTY()
198 TArray<FColor> DVSOutput;
199
200 bool SetParentParameters = false;
201
202 bool ParametersChanged = false;
203
204 TSharedPtr<FUnrealWindow> DVSUnrealWindow;
205
206 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> PointCloudMessage;
207
208 FOnWindowClosed OnDVSWindowClosed;
209
210 static TArray<int32> ApprovedWidths;
211
217 inline constexpr std::int64_t SecToNanoSec(double seconds)
218 {
219 return static_cast<std::int64_t>(seconds * 1e9);
220 }
221
227 inline constexpr double NanoSecToSecTrunc(std::int64_t nanoseconds)
228 {
229 return static_cast<double>(nanoseconds) / 1e9;
230 }
231
232};
ESensorTypes
Definition: SensorTypes.h:15
Definition: Camera.h:52
virtual ESensorTypes GetSensorType() const override
Definition: DVSCamera.h:44
virtual FString GetParametersAsString() const override
Definition: DVSCamera.h:83
constexpr double NanoSecToSecTrunc(std::int64_t nanoseconds)
Definition: DVSCamera.h:227