Agrarsense
DVSCamera.cpp
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#include "DVSCamera.h"
7
10
11#include "Async/TaskGraphInterfaces.h"
12#include "Engine/Texture2D.h"
13#include "Async/ParallelFor.h"
14
15#include <random>
16#include <algorithm>
17#include <cstring>
18#include <cerrno>
19#include <cmath>
20#include <cfenv>
21
22std::random_device rd;
23std::minstd_rand Engine;
24
25static constexpr float R_WEIGHT = 0.2989f;
26static constexpr float G_WEIGHT = 0.5870f;
27static constexpr float B_WEIGHT = 0.1140f;
28static constexpr float INV_MAX_VALUE = 1.0f / 255.0f;
29
30ADVSCamera::ADVSCamera(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
31{
32 // Cannot tick parallel due UTexture2D locks
33 UseParallelLateTick = false;
34
35 PrimaryActorTick.bCanEverTick = true;
36 PrimaryActorTick.TickGroup = TG_PostUpdateWork;
37}
38
39void ADVSCamera::DVSInit(FDVSCameraParameters Parameters, bool SimulateSensor)
40{
41 DVSCameraParameters = Parameters;
43}
44
45void ADVSCamera::Init(FCameraBaseParameters parameters, bool SimulateSensor)
46{
47 // Defined in Camera.h
48 CameraName = "DVSCamera ";
49 FilePrefix = "Data/DVSCamera_";
50
51 Super::Init(DVSCameraParameters.CameraParameters, SimulateSensor);
52
53 const int32 Width = GetCameraWidth();
54 const int32 Height = GetCameraHeight();
55 const int32 Size = Width * Height;
56
57 auto DVSEventFill = DVSEvent();
58 EventArray.resize(Size, DVSEventFill);
59
60 DVSOutput.Init(FColor::Black, Size);
61
63
65 {
66 return;
67 }
68
69 // Since the Camera.cpp sensor works by USceneCaptureComponent2D rendering into custom Window texture,
70 // where its pixels are read through FrameGrabber API,
71 // We are unable (or at least I couldn't figure a way) to manipulate the pixels
72 // AND visualize it in the same Window texture without flickering.
73 // So here we can optionally create another window where we can visualize the DVS camera output.
74 // This Window can be closed safely and it does not destroy the sensor itself, and it will not stop sending data to ROS.
75
76 // Create another Window for DVS visualization.
77 FString windowName = GetSensorIdentifier() + " Output";
78 DVSUnrealWindow = MakeShareable(new FUnrealWindow(Width, Height, windowName));
79 if (DVSUnrealWindow.IsValid())
80 {
81 // Only draw when requested.
82 DVSUnrealWindow->SetAutomaticDraw(false);
83
85 DVSUnrealWindow->GetSWindow()->SetOnWindowClosed(OnDVSWindowClosed);
86 DVSUnrealWindow->ResizeWindow(Width, Height);
87 }
88
89#ifdef EngineAllowRenderingMinimized
90 // Minimize the DVS camera window (which just shows the RGB camera image without DVS conversion),
91 // so we are only left with DVS window
92 if (UnrealWindow.IsValid())
93 {
94 UnrealWindow->GetSWindow()->Minimize();
95 }
96#endif
97
98 // Setup PointCloudMessage
99 PointCloudMessage = MakeShared<ROSMessages::sensor_msgs::PointCloud2>();
100 PointCloudMessage->header.frame_id = "world";
101 PointCloudMessage->height = 1;
102 PointCloudMessage->is_dense = true;
103
104 PointCloudMessage->fields.Reserve(4);
105
106 PointCloudMessage->fields.Add({ "x", 0, ROSMessages::sensor_msgs::PointCloud2::PointField::UINT16, 1 });
107 PointCloudMessage->fields.Add({ "y", 2, ROSMessages::sensor_msgs::PointCloud2::PointField::UINT16, 1 });
108 PointCloudMessage->fields.Add({ "t", 4, ROSMessages::sensor_msgs::PointCloud2::PointField::UINT32, 1 });
109 PointCloudMessage->fields.Add({ "pol", 8, ROSMessages::sensor_msgs::PointCloud2::PointField::UINT8, 1 });
110
111 PointCloudMessage->point_step = 9;
112}
113
114void ADVSCamera::EndPlay(const EEndPlayReason::Type EndPlayReason)
115{
116 Super::EndPlay(EndPlayReason);
117
118 if (DVSUnrealWindow.IsValid())
119 {
120 OnDVSWindowClosed.Unbind();
121 DVSUnrealWindow->DestroyWindow();
122 DVSUnrealWindow.Reset();
123 }
124
126
127 LastEventTimestamp.Empty();
128 PreviousImage.Empty();
129 LastImage.Empty();
130 RefValues.Empty();
131 DVSOutput.Empty();
132
133 EventArray.clear();
134
135 PointCloudMessage.Reset();
136
137 if (DvsTopic)
138 {
139 DvsTopic->Unadvertise();
140 DvsTopic->Unsubscribe();
141 DvsTopic->MarkAsDisconnected();
142 DvsTopic->ConditionalBeginDestroy();
143 DvsTopic = nullptr;
144 }
145}
146
148{
150 SetParentParameters = false;
151 ParametersChanged = true;
152}
153
155{
156 TempDVSCameraParameters = NewParameters;
157 SetParentParameters = true;
158
159 if (!CanSimulateSensor())
160 {
162 }
163 else
164 {
165 ParametersChanged = true;
166 }
167}
168
169void ADVSCamera::DVSWindowClosedCallback(const TSharedRef<SWindow>& Window)
170{
171#if WITH_EDITOR
172 UE_LOG(LogTemp, Warning, TEXT("DVSCamera.cpp: DVS Camera output window closed."));
173#endif
174}
175
176float ADVSCamera::FColorToGrayScaleFloat(const FColor& Color)
177{
178 return R_WEIGHT * Color.R + G_WEIGHT * Color.G + B_WEIGHT * Color.B;
179}
180
181void ADVSCamera::ImageToGray(const TArray<FColor>& Buffer)
182{
183 LastImage.SetNumUninitialized(Buffer.Num());
184
185 // Convert image to gray image values
186 ParallelFor(Buffer.Num(), [&](int32 i)
187 {
188 LastImage[i] = FColorToGrayScaleFloat(Buffer[i]);
190}
191
192void ADVSCamera::ImageToLogGray(const TArray<FColor>& Buffer)
193{
194 const int32 Size = Buffer.Num();
195 const float LogEps = DVSCameraParameters.LogEps;
196
197 LastImage.SetNumUninitialized(Size);
198
199 // Convert FColors to logarithmic grayscale
200 ParallelFor(Size, [&](int32 Index)
201 {
202 float GrayScale = FColorToGrayScaleFloat(Buffer[Index]) * INV_MAX_VALUE;
203 LastImage[Index] = std::log(LogEps + GrayScale);
204 }, !DVSCameraParameters.ParalellImageConversion); // Force single thread? Default false.
205}
206
207std::vector<DVSEvent> ADVSCamera::SimulateDVS(const TArray<FColor>& Buffer)
208{
209 std::vector<DVSEvent> Events;
210
211 const int32 Width = GetCameraWidth();
212 const int32 Height = GetCameraHeight();
213 const int32 Size = Width * Height;
214
215 if (DVSOutput.Num() != Size)
216 {
217 DVSOutput.Empty();
218 DVSOutput.SetNumUninitialized(Size);
219 DVSOutput.Init(FColor::Black, Size);
220
221 PreviousImage.Empty();
222 PreviousImage.SetNumZeroed(0);
223 }
224
225 if (Buffer.Num() != Size)
226 {
227 return Events;
228 }
229
231 {
232 ImageToLogGray(Buffer);
233 }
234 else
235 {
236 ImageToGray(Buffer);
237 }
238
239 UWorld* World = GetWorld();
240
241 if (PreviousImage.Num() == 0)
242 {
243 // Set the first rendered image
246
247 // Resizes array to given number of elements. New elements will be zeroed.
248 LastEventTimestamp.SetNumZeroed(LastImage.Num());
249
250 // Reset current time
251 CurrentTime = SecToNanoSec(World->GetTimeSeconds());
252
253 return Events;
254 }
255
256 EventArray.clear();
257
258 auto DVSEventFill = DVSEvent();
259 DVSEventFill.x = 100;
260 DVSEventFill.y = 100;
261 DVSEventFill.t = 100;
262 EventArray.resize(Size, DVSEventFill);
263
264 FColor desiredColor = FColor::Black;
265 FMemory::Memset(DVSOutput.GetData(), desiredColor.ToPackedARGB(), DVSOutput.Num() * sizeof(FColor));
266
267 static constexpr float tolerance = 1e-6;
268
269 const std::uint64_t delta_t_ns = SecToNanoSec(World->GetTimeSeconds()) - CurrentTime;
270
271 const float cp = DVSCameraParameters.PositiveThreshold;
272 const float cm = DVSCameraParameters.NegativeThreshold;
273 const float sigma_cp = DVSCameraParameters.SigmaPositiveThreshold;
274 const float sigma_cm = DVSCameraParameters.SigmaNegativeThreshold;
275 const float refractory_period_ns = DVSCameraParameters.RefractoryPeriodNs;
276
277 // TODO: This could improved.
278 for (size_t y = 0; y < Height; y++)
279 {
280 for (int x = 0; x < Width; ++x)
281 {
282 const uint32 i = (Width * y) + x;
283 const float itdt = LastImage[i];
284 const float it = PreviousImage[i];
285 const float prev_cross = RefValues[i];
286
287 if (std::fabs(it - itdt) > tolerance)
288 {
289 const float pol = (itdt >= it) ? +1.0 : -1.0;
290 float C = (pol > 0) ? cp : cm;
291 const float sigma_C = (pol > 0) ? sigma_cp : sigma_cm;
292
293 if (sigma_C > 0)
294 {
295 C += std::normal_distribution<float>(0, sigma_C)(Engine);
296 constexpr float minimum_contrast_threshold = 0.01;
297 C = std::max(minimum_contrast_threshold, C);
298 }
299 float curr_cross = prev_cross;
300 bool all_crossings = false;
301 do
302 {
303 curr_cross += pol * C;
304
305 if ((pol > 0 && curr_cross > it && curr_cross <= itdt)
306 || (pol < 0 && curr_cross < it && curr_cross >= itdt))
307 {
308 const std::uint64_t edt = (curr_cross - it) * delta_t_ns / (itdt - it);
309 const std::int64_t t = CurrentTime + edt;
310
311 // check that pixel (x,y) is not currently in a "refractory" state
312 // i.e. |t-that last_timestamp(x,y)| >= refractory_period
313 const std::int64_t last_stamp_at_xy = SecToNanoSec(LastEventTimestamp[i]);
314 if (t >= last_stamp_at_xy)
315 {
316 const std::uint64_t dt = t - last_stamp_at_xy;
317 if (LastEventTimestamp[i] == 0 || dt >= refractory_period_ns)
318 {
319 bool val = pol > 0;
320
321 EventArray[i] = DVSEvent(x, y, t, val);
322 DVSOutput[i] = val ? FColor::Red : FColor::Black;
323
325 }
326 RefValues[i] = curr_cross;
327 }
328 }
329 else
330 {
331 all_crossings = true;
332 }
333 } while (!all_crossings);
334 }
335 }
336 }
337
338 // Update current time
339 CurrentTime = SecToNanoSec(World->GetTimeSeconds());
340
342
343 // Remove default values from EventArray std::vector
344 EventArray.erase(std::remove(EventArray.begin(), EventArray.end(), DVSEventFill), EventArray.end());
345
347 {
348 // Sort the events by increasing timestamps
349 std::sort(EventArray.begin(), EventArray.end(), [](const DVSEvent& it1, const DVSEvent& it2)
350 {
351 return it1.t < it2.t;
352 });
353 }
354
355 return EventArray;
356}
357
359{
360 if (!ROSInstance || !IsROSConnected())
361 {
362 return;
363 }
364
365 FString ID = GetSensorIdentifier();
366
367 if (!DvsTopic)
368 {
369 FString RawDataTopicName = FString::Printf(TEXT("/agrarsense/out/sensors/%s_raw"), *ID);
370
371 DvsTopic = NewObject<UTopic>(UTopic::StaticClass());
372 DvsTopic->Init(ROSInstance->ROSIntegrationCore, RawDataTopicName, TEXT("sensor_msgs/PointCloud2"));
373 DvsTopic->Advertise();
374
375#if WITH_EDITOR
376 UE_LOG(LogTemp, Warning, TEXT("DVSCamera.cpp: Created DVS Camera raw data ROS topic. Topic name: %s"), *RawDataTopicName);
377#endif
378 }
379
380 if (!ROSTopic)
381 {
382 FString ImageTopicName = FString::Printf(TEXT("/agrarsense/out/sensors/%s"), *ID);
383
384 ROSTopic = NewObject<UTopic>(UTopic::StaticClass());
385 ROSTopic->Init(ROSInstance->ROSIntegrationCore, ImageTopicName, TEXT("sensor_msgs/Image"));
386 ROSTopic->Advertise();
387
388#if WITH_EDITOR
389 UE_LOG(LogTemp, Warning, TEXT("DVSCamera.cpp: Created DVS Camera Image ROS topic. Topic name: %s"), *ImageTopicName);
390#endif
391 }
392}
393
395{
396 if (EventArray.size() == 0
397 || !SendDataToROS
398 || !DvsTopic
399 || !IsROSConnected()
400 || !PointCloudMessage.IsValid())
401 {
402 return;
403 }
404
405 PointCloudMessage->width = EventArray.size();
406 PointCloudMessage->row_step = PointCloudMessage->width * PointCloudMessage->point_step;
407
408 const DVSEvent* PointsDataPtr = EventArray.data();
409 PointCloudMessage->data_ptr = reinterpret_cast<uint8*>(const_cast<DVSEvent*>(PointsDataPtr));
410
411 // Send raw DVS data (PointCloud2) to ROS Topic
412 DvsTopic->Publish(PointCloudMessage);
413}
414
415void ADVSCamera::AddProcessingToFrameBuffer(TArray<FColor>& buffer)
416{
417 SimulateDVS(buffer);
418
419 FGraphEventRef SendDataToROSTask = FFunctionGraphTask::CreateAndDispatchWhenReady([this]()
420 {
422 }, TStatId(), nullptr, ENamedThreads::AnyBackgroundHiPriTask);
423
424 // Bind DVSOutput to buffer
425 buffer = DVSOutput;
426
427 // Update secondary Window with the new DVS image
428 UpdateDVSWindowOutput(buffer);
429
430 if (SendDataToROSTask.IsValid())
431 {
432 FTaskGraphInterface::Get().WaitUntilTaskCompletes(SendDataToROSTask);
433 }
434
436 {
438 }
439}
440
442{
443 ParametersChanged = false;
445
447 {
448 SetParentParameters = false;
449
450 // Change FCameraBaseParameters
452 }
453 else
454 {
455 if (DVSUnrealWindow.IsValid())
456 {
457 const int32 Width = GetCameraWidth();
458 const int32 Height = GetCameraHeight();
459 DVSUnrealWindow->ResizeWindow(Width, Height);
460 }
461 }
462}
463
464void ADVSCamera::UpdateDVSWindowOutput(const TArray<FColor>& Buffer)
465{
466 if (!DVSUnrealWindow.IsValid() || !CaptureFrameTexture)
467 {
468 return;
469 }
470
471 // CaptureFrameTexture defined in Camera.h and it should
472 // resize automatically in Camera.cpp if parent Window is resized.
473
474 // Lock texture
475 uint8* TextureData = static_cast<uint8*>(CaptureFrameTexture->GetPlatformData()->Mips[0].BulkData.Lock(LOCK_READ_WRITE));
476
477 // Copy buffer to texture
478 FMemory::Memcpy(TextureData, Buffer.GetData(), Buffer.Num() * sizeof(FColor));
479
480 // Unlock texture
481 CaptureFrameTexture->GetPlatformData()->Mips[0].BulkData.Unlock();
482
483 // Update texture resource
484 CaptureFrameTexture->UpdateResource();
485 FTextureResource* resource = CaptureFrameTexture->GetResource();
486
487 // Update new texture to window and draw
488 DVSUnrealWindow->UpdateTexture(resource);
489 DVSUnrealWindow->DrawManually();
490}
std::minstd_rand Engine
Definition: DVSCamera.cpp:23
static constexpr float INV_MAX_VALUE
Definition: DVSCamera.cpp:28
std::random_device rd
Definition: DVSCamera.cpp:22
static constexpr float G_WEIGHT
Definition: DVSCamera.cpp:26
static constexpr float R_WEIGHT
Definition: DVSCamera.cpp:25
static constexpr float B_WEIGHT
Definition: DVSCamera.cpp:27
Definition: Camera.h:52
bool UseParallelLateTick
Definition: Camera.h:220
void ChangeCameraParameters(FCameraBaseParameters newParameters)
Definition: Camera.cpp:50
FString FilePrefix
Definition: Camera.h:264
UTexture2D * CaptureFrameTexture
Definition: Camera.h:277
FCameraDelegate_OnWindowResized OnCameraWindowResized
Definition: Camera.h:147
FString CameraName
Definition: Camera.h:262
TSharedPtr< FUnrealWindow > UnrealWindow
Definition: Camera.h:279
int GetCameraWidth() const
Definition: Camera.h:192
int GetCameraHeight() const
Definition: Camera.h:198
float FColorToGrayScaleFloat(const FColor &Color)
Definition: DVSCamera.cpp:176
void ImageToLogGray(const TArray< FColor > &Buffer)
Definition: DVSCamera.cpp:192
void SendRawDVSImageDataToROS()
Definition: DVSCamera.cpp:394
TSharedPtr< FUnrealWindow > DVSUnrealWindow
Definition: DVSCamera.h:204
TArray< FColor > DVSOutput
Definition: DVSCamera.h:198
ADVSCamera(const FObjectInitializer &ObjectInitializer)
Definition: DVSCamera.cpp:30
TArray< float > PreviousImage
Definition: DVSCamera.h:175
FOnWindowClosed OnDVSWindowClosed
Definition: DVSCamera.h:208
virtual void AddProcessingToFrameBuffer(TArray< FColor > &buffer) override
Definition: DVSCamera.cpp:415
void ChangeParametersInternal()
Definition: DVSCamera.cpp:441
bool SetParentParameters
Definition: DVSCamera.h:200
bool ParametersChanged
Definition: DVSCamera.h:202
std::vector< DVSEvent > EventArray
Definition: DVSCamera.h:167
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: DVSCamera.h:206
UTopic * DvsTopic
Definition: DVSCamera.h:195
FDVSCameraParameters DVSCameraParameters
Definition: DVSCamera.h:187
void ChangeDVSCameraParameters(FDVSCameraParameters NewParameters)
Definition: DVSCamera.cpp:154
void DVSWindowClosedCallback(const TSharedRef< SWindow > &Window)
Definition: DVSCamera.cpp:169
TArray< float > RefValues
Definition: DVSCamera.h:181
void Init(FCameraBaseParameters parameters, bool SimulateSensor=true) override
Definition: DVSCamera.cpp:45
void CreateROSTopic() override
Definition: DVSCamera.cpp:358
void DVSInit(FDVSCameraParameters Parameters, bool SimulateSensor=true)
Definition: DVSCamera.cpp:39
FDVSCameraParameters TempDVSCameraParameters
Definition: DVSCamera.h:185
TArray< double > LastEventTimestamp
Definition: DVSCamera.h:172
void ImageToGray(const TArray< FColor > &Buffer)
Definition: DVSCamera.cpp:181
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: DVSCamera.cpp:114
std::vector< DVSEvent > SimulateDVS(const TArray< FColor > &Buffer)
Definition: DVSCamera.cpp:207
void OnMainCameraWindowResized(ACamera *Camera, FCameraBaseParameters Params)
Definition: DVSCamera.cpp:147
TArray< float > LastImage
Definition: DVSCamera.h:178
std::int64_t CurrentTime
Definition: DVSCamera.h:183
void UpdateDVSWindowOutput(const TArray< FColor > &Buffer)
Definition: DVSCamera.cpp:464
constexpr double NanoSecToSecTrunc(std::int64_t nanoseconds)
Definition: DVSCamera.h:227
constexpr std::int64_t SecToNanoSec(double seconds)
Definition: DVSCamera.h:217
UROSIntegrationGameInstance * ROSInstance
Definition: Sensor.h:352
bool CanSimulateSensor() const
Definition: Sensor.h:161
FString GetSensorIdentifier() const
Definition: Sensor.h:74
UTopic * ROSTopic
Definition: Sensor.h:341
bool IsROSConnected() const
Definition: Sensor.h:192
bool SendDataToROS
Definition: Sensor.h:344
FCameraBaseParameters CameraParameters