Agrarsense
Camera.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 "Camera.h"
7
16
17#include "NiagaraComponent.h"
18#include "Components/PrimitiveComponent.h"
19#include "Materials/Material.h"
20#include "ImageUtils.h"
21#include "Async/Async.h"
22#include "HighResScreenshot.h"
23#include "ImageWriteTask.h"
24#include "ImageWriteQueue.h"
25#include "Misc/DateTime.h"
26#include "Math/Color.h"
27#include "Blueprint/UserWidget.h"
28#include "GameFramework/PlayerController.h"
29#include "GeoReferencingSystem.h"
30#include "TimerManager.h"
31#include "GameFramework/SpringArmComponent.h"
32
33ACamera::ACamera(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
34{
35 PrimaryActorTick.bCanEverTick = true;
36 PrimaryActorTick.TickGroup = TG_PostUpdateWork;
37
38 CaptureRenderTarget = CreateDefaultSubobject<UTextureRenderTarget2D>(FName(*FString::Printf(TEXT("CaptureRenderTarget"))));
39 CaptureRenderTarget->CompressionSettings = TextureCompressionSettings::TC_Default;
40 CaptureRenderTarget->SRGB = false;
41 CaptureRenderTarget->bAutoGenerateMips = false;
42 CaptureRenderTarget->bGPUSharedFlag = true;
43 CaptureRenderTarget->AddressX = TextureAddress::TA_Clamp;
44 CaptureRenderTarget->AddressY = TextureAddress::TA_Clamp;
45
46 CaptureComponent2D = CreateDefaultSubobject<USceneCaptureComponent2D>(FName(*FString::Printf(TEXT("SceneCaptureComponent2D"))));
47 CaptureComponent2D->SetupAttachment(RootComponent);
48 CaptureComponent2D->PrimitiveRenderMode = ESceneCapturePrimitiveRenderMode::PRM_RenderScenePrimitives;
49 CaptureComponent2D->bCaptureOnMovement = false;
50 CaptureComponent2D->bCaptureEveryFrame = false;
51 CaptureComponent2D->bAlwaysPersistRenderingState = true;
52}
53
55{
56 SetupCamera(newParameters);
57}
58
59void ACamera::AddPostProcessingMaterial(const FString& Path, float Weight)
60{
61 UMaterial* PostProcessingMat = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
62 if (PostProcessingMat && CaptureComponent2D)
63 {
64 FPostProcessSettings& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
65 PostProcessSettings.AddBlendable(PostProcessingMat, Weight);
66 }
67 else
68 {
69 const FString ErrorMessage = FString::Printf(TEXT("Failed to add post-processing material to sensor: %s"), *GetSensorName());
70 SimulatorLog::Log(ErrorMessage);
71 }
72}
73
75{
77 {
78 FPostProcessSettings& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
79 PostProcessSettings.RemoveBlendable(Material);
80 }
81}
82
83void ACamera::Init(FCameraBaseParameters parameters, bool SimulateSensor)
84{
86 SetSimulateSensor(SimulateSensor);
87 SetupCamera(parameters);
88}
89
91{
92 if (IsValid(LogFile))
93 {
94 // File has already been created, return
95 return;
96 }
97
98 FLogFileSettings Settings;
101 Settings.QueueLength = MAX_int32; // Only write the log after destroying the sensor
102 Settings.KeepFileOpen = false;
103 Settings.Timestamp = false;
104 Settings.OverrideFilePath = true;
105 Settings.FilePath = FileSavePath;
106
107 LogFile = NewObject<ULogFile>(ULogFile::StaticClass());
108 if (IsValid(LogFile))
109 {
110 const FString FileName = "camera_metadata";
111 LogFile->Create(FileName, Settings);
112
113 // Write camera metadata first line to explain the values.
114 GeoReferencingSystem = AGeoReferencingSystem::GetGeoReferencingSystem(GetWorld());
116 {
117 WriteToLogFile("timestamp, image_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation, GPS latitude, GPS longitude, GPS altitude");
118 }
119 else
120 {
121 WriteToLogFile("timestamp, image_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation");
122 }
123 }
124}
125
127{
129 {
130#if WITH_EDITOR
131 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: CaptureComponent2D is nullptr!"));
132#endif
133 return;
134 }
135
136 CameraParameters = parameters;
137
139
141 {
143 }
144
145 const bool UsePostProcessingEffects = CameraParameters.PostProcessingEffects;
146 auto& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
147
148 if (parameters.UsePhysicLensDistortionEffect)
149 {
150 if (!PhysicLensDistortion.IsValid())
151 {
152 const FString Path = "/Game/Agrarsense/Materials/PostProcessingMaterials/PhysicLensDistortion.PhysicLensDistortion";
153 PhysicLensDistortion = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
154
155 if (PhysicLensDistortion.IsValid())
156 {
157 PostProcessSettings.AddBlendable(PhysicLensDistortion.Get(), 1.0f);
158#if WITH_EDITOR
159 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Added physics lens distortion effect."));
160#endif
161 }
162 }
163 }
164 else if (PhysicLensDistortion.IsValid())
165 {
166 PostProcessSettings.RemoveBlendable(PhysicLensDistortion.Get());
167 PhysicLensDistortion.Reset();
168#if WITH_EDITOR
169 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Removed physics lens distortion effect."));
170#endif
171 }
172
173 if (parameters.UseIceLensEffect)
174 {
175 if (!IceMaterialInstance.IsValid())
176 {
177 const FString Path = "/Game/Agrarsense/Materials/PostProcessingMaterials/CameraPostProcessEffects/m_ice_lens_effect";
178 UMaterial* LoadedIceMaterial = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
179
180 // Create UMaterialInstanceDynamic from LoadedIceMaterial
181 IceMaterialInstance = UMaterialInstanceDynamic::Create(LoadedIceMaterial, nullptr);
182 if (IceMaterialInstance.IsValid())
183 {
184 // Add material to CaptureComponent2D PostProcessSettings
185 PostProcessSettings.AddBlendable(IceMaterialInstance.Get(), 1.0f);
186#if WITH_EDITOR
187 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Added ice lens effect."));
188#endif
189 }
190 }
191
192 UMaterialInstanceDynamic* IceMatInstance = IceMaterialInstance.Get();
193 if (IceMatInstance)
194 {
195 // Set IceMaterialInstance scalar parameters values
196 IceMatInstance->SetScalarParameterValue(FName("Strength"), parameters.IceLensEffectStrength);
197 IceMatInstance->SetScalarParameterValue(FName("Angle"), parameters.IceLensEffectAngle);
198#if WITH_EDITOR
199 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Changed ice lens effect parameters."));
200#endif
201 }
202 }
203 else if (IceMaterialInstance.IsValid())
204 {
205 UMaterialInstanceDynamic* IceMatInstance = IceMaterialInstance.Get();
206 if (IceMatInstance)
207 {
208 // Remove material from CaptureComponent2D PostProcessSettings
209 PostProcessSettings.RemoveBlendable(IceMatInstance);
210 IceMaterialInstance.Reset();
211
212#if WITH_EDITOR
213 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Removed ice lens effect."));
214#endif
215 }
216 }
217
220 const float TargetGamma = CameraParameters.TargetGamma;
221 const bool Enable16BitFormat = CameraParameters.Enable16BitFormat;
222
223 CaptureRenderTarget->InitCustomFormat(ImageWidth, ImageHeight, Enable16BitFormat ? PF_FloatRGB : PF_B8G8R8A8, !UsePostProcessingEffects);
224
225 CaptureRenderTarget->TargetGamma = TargetGamma;
226
227 // Set PostProcessSettings override (on or off)
228 PostProcessSettings.bOverride_AutoExposureMethod = UsePostProcessingEffects;
229 PostProcessSettings.bOverride_AutoExposureBias = UsePostProcessingEffects;
230 PostProcessSettings.bOverride_AutoExposureMinBrightness = UsePostProcessingEffects;
231 PostProcessSettings.bOverride_AutoExposureMaxBrightness = UsePostProcessingEffects;
232 PostProcessSettings.bOverride_AutoExposureSpeedUp = UsePostProcessingEffects;
233 PostProcessSettings.bOverride_AutoExposureSpeedDown = UsePostProcessingEffects;
234 PostProcessSettings.bOverride_HistogramLogMin = UsePostProcessingEffects;
235 PostProcessSettings.bOverride_HistogramLogMax = UsePostProcessingEffects;
236 PostProcessSettings.bOverride_CameraShutterSpeed = UsePostProcessingEffects;
237 PostProcessSettings.bOverride_CameraISO = UsePostProcessingEffects;
238 PostProcessSettings.bOverride_DepthOfFieldFstop = UsePostProcessingEffects;
239 PostProcessSettings.bOverride_DepthOfFieldMinFstop = UsePostProcessingEffects;
240 PostProcessSettings.bOverride_DepthOfFieldBladeCount = UsePostProcessingEffects;
241 PostProcessSettings.bOverride_FilmSlope = UsePostProcessingEffects;
242 PostProcessSettings.bOverride_FilmToe = UsePostProcessingEffects;
243 PostProcessSettings.bOverride_FilmShoulder = UsePostProcessingEffects;
244 PostProcessSettings.bOverride_FilmWhiteClip = UsePostProcessingEffects;
245 PostProcessSettings.bOverride_FilmBlackClip = UsePostProcessingEffects;
246 PostProcessSettings.bOverride_MotionBlurAmount = UsePostProcessingEffects;
247 PostProcessSettings.bOverride_MotionBlurMax = UsePostProcessingEffects;
248 PostProcessSettings.bOverride_MotionBlurPerObjectSize = UsePostProcessingEffects;
249 PostProcessSettings.bOverride_WhiteTemp = UsePostProcessingEffects;
250 PostProcessSettings.bOverride_WhiteTint = UsePostProcessingEffects;
251 PostProcessSettings.bOverride_ColorContrast = UsePostProcessingEffects;
252 PostProcessSettings.bOverride_SceneFringeIntensity = UsePostProcessingEffects;
253 PostProcessSettings.bOverride_ChromaticAberrationStartOffset = UsePostProcessingEffects;
254 PostProcessSettings.bOverride_AmbientOcclusionIntensity = UsePostProcessingEffects;
255 PostProcessSettings.bOverride_AmbientOcclusionRadius = UsePostProcessingEffects;
256 PostProcessSettings.bOverride_AmbientOcclusionStaticFraction = UsePostProcessingEffects;
257 PostProcessSettings.bOverride_AmbientOcclusionFadeDistance = UsePostProcessingEffects;
258 PostProcessSettings.bOverride_AmbientOcclusionPower = UsePostProcessingEffects;
259 PostProcessSettings.bOverride_AmbientOcclusionBias = UsePostProcessingEffects;
260 PostProcessSettings.bOverride_AmbientOcclusionQuality = UsePostProcessingEffects;
261 PostProcessSettings.bOverride_BloomMethod = UsePostProcessingEffects;
262 PostProcessSettings.bOverride_BloomIntensity = UsePostProcessingEffects;
263 PostProcessSettings.bOverride_BloomThreshold = UsePostProcessingEffects;
264 PostProcessSettings.bOverride_LensFlareIntensity = UsePostProcessingEffects;
265 PostProcessSettings.bOverride_DepthOfFieldFocalDistance = UsePostProcessingEffects;
266 PostProcessSettings.bOverride_DepthOfFieldDepthBlurAmount = UsePostProcessingEffects;
267 PostProcessSettings.bOverride_DepthOfFieldDepthBlurRadius = UsePostProcessingEffects;
268
269 // Set PostProcessSettings values
270 PostProcessSettings.CameraShutterSpeed = CameraParameters.ShutterSpeed;
271 PostProcessSettings.CameraISO = CameraParameters.ISO;
272 PostProcessSettings.DepthOfFieldFstop = CameraParameters.Aperture;
273 PostProcessSettings.DepthOfFieldFocalDistance = CameraParameters.FocalDistance;
274 PostProcessSettings.DepthOfFieldDepthBlurAmount = CameraParameters.DepthBlurAmount;
275 PostProcessSettings.DepthOfFieldDepthBlurRadius = CameraParameters.DepthBlurRadius;
276 PostProcessSettings.DepthOfFieldMinFstop = CameraParameters.DofMinFStop;
277 PostProcessSettings.DepthOfFieldBladeCount = CameraParameters.DofBladeCount;
278 PostProcessSettings.FilmSlope = CameraParameters.FilmSlope;
279 PostProcessSettings.FilmToe = CameraParameters.FilmToe;
280 PostProcessSettings.FilmShoulder = CameraParameters.FilmShoulder;
281 PostProcessSettings.FilmBlackClip = CameraParameters.FilmBlackClip;
282 PostProcessSettings.FilmWhiteClip = CameraParameters.FilmWhiteClip;
283 PostProcessSettings.AutoExposureMinBrightness = CameraParameters.ExposureMinBrightness;
284 PostProcessSettings.AutoExposureMaxBrightness = CameraParameters.ExposureMaxBrightness;
285 PostProcessSettings.AutoExposureSpeedUp = CameraParameters.ExposureSpeedUp;
286 PostProcessSettings.AutoExposureSpeedDown = CameraParameters.ExposureSpeedDown;
287 PostProcessSettings.MotionBlurAmount = CameraParameters.MotionBlurIntensity;
288 PostProcessSettings.MotionBlurMax = CameraParameters.MotionBlurMax;
289 PostProcessSettings.MotionBlurPerObjectSize = CameraParameters.MotionBlurMinObjSize;
290 PostProcessSettings.LensFlareIntensity = CameraParameters.LensFlareIntensity;
291 PostProcessSettings.BloomIntensity = CameraParameters.BloomIntensity;
292 PostProcessSettings.WhiteTemp = CameraParameters.WhiteTemp;
293 PostProcessSettings.WhiteTint = CameraParameters.WhiteTint;
294 PostProcessSettings.SceneFringeIntensity = CameraParameters.ChromAberrIntensity;
295 PostProcessSettings.ChromaticAberrationStartOffset = CameraParameters.ChromAberrOffset;
296
299
301 {
303 }
304 else
305 {
306 CaptureComponent2D->MaxViewDistanceOverride = -1.0f; // Infinite
307 }
308
310 {
311 // Enable HDR on CaptureSource, only allowed for RGB Camera for now.
312 CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_FinalToneCurveHDR;
313 }
314 else
315 {
316 CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR;
317 }
318
319 CaptureComponent2D->bUseRayTracingIfEnabled = true;
320 CaptureComponent2D->UpdateContent();
321 CaptureComponent2D->Activate();
322
324
325 const FString Encoding = "bgr8";
326
327 // Create ROS Image message
328 ImageMsg.Reset();
329 ImageMsg = MakeShared<ROSMessages::sensor_msgs::Image>();
330 ImageMsg->header.frame_id = "world";
331 ImageMsg->height = ImageWidth;
332 ImageMsg->width = ImageHeight;
333 ImageMsg->encoding = Encoding;
334 ImageMsg->is_bigendian = 0;
335 ImageMsg->step = ImageWidth * 4;
336
338
339 if (!UnrealWindow.IsValid())
340 {
341 // Create and setup UnrealWindow
342 const FString WindowName = GetSensorIdentifier() + " Window";
344
345 // Set on Window closed event
347 UnrealWindow->GetSWindow()->SetOnWindowClosed(OnWindowClosedDelegate);
348
349 // try to create Camera parameter Widget from path
350 FSoftClassPath WidgetClassPath(TEXT("/Game/Agrarsense/Widgets/Camera/WBP_CameraControlsMenu.WBP_CameraControlsMenu_C"));
351 UClass* WidgetClass = WidgetClassPath.TryLoadClass<UUserWidget>();
352
353 APlayerController* PlayerController = UGameplayStatics::GetPlayerController(GetWorld(), 0);
354
355 if (WidgetClass && PlayerController)
356 {
357 UCameraWidgetBase* WidgetInstance = CreateWidget<UCameraWidgetBase>(PlayerController, WidgetClass);
358 if (WidgetInstance)
359 {
360 bool ShowGuide = false;
361 WidgetInstance->Setup(this, ShowGuide);
362 this->AddWidgetToWindow(WidgetInstance);
363 }
364 }
365 }
366
367 bool Resized = false;
368 if (UnrealWindow.IsValid())
369 {
370 UnrealWindow->SetupComponent(CaptureRenderTarget);
371 if (UnrealWindow->GetWindowWidth() != ImageWidth || UnrealWindow->GetWindowHeight() != ImageHeight)
372 {
373 UnrealWindow->ResizeWindow(ImageWidth, ImageHeight);
374 Resized = true;
375 }
376 }
377
379
380 if (Resized)
381 {
383 }
384
386 {
388 }
389}
390
392{
393 Super::BeginPlay();
394
395 // Register to PreActorTick where USceneCaptureComponent2D will get rendered.
396 OnPreTickDelegate = FWorldDelegates::OnWorldPreActorTick.AddUObject(this, &ACamera::PreActorTick);
397
398 // Check if we should use ATickManager which ticks in parallel, or use Post actor tick
399 // In there we capture the screen pixels with FrameGrabber API,
400 // might do some extra processing, save image to disk and send data to ROS.
402 {
403 SetActorTickEnabled(false);
404 TickEntry = ATickManager::AddTick(this, BindTick(this, &ACamera::EndOfFrameParellel), ETickType::LateTickParallel);
405 }
406 else
407 {
408 SetActorTickEnabled(true);
409 OnPostTickDelegate = FWorldDelegates::OnWorldPostActorTick.AddUObject(this, &ACamera::EndOfFrame);
410 }
411
412 // Get all existing components set to be hidden for all Camera sensors (like Lidar point cloud visualization).
413 auto Components = ASensor::GetComponentsToHide();
414 for (int32 i = 0; i < Components.Num(); i++)
415 {
416 UPrimitiveComponent* Primitive = Components[i].Get();
417 if (Primitive)
418 {
419 HidePrimitiveComponent(Primitive);
420 }
421 }
422
423 OnPrimitiveAdded.AddUniqueDynamic(this, &ACamera::HidePrimitiveComponent);
424
425 GetWorld()->GetTimerManager().SetTimerForNextTick([this]()
426 {
427 if (IsValid(this))
428 {
429 DronePtr = Cast<APIDDrone>(GetAttachParentActor());
430 if (!DronePtr)
431 {
432 AllowGimbal = false;
433 }
434 }
435 });
436}
437
438void ACamera::EndPlay(const EEndPlayReason::Type EndPlayReason)
439{
440 Super::EndPlay(EndPlayReason);
441
442 FWorldDelegates::OnWorldPreActorTick.Remove(OnPreTickDelegate);
443
445 {
447 }
448 else
449 {
450 FWorldDelegates::OnWorldPostActorTick.Remove(OnPostTickDelegate);
451 }
452
453 if (UnrealWindow.IsValid())
454 {
455 OnWindowClosedDelegate.Unbind();
456 UnrealWindow->DestroyWindow();
457 UnrealWindow.Reset();
458 }
459
461
463 {
464 CaptureRenderTarget->ConditionalBeginDestroy();
465 CaptureRenderTarget = nullptr;
466 }
467
469 {
470 CaptureComponent2D->UnregisterComponent();
471 CaptureComponent2D->ConditionalBeginDestroy();
472 CaptureComponent2D = nullptr;
473 }
474
475 ImageMsg.Reset();
476 IceMaterialInstance.Reset();
477
478 if (BGR8Buffer)
479 {
480 delete[] BGR8Buffer;
481 BGR8Buffer = nullptr;
482 }
484}
485
486void ACamera::PreActorTick(UWorld* World, ELevelTick TickType, float DeltaSeconds)
487{
488 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::PreActorTick);
489
490 // If this Camera sensor is attached to Drone, keep the camera steady kind of like a Gimbal.
492 {
493 if (SensorSetRotation == FRotator::ZeroRotator)
494 {
495 // Save garage sensor values
496 SensorSetRotation = GetTransform().Rotator();
497 }
498 FRotator gimbalRot = FRotator(SensorSetRotation.Pitch, GetActorRotation().Yaw, SensorSetRotation.Roll);
499 SetActorRotation(gimbalRot);
500 }
501
502 if (ShouldSimulate(DeltaSeconds) && CaptureComponent2D)
503 {
504 // Capture scene now.
505 // We could use CaptureSceneDeferred but it would not work if World (Spectator) Rendering is disabled.
506 CaptureComponent2D->CaptureScene();
507
508 // Inform FrameGrabber to capture this frame
509 if (FrameGrabber.IsValid())
510 {
511 FrameGrabber->CaptureThisFrame(FFramePayloadPtr());
512 }
513 }
514}
515
516void ACamera::EndOfFrame(UWorld* World, ELevelTick TickType, float DeltaSeconds)
517{
519}
520
521void ACamera::EndOfFrameParellel(float DeltaTime)
522{
524}
525
526bool ACamera::ShouldSimulate(const float DeltaSeconds)
527{
528 if (!CanSimulateSensor())
529 {
530 ShouldSimulateCamera = false;
532 }
533
535 {
538 }
539
540 FrameRateTimer += DeltaSeconds;
542 {
543 FrameRateTimer = 0.0f;
546 }
547
548 ShouldSimulateCamera = false;
549
551}
552
554{
555 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::FrameGrabberCapture);
556
557 if (!ShouldSimulateCamera || !FrameGrabber.IsValid())
558 {
559 return;
560 }
561
563 {
564 return;
565 }
566
567 TArray<FCapturedFrameData> Frames = FrameGrabber->GetCapturedFrames();
568 if (Frames.Num())
569 {
570 FCapturedFrameData& LastFrame = Frames.Last();
571 TArray<FColor>& ImageBuffer = LastFrame.ColorBuffer;
572
573 AddProcessingToFrameBuffer(ImageBuffer);
574
576 {
578 {
581 }
582
583 AsyncTask(ENamedThreads::AnyBackgroundThreadNormalTask, [this, ImageBuffer]()
584 {
586 });
587 }
588
590 }
591}
592
593void ACamera::AddProcessingToFrameBuffer(TArray<FColor>& buffer)
594{
595 return;
596}
597
598void ACamera::ApplyGammaCorrectionLUT(TArray<FColor>& Buffer)
599{
600 static uint8 GammaLUT[256];
601 static bool LUTInitialized = false;
602 if (!LUTInitialized)
603 {
604 LUTInitialized = true;
605 for (int32 i = 0; i < 256; ++i)
606 {
607 float Linear = FMath::Pow(i / 255.0f, 2.2f);
608 GammaLUT[i] = FMath::RoundToInt(Linear * 255.0f);
609 }
610 }
611
612 FColor* RESTRICT BufferPtr = Buffer.GetData();
613 const int32 Num = Buffer.Num();
614
615 const int32 ChunkSize = 512;
616 const int32 NumChunks = (Num + ChunkSize - 1) / ChunkSize;
617
618 ParallelFor(NumChunks, [BufferPtr, Num](int32 ChunkIndex)
619 {
620 const int32 Start = ChunkIndex * ChunkSize;
621 const int32 End = FMath::Min(Start + ChunkSize, Num);
622
623 for (int32 i = Start; i < End; ++i)
624 {
625 FColor& C = BufferPtr[i];
626 C.R = GammaLUT[C.R];
627 C.G = GammaLUT[C.G];
628 C.B = GammaLUT[C.B];
629 }
630 }, false);
631}
632
633void ACamera::HidePrimitiveComponent(UPrimitiveComponent* PrimitiveComponent)
634{
635 if (PrimitiveComponent && CaptureComponent2D)
636 {
637 CaptureComponent2D->HideComponent(PrimitiveComponent);
638 }
639}
640
642{
643 if (!UnrealWindow.IsValid())
644 {
645#if WITH_EDITOR
646 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: UnrealWindow is nullptr!"));
647#endif
648 return;
649 }
650
651 // Destroy old FrameGrabber
653
654 TSharedPtr<FSceneViewport> SceneViewport = UnrealWindow->GetSceneViewport();
655 if (SceneViewport.IsValid() && CaptureRenderTarget)
656 {
657 EPixelFormat PixelFormat = GetPixelFormatFromRenderTargetFormat(TextureFormat);
658 FIntPoint Size = SceneViewport->GetSize();
659
661 {
662 // Currently only DVS camera needs this texture to render DVS output into separate FUnrealWindow.
663 CaptureFrameTexture = UTexture2D::CreateTransient(Size.X, Size.Y, PixelFormat);
664 CaptureFrameTexture->UpdateResource();
665 }
666
667 FrameGrabber = MakeShareable(new FFrameGrabber(SceneViewport.ToSharedRef(), Size, PixelFormat));
668 FrameGrabber->StartCapturingFrames();
669 }
670}
671
673{
674 if (FrameGrabber.IsValid())
675 {
676 FrameGrabber->StopCapturingFrames();
677 FrameGrabber->Shutdown();
678 FrameGrabber.Reset();
679 }
680
682 {
683 CaptureFrameTexture->RemoveFromRoot();
684 CaptureFrameTexture->ConditionalBeginDestroy();
685 CaptureFrameTexture = nullptr;
686 }
687}
688
689void ACamera::SendImageDataToROS(const TArray<FColor>& FrameBuffer, int32 Width, int32 Height)
690{
691 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::SendImageDataToROS);
692
693 UTopic* Topic = GetROSTopic();
694 if (!SendDataToROS
695 || !Topic
696 || !IsROSConnected()
697 || FrameBuffer.IsEmpty()
698 || !ImageMsg.IsValid())
699 {
700 return;
701 }
702
703 // Cast TArray<FColor> into uint8[] data with all channels (RBGA)
704 // If you want to send RGBA data, uncomment the following lines
705 // and comment the BGR8Buffer conversion below
706 //ImageMsg->encoding = "bgra8";
707 //ImageMsg->step = Width * 4;
708 //ImageMsg->data = const_cast<uint8*>(reinterpret_cast<const uint8*>(FrameBuffer.GetData()));
709
710 // Convert TArray<FColor> to uint8[] data without alpha channel
711 // By removing alpha channel, we reduce ~25% of ROS bandwidth,
712 // but costs a bit more in processing time here
713 const int32 BufferSize = Width * Height * 3;
714 if (!BGR8Buffer || CurrentBufferSize != BufferSize)
715 {
716 // Resize buffer if needed
717 delete[] BGR8Buffer;
718 BGR8Buffer = new uint8[BufferSize];
719 CurrentBufferSize = BufferSize;
720 }
721
722 const FColor* RESTRICT Source = FrameBuffer.GetData();
723 uint8* RESTRICT Dest = BGR8Buffer;
724 const int32 PixelCount = FrameBuffer.Num();
725 const int32 ChunkSize = 512;
726 const int32 NumChunks = (PixelCount + ChunkSize - 1) / ChunkSize;
727
728 ParallelFor(NumChunks, [Source, Dest, ChunkSize, PixelCount](int32 ChunkIndex)
729 {
730 const int32 StartIndex = ChunkIndex * ChunkSize;
731 const int32 EndIndex = FMath::Min(StartIndex + ChunkSize, PixelCount);
732
733 for (int32 i = StartIndex; i < EndIndex; ++i)
734 {
735 const FColor& Pixel = Source[i];
736 const int32 j = i * 3;
737 Dest[j + 0] = Pixel.B;
738 Dest[j + 1] = Pixel.G;
739 Dest[j + 2] = Pixel.R;
740 }
741 }, false);
742
743 ImageMsg->data = BGR8Buffer;
744 ImageMsg->step = Width * 3;
745
746 ImageMsg->height = Height;
747 ImageMsg->width = Width;
748 ImageMsg->header.time = FROSTime::Now();
749
750 Topic->Publish(ImageMsg);
751}
752
753void ACamera::SaveImageToDisk(const TArray<FColor> FrameBuffer, int32 Width, int32 Height)
754{
755 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::SaveImageToDisk);
756
757 if (FrameBuffer.IsEmpty() || Width == 0 || Height == 0)
758 {
759 return;
760 }
761
762 int32 Size = Width * Height;
763 if (FrameBuffer.Num() != Size)
764 {
765 const FString Msg = "Camera sensor: Unable to save Image to disk. FrameBuffer size and resolution don't match!";
767 return;
768 }
769
770 const FString ImageName = FString::Printf(TEXT("image_%d.png"), ImageNumber);
771 const FString FullFileName = FString::Printf(TEXT("%s%s"), *FileSavePath, *ImageName);
772 ++ImageNumber;
773
774 SaveCameraMetaDataToDisk(ImageName);
775
776 FIntPoint DestSize(Width, Height);
777 TImagePixelData<FColor> PixelData(DestSize);
778 PixelData.Pixels = FrameBuffer;
779
780 // Create ImageTask
781 TUniquePtr<FImageWriteTask> ImageTask = MakeUnique<FImageWriteTask>();
782 ImageTask->PixelData = MakeUnique<TImagePixelData<FColor>>(PixelData);
783 ImageTask->Filename = FullFileName;
784 ImageTask->Format = EImageFormat::PNG;
785 ImageTask->CompressionQuality = (int32)EImageCompressionQuality::Default;
786 ImageTask->bOverwriteFile = true;
787 ImageTask->PixelPreProcessors.Add(TAsyncAlphaWrite<FColor>(255));
788
789 // Get Screenshot config and enqueue image save task
790 FHighResScreenshotConfig& HighResScreenshotConfig = GetHighResScreenshotConfig();
791 TFuture<bool> CompletionFuture = HighResScreenshotConfig.ImageWriteQueue->Enqueue(MoveTemp(ImageTask));
792}
793
794void ACamera::SaveCameraMetaDataToDisk(const FString& ImageName)
795{
796 if (!IsValid(LogFile))
797 {
798 // If the log file located in base class is not valid, return here.
799 return;
800 }
801
802 const FVector ActorPosition = GetActorLocation();
803 const FRotator ActorRotation = GetActorRotation();
804
805 const FString TimeStamp = CreateTimeStampString();
806 FString MetaData;
807
809 {
810 FGeographicCoordinates GeoCoordinates = UCoordinateConversionUtilities::UnrealToGeographicCoordinates(GeoReferencingSystem, ActorPosition);
811 MetaData = FString::Printf(TEXT("%s, %s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.8f, %.8f, %.8f"),
812 *TimeStamp, *ImageName,
813 ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
814 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll,
815 GeoCoordinates.Latitude, GeoCoordinates.Longitude, GeoCoordinates.Altitude);
816 }
817 else
818 {
819 MetaData = FString::Printf(TEXT("%s, %s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f"),
820 *TimeStamp, *ImageName,
821 ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
822 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll);
823 }
824
825 // Write to the log file (this is written after sensor is destroyed)
826 WriteToLogFile(MetaData);
827}
828
829void ACamera::OnWindowClosed(const TSharedRef<SWindow>& Window)
830{
831#if WITH_EDITOR
832 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Camera window closed. Destroying Camera sensor.."));
833#endif
834
835 // Broadcast event that this Camera sensor is about be destroyed when user has clicked Window Close button.
836 OnCameraWindowClosed.Broadcast(this);
837
838 // Destroy this camera sensor
839 this->Destroy();
840}
841
842void ACamera::AddWidgetToWindow(UWidget* WidgetToAdd)
843{
844 if (UnrealWindow.IsValid() && WidgetToAdd)
845 {
846 UnrealWindow->AddUWidgetToWindow(WidgetToAdd);
847 }
848}
849
850void ACamera::RemoveWidgetFromWindow(UWidget* WidgetToRemove)
851{
852 if (UnrealWindow.IsValid() && WidgetToRemove)
853 {
854 UnrealWindow->RemoveUWidgetFromWindow(WidgetToRemove);
855 }
856}
857
858void ACamera::SetShadowRendering(bool RenderShadows)
859{
861 {
862 auto& CameraShowFlags = CaptureComponent2D->ShowFlags;
863 CameraShowFlags.SetDynamicShadows(RenderShadows);
864 CameraShowFlags.SetContactShadows(RenderShadows);
865 CameraShowFlags.SetCapsuleShadows(RenderShadows);
866 }
867}
868
869void ACamera::SetTemporalAA(bool SetTemporal)
870{
872 {
873 auto& CameraShowFlags = CaptureComponent2D->ShowFlags;
874 CameraShowFlags.SetTemporalAA(SetTemporal);
875 }
876}
877
878void ACamera::ResizeCamera(int32 Width, int32 Height)
879{
880 if (Width == 0 || Height == 0)
881 {
882 return;
883 }
884
885 CameraParameters.Width = Width;
886 CameraParameters.Height = Height;
888}
889
890void ACamera::AddHiddenActor(AActor* Actor)
891{
892 if (Actor && CaptureComponent2D)
893 {
894 CaptureComponent2D->HiddenActors.AddUnique(Actor);
895 }
896}
897
899{
901 {
902 return;
903 }
904
905 auto& ShowFlags = CaptureComponent2D->ShowFlags;
906
907 ShowFlags.SetDeferredLighting(false);
908 ShowFlags.SetSkyLighting(false);
909 ShowFlags.SetAmbientOcclusion(false);
910 ShowFlags.SetAntiAliasing(false);
911 ShowFlags.SetVolumetricFog(false);;
912 ShowFlags.SetBloom(false);
913 ShowFlags.SetCameraImperfections(false);
914 ShowFlags.SetCameraInterpolation(false);
915 ShowFlags.SetColorGrading(false);
916 ShowFlags.SetDepthOfField(false);
917 ShowFlags.SetDiffuse(false);
918 ShowFlags.SetDirectionalLights(false);
919 ShowFlags.SetDirectLighting(false);
920 ShowFlags.SetDynamicShadows(false);
921 ShowFlags.SetEyeAdaptation(false);
922 ShowFlags.SetFog(false);
923 ShowFlags.SetGlobalIllumination(false);
924 ShowFlags.SetGrain(false);
925 ShowFlags.SetHLODColoration(false);
926 ShowFlags.SetHMDDistortion(false);
927 ShowFlags.SetLensFlares(false);
928 ShowFlags.SetLightComplexity(false);
929 ShowFlags.SetLightFunctions(false);
930 ShowFlags.SetLightInfluences(false);
931 ShowFlags.SetLighting(false);
932 ShowFlags.SetLightMapDensity(false);
933 ShowFlags.SetLightRadius(false);
934 ShowFlags.SetLightShafts(false);
935 ShowFlags.SetLODColoration(false);
936 ShowFlags.SetMotionBlur(false);
937 ShowFlags.SetOnScreenDebug(false);
938 ShowFlags.SetParticles(false);
939 ShowFlags.SetPointLights(false);
940 ShowFlags.SetRefraction(false);
941 ShowFlags.SetSceneColorFringe(false);
942 ShowFlags.SetScreenSpaceAO(false);
943 ShowFlags.SetScreenSpaceReflections(false);
944 ShowFlags.SetSkyLighting(false);
945 ShowFlags.SetSpotLights(false);
946 ShowFlags.SetStationaryLightOverlap(false);
947 ShowFlags.SetSubsurfaceScattering(false);
948 ShowFlags.SetTonemapper(false);
949 ShowFlags.SetVisualizeBuffer(false);
950 ShowFlags.SetVisualizeDistanceFieldAO(false);
951 ShowFlags.SetVisualizeDOF(false);
952 ShowFlags.SetVisualizeHDR(false);
953 ShowFlags.SetVisualizeLightCulling(false);
954 ShowFlags.SetVisualizeMeshDistanceFields(false);
955 ShowFlags.SetVisualizeMotionBlur(false);
956 ShowFlags.SetVisualizeOutOfBoundsPixels(false);
957 ShowFlags.SetVisualizeSenses(false);
958 ShowFlags.SetVisualizeShadingModels(false);
959 ShowFlags.SetVisualizeSSR(false);
960 ShowFlags.SetVisualizeSSS(false);
961}
static auto BindTick(ObjectType *Object, FunctionType Function)
Definition: TickManager.h:162
bool UseParallelLateTick
Definition: Camera.h:235
void AddPostProcessingMaterial(const FString &Path, float Weight=1.0f)
Definition: Camera.cpp:59
int32 ImageNumber
Definition: Camera.h:378
FTickEntry TickEntry
Definition: Camera.h:298
TSharedPtr< FFrameGrabber > FrameGrabber
Definition: Camera.h:335
void ChangeCameraParameters(FCameraBaseParameters newParameters)
Definition: Camera.cpp:54
virtual ESensorTypes GetSensorType() const override
Definition: Camera.h:74
FCameraBaseParameters CameraParameters
Definition: Camera.h:351
void ApplyGammaCorrectionLUT(TArray< FColor > &Buffer)
Definition: Camera.cpp:598
FOnWindowClosed OnWindowClosedDelegate
Definition: Camera.h:364
void AddHiddenActor(AActor *Actor)
Definition: Camera.cpp:890
virtual void Init(FCameraBaseParameters parameters, bool SimulateSensor=true)
Definition: Camera.cpp:83
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: Camera.cpp:438
APIDDrone * DronePtr
Definition: Camera.h:305
USceneCaptureComponent2D * CaptureComponent2D
Definition: Camera.h:287
void RemovePostProcessingMaterial(UMaterial *Material)
Definition: Camera.cpp:74
void SaveCameraMetaDataToDisk(const FString &ImageName)
Definition: Camera.cpp:794
AGeoReferencingSystem * GeoReferencingSystem
Definition: Camera.h:360
float FrameRateTimer
Definition: Camera.h:376
void SaveImageToDisk(const TArray< FColor > FrameBuffer, int32 Width, int32 Height)
Definition: Camera.cpp:753
FDelegateHandle OnPostTickDelegate
Definition: Camera.h:240
bool ShouldSimulateCamera
Definition: Camera.h:373
void SetShadowRendering(bool RenderShadows)
Definition: Camera.cpp:858
void OnWindowClosed(const TSharedRef< SWindow > &Window)
Definition: Camera.cpp:829
void StartFrameGrabber()
Definition: Camera.cpp:641
void FrameGrabberCapture()
Definition: Camera.cpp:553
void SendImageDataToROS(const TArray< FColor > &FrameBuffer, int32 Width, int32 Height)
Definition: Camera.cpp:689
FDelegateHandle OnPreTickDelegate
Definition: Camera.h:237
UTextureRenderTarget2D * CaptureRenderTarget
Definition: Camera.h:284
void AddWidgetToWindow(UWidget *WidgetToAdd)
Definition: Camera.cpp:842
TSharedPtr< ROSMessages::sensor_msgs::Image > ImageMsg
Definition: Camera.h:366
int32 CurrentBufferSize
Definition: Camera.h:382
FRotator SensorSetRotation
Definition: Camera.h:306
bool SaveCurrentFrameToDiskRequested
Definition: Camera.h:371
void SetTemporalAA(bool SetTemporal)
Definition: Camera.cpp:869
void CreateLogFile() override
Definition: Camera.cpp:90
UTexture2D * CaptureFrameTexture
Definition: Camera.h:294
void SetupCamera(FCameraBaseParameters parameters)
Definition: Camera.cpp:126
TWeakObjectPtr< UMaterial > PhysicLensDistortion
Definition: Camera.h:302
void RemoveWidgetFromWindow(UWidget *WidgetToRemove)
Definition: Camera.cpp:850
FCameraDelegate_OnWindowResized OnCameraWindowResized
Definition: Camera.h:148
void HidePrimitiveComponent(UPrimitiveComponent *PrimitiveComponent)
Definition: Camera.cpp:633
TEnumAsByte< ETextureRenderTargetFormat > TextureFormat
Definition: Camera.h:134
void ReleaseFrameGrabber()
Definition: Camera.cpp:672
void EndOfFrameParellel(float DeltaTime)
Definition: Camera.cpp:521
virtual void AddProcessingToFrameBuffer(TArray< FColor > &buffer)
Definition: Camera.cpp:593
void ResizeCamera(int32 Width=1280, int32 Height=720)
Definition: Camera.cpp:878
uint8 * BGR8Buffer
Definition: Camera.h:380
TSharedPtr< FUnrealWindow > UnrealWindow
Definition: Camera.h:296
void EndOfFrame(UWorld *World, ELevelTick TickType, float DeltaSeconds)
Definition: Camera.cpp:516
float CameraFrameRate
Definition: Camera.h:375
ACamera(const FObjectInitializer &ObjectInitializer)
Definition: Camera.cpp:33
int32 ImageHeight
Definition: Camera.h:369
void PreActorTick(UWorld *World, ELevelTick TickType, float DeltaSeconds)
Definition: Camera.cpp:486
FCameraDelegate_OnWindowClosed OnCameraWindowClosed
Definition: Camera.h:141
void DisableShowFlags()
Definition: Camera.cpp:898
virtual void BeginPlay() override
Definition: Camera.cpp:391
TWeakObjectPtr< UMaterialInstanceDynamic > IceMaterialInstance
Definition: Camera.h:300
int32 ImageWidth
Definition: Camera.h:368
bool ShouldSimulate(const float DeltaSeconds)
Definition: Camera.cpp:526
bool AllowGimbal
Definition: Camera.h:307
bool CanSimulateSensor() const
Definition: Sensor.h:170
static FPrimitiveAdded OnPrimitiveAdded
Definition: Sensor.h:377
FString GetSensorIdentifier() const
Definition: Sensor.h:75
virtual void CreateDataSavePath()
Definition: Sensor.cpp:254
FString GetSensorName() const
Definition: Sensor.h:96
void SetSimulateSensor(bool SimulateSensor)
Definition: Sensor.h:160
UTopic * GetROSTopic() const
Definition: Sensor.h:150
ULogFile * LogFile
Definition: Sensor.h:367
bool SendDataToROS
Definition: Sensor.h:364
static TArray< TWeakObjectPtr< UPrimitiveComponent > > GetComponentsToHide()
Definition: Sensor.h:270
FString CreateTimeStampString() const
Definition: Sensor.cpp:330
FString FileSavePath
Definition: Sensor.h:372
void WriteToLogFile(const FString &Message)
Definition: Sensor.cpp:302
FORCEINLINE bool IsROSConnected() const
Definition: Sensor.h:201
virtual void CreateROSTopic()
Definition: Sensor.cpp:197
static void RemoveTick(FTickEntry TickEntry)
Definition: TickManager.cpp:80
static FTickEntry AddTick(UObject *Object, std::function< void(float)> Function, ETickType Type)
Definition: TickManager.cpp:51
bool IsVehicleInGarage() const
Definition: Vehicle.h:133
static void Log(const FString &Message, bool LogToTextFile=true, bool LogToROS=true)
static bool ShouldStartWindowMinimized()
virtual void Setup(ACamera *CameraRef, bool ShowOnStartup=true)
static FGeographicCoordinates UnrealToGeographicCoordinates(AGeoReferencingSystem *GeoReferencingSystem, const FVector &Position)
void Create(const FString &FileNameWithoutExtension, FLogFileSettings Settings)
Definition: LogFile.cpp:40
bool KeepFileOpen
Definition: LogFile.h:42
bool Timestamp
Definition: LogFile.h:39
FString FilePath
Definition: LogFile.h:54
FFileWriteOptions FileWriteOptions
Definition: LogFile.h:45
int32 QueueLength
Definition: LogFile.h:48
bool OverrideFilePath
Definition: LogFile.h:51
FFileCreationOptions FileCreationOptions
Definition: LogFile.h:36