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
168 /*
169 * Disables many camera show flags for faster rendering. Used for Depth/Semantic cameras.
170 */
171 void DisableShowFlags();
172
176 UFUNCTION(BlueprintCallable)
177 void SetTemporalAA(bool SetTemporal);
178
182 UFUNCTION(BlueprintCallable)
183 void ResizeCamera(int Width = 1280, int Height = 720);
184
188 UFUNCTION(BlueprintCallable)
189 void SaveCurrentFrameToDisk()
190 {
191 if (!CameraParameters.SaveImageToDisk)
192 {
193 SaveCurrentFrameToDiskRequested = true;
194 }
195 }
196
197 UFUNCTION(BlueprintCallable)
198 int GetCameraWidth() const
199 {
200 return ImageWidth;
201 }
202
203 UFUNCTION(BlueprintCallable)
204 int GetCameraHeight() const
205 {
206 return ImageHeight;
207 }
208
209 UFUNCTION(BlueprintCallable)
210 void SetUseGimbal(bool UseGimbal)
211 {
212 AllowGimbal = UseGimbal;
213 }
214
218 virtual FString GetParametersAsString() const override
219 {
220 return StructToString(CameraParameters);
221 }
222
223protected:
224
225 virtual void BeginPlay() override;
226
227 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
228
229 /*
230 * Should we use ATicMananger to tick in parallel or use post actor tick
231 */
232 bool UseParallelLateTick = true;
233
234 FDelegateHandle OnPreTickDelegate;
235 virtual void PreActorTick(UWorld* World, ELevelTick TickType, float DeltaSeconds);
236
237 FDelegateHandle OnPostTickDelegate;
238 virtual void EndOfFrame(UWorld* World, ELevelTick TickType, float DeltaSeconds);
239 virtual void EndOfFrameParellel(float DeltaTime);
240
241 /*
242 * Override function to all other camera variants if buffer editing is needed
243 */
244 virtual void AddProcessingToFrameBuffer(TArray<FColor>& buffer);
245
252 virtual void SendImageDataToROS(const TArray<FColor>& FrameBuffer, int32 Width, int32 Height);
253
254 UFUNCTION()
255 void HidePrimitiveComponent(UPrimitiveComponent* PrimitiveComponent);
256
263 void SaveImageToDisk(const TArray<FColor> FrameBuffer, int32 Width, int32 Height);
264
265 void SaveCameraMetaDataToDisk(const FString& ImageName);
266
267 void CreateLogFile() override;
268
274 FString CameraName = "Camera ";
275
276 FString FilePrefix = "Data/Camera_";
277
278 UPROPERTY()
279 UTextureRenderTarget2D* CaptureRenderTarget = nullptr;
280
281 UPROPERTY(VisibleAnywhere)
282 USceneCaptureComponent2D* CaptureComponent2D = nullptr;
283
288 UPROPERTY(EditAnywhere, BlueprintReadOnly, Category = "FrameGrabber")
289 UTexture2D* CaptureFrameTexture;
290
291 TSharedPtr<FUnrealWindow> UnrealWindow;
292
293 FTickEntry TickEntry;
294
295 TWeakObjectPtr<UMaterialInstanceDynamic> IceMaterialInstance;
296
297 TWeakObjectPtr<UMaterial> PhysicLensDistortion;
298
299 // For Gimbal
300 APIDDrone* DronePtr = nullptr;
301 FRotator SensorSetRotation;
302 bool AllowGimbal = true;
303
304private:
305
309 void StartFrameGrabber();
310
314 void ReleaseFrameGrabber();
315
319 void FrameGrabberCapture();
320
325 void OnWindowClosed(const TSharedRef<SWindow>& Window);
326
330 TSharedPtr<FFrameGrabber>FrameGrabber;
331
335 void SetupCamera(FCameraBaseParameters parameters);
336
340 bool ShouldSimulate(const float DeltaSeconds);
341
345 UPROPERTY(VisibleAnywhere, Category = "Sensor")
346 FCameraBaseParameters CameraParameters;
347
348 /*
349 * Temperaory Camera parameters.
350 * Camera parameter changes are applied at the end of the frame.
351 */
353
354 UPROPERTY()
355 AGeoReferencingSystem* GeoReferencingSystem = nullptr;
356
357 bool ParametersChanged = false;
358
359 FOnWindowClosed OnWindowClosedDelegate;
360
361 TSharedPtr<ROSMessages::sensor_msgs::Image> ImageMsg;
362
363 int32 ImageWidth = 1280;
364 int32 ImageHeight = 720;
365
366 bool SaveCurrentFrameToDiskRequested = false;
367
368 bool ShouldSimulateCamera = true;
369
370 float CameraFrameRate = 0.0f;
371 float FrameRateTimer = 0.0f;
372
373 int32 ImageNumber = 0;
374
375 uint8* BGR8Buffer = nullptr;
376
377 int32 CurrentBufferSize = 0;
378};
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:218
FDelegateHandle OnPostTickDelegate
Definition: Camera.h:237
FDelegateHandle OnPreTickDelegate
Definition: Camera.h:234
UWorld * World
Definition: PIDDrone.h:207
virtual void BeginPlay() override
Definition: PIDDrone.cpp:29
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: PIDDrone.cpp:61
Definition: Sensor.h:45