Agrarsense
Camera.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
8#include "CoreMinimal.h"
10
11#include "Engine/TextureRenderTarget2D.h"
12#include "Kismet/KismetSystemLibrary.h"
13#include "Delegates/IDelegateInstance.h"
14#include "Materials/MaterialInstanceDynamic.h"
15#include "Components/SceneCaptureComponent2D.h"
16#include "Engine/Texture2D.h"
17#include "FrameGrabber.h"
18#include "Materials/Material.h"
19
23
24#include "ROSIntegration/Public/sensor_msgs/Image.h"
25
26#include "Camera.generated.h"
27
28class AGeoReferencingSystem;
29class UROSHandler;
30class UWidget;
31class APIDDrone;
32
36DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FCameraDelegate_OnWindowClosed, ACamera*, Camera);
37
41DECLARE_DYNAMIC_MULTICAST_DELEGATE_TwoParams(FCameraDelegate_OnWindowResized, ACamera*, Camera, FCameraBaseParameters, Params);
42
51UCLASS()
52class AGRARSENSE_API ACamera : public ASensor
53{
54 GENERATED_BODY()
55
56public:
57
62 ACamera(const FObjectInitializer& ObjectInitializer);
63
68 virtual void Init(FCameraBaseParameters parameters, bool SimulateSensor = true);
69
74 virtual ESensorTypes GetSensorType() const override
75 {
77 }
78
83 UFUNCTION(BlueprintCallable)
84 void ChangeCameraParameters(FCameraBaseParameters newParameters);
85
90 UFUNCTION(BlueprintCallable, BlueprintPure)
91 FCameraBaseParameters GetCameraParameters()
92 {
93 return CameraParameters;
94 }
95
101 void AddPostProcessingMaterial(const FString& Path, float Weight = 1.0f);
102
107 void RemovePostProcessingMaterial(UMaterial* Material);
108
113 UFUNCTION(BlueprintCallable)
114 USceneCaptureComponent2D* GetCaptureComponent2D() const
115 {
116 return CaptureComponent2D;
117 }
118
123 UFUNCTION(BlueprintCallable)
124 UTextureRenderTarget2D* GetCaptureRenderTarget2D() const
125 {
126 return CaptureRenderTarget;
127 }
128
133 UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "FrameGrabber")
134 TEnumAsByte<ETextureRenderTargetFormat> TextureFormat = ETextureRenderTargetFormat::RTF_RGBA8;
135
140 UPROPERTY(BlueprintAssignable)
141 FCameraDelegate_OnWindowClosed OnCameraWindowClosed;
142
147 UPROPERTY(BlueprintAssignable)
148 FCameraDelegate_OnWindowResized OnCameraWindowResized;
149
153 UFUNCTION(BlueprintCallable)
154 void AddWidgetToWindow(UWidget* WidgetToAdd);
155
159 UFUNCTION(BlueprintCallable)
160 void RemoveWidgetFromWindow(UWidget* WidgetToRemove);
161
165 UFUNCTION(BlueprintCallable)
166 void SetShadowRendering(bool RenderShadows);
167
171 UFUNCTION(BlueprintCallable)
172 void SetTemporalAA(bool SetTemporal);
173
177 UFUNCTION(BlueprintCallable)
178 void ResizeCamera(int Width = 1280, int Height = 720);
179
183 UFUNCTION(BlueprintCallable)
184 void SaveCurrentFrameToDisk()
185 {
186 if (!CameraParameters.SaveImageToDisk)
187 {
188 SaveCurrentFrameToDiskRequested = true;
189 }
190 }
191
192 UFUNCTION(BlueprintCallable)
193 int GetCameraWidth() const
194 {
195 return ImageWidth;
196 }
197
198 UFUNCTION(BlueprintCallable)
199 int GetCameraHeight() const
200 {
201 return ImageHeight;
202 }
203
204 UFUNCTION(BlueprintCallable)
205 void SetUseGimbal(bool UseGimbal)
206 {
207 AllowGimbal = UseGimbal;
208 }
209
213 virtual FString GetParametersAsString() const override
214 {
215 return StructToString(CameraParameters);
216 }
217
218protected:
219
220 virtual void BeginPlay() override;
221
222 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
223
224 /*
225 * Should we use ATicMananger to tick in parallel or use post actor tick
226 */
227 bool UseParallelLateTick = true;
228
229 FDelegateHandle OnPreTickDelegate;
230 virtual void PreActorTick(UWorld* World, ELevelTick TickType, float DeltaSeconds);
231
232 FDelegateHandle OnPostTickDelegate;
233 virtual void EndOfFrame(UWorld* World, ELevelTick TickType, float DeltaSeconds);
234 virtual void EndOfFrameParellel(float DeltaTime);
235
236 /*
237 * Override function to all other camera variants if buffer editing is needed
238 */
239 virtual void AddProcessingToFrameBuffer(TArray<FColor>& buffer);
240
247 virtual void SendImageDataToROS(const TArray<FColor>& FrameBuffer, int32 Width, int32 Height);
248
249 UFUNCTION()
250 void HidePrimitiveComponent(UPrimitiveComponent* PrimitiveComponent);
251
258 void SaveImageToDisk(const TArray<FColor> FrameBuffer, int32 Width, int32 Height);
259
260 void SaveCameraMetaDataToDisk(const FString& ImageName);
261
262 void CreateLogFile() override;
263
269 FString CameraName = "Camera ";
270
271 FString FilePrefix = "Data/Camera_";
272
273 UPROPERTY()
274 UTextureRenderTarget2D* CaptureRenderTarget = nullptr;
275
276 UPROPERTY(VisibleAnywhere)
277 USceneCaptureComponent2D* CaptureComponent2D = nullptr;
278
283 UPROPERTY(EditAnywhere, BlueprintReadOnly, Category = "FrameGrabber")
284 UTexture2D* CaptureFrameTexture;
285
286 TSharedPtr<FUnrealWindow> UnrealWindow;
287
288 FTickEntry TickEntry;
289
290 TWeakObjectPtr<UMaterialInstanceDynamic> IceMaterialInstance;
291
292 TWeakObjectPtr<UMaterial> PhysicLensDistortion;
293
294 // For Gimbal
295 APIDDrone* DronePtr = nullptr;
296 FRotator SensorSetRotation;
297 bool AllowGimbal = true;
298
299private:
300
304 void StartFrameGrabber();
305
309 void ReleaseFrameGrabber();
310
314 void FrameGrabberCapture();
315
320 void OnWindowClosed(const TSharedRef<SWindow>& Window);
321
325 TSharedPtr<FFrameGrabber>FrameGrabber;
326
330 void SetupCamera(FCameraBaseParameters parameters);
331
335 bool ShouldSimulate(const float DeltaSeconds);
336
340 UPROPERTY(VisibleAnywhere, Category = "Sensor")
341 FCameraBaseParameters CameraParameters;
342
343 /*
344 * Temperaory Camera parameters.
345 * Camera parameter changes are applied at the end of the frame.
346 */
348
349 UPROPERTY()
350 AGeoReferencingSystem* GeoReferencingSystem = nullptr;
351
352 bool ParametersChanged = false;
353
354 FOnWindowClosed OnWindowClosedDelegate;
355
356 TSharedPtr<ROSMessages::sensor_msgs::Image> ImageMsg;
357
358 int ImageWidth = 1280;
359 int ImageHeight = 720;
360
361 bool SaveCurrentFrameToDiskRequested = false;
362
363 bool ShouldSimulateCamera = true;
364
365 float CameraFrameRate = 0.0f;
366 float FrameRateTimer = 0.0f;
367
368 int ImageNumber = 0;
369
370 uint8* BGR8Buffer = nullptr;
371
372 int32 CurrentBufferSize = 0;
373};
DECLARE_DYNAMIC_MULTICAST_DELEGATE_TwoParams(FCameraDelegate_OnWindowResized, ACamera *, Camera, FCameraBaseParameters, Params)
DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FCameraDelegate_OnWindowClosed, ACamera *, Camera)
ESensorTypes
Definition: SensorTypes.h:15
Definition: Camera.h:53
virtual ESensorTypes GetSensorType() const override
Definition: Camera.h:74
virtual FString GetParametersAsString() const override
Definition: Camera.h:213
FDelegateHandle OnPostTickDelegate
Definition: Camera.h:232
FDelegateHandle OnPreTickDelegate
Definition: Camera.h:229
UWorld * World
Definition: PIDDrone.h:188
virtual void BeginPlay() override
Definition: PIDDrone.cpp:24
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: PIDDrone.cpp:36
Definition: Sensor.h:44