Agrarsense
Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
ACamera Class Reference

#include <Camera.h>

Inheritance diagram for ACamera:
Inheritance graph
[legend]
Collaboration diagram for ACamera:
Collaboration graph
[legend]

Public Member Functions

 ACamera (const FObjectInitializer &ObjectInitializer)
 
virtual void Init (FCameraBaseParameters parameters, bool SimulateSensor=true)
 
virtual ESensorTypes GetSensorType () const override
 
void ChangeCameraParameters (FCameraBaseParameters newParameters)
 
FCameraBaseParameters GetCameraParameters ()
 
void AddPostProcessingMaterial (const FString &Path, float Weight=1.0f)
 
void RemovePostProcessingMaterial (UMaterial *Material)
 
USceneCaptureComponent2D * GetCaptureComponent2D () const
 
UTextureRenderTarget2D * GetCaptureRenderTarget2D () const
 
void AddWidgetToWindow (UWidget *WidgetToAdd)
 
void RemoveWidgetFromWindow (UWidget *WidgetToRemove)
 
void SetShadowRendering (bool RenderShadows)
 
void DisableShowFlags ()
 
void SetTemporalAA (bool SetTemporal)
 
void ResizeCamera (int Width=1280, int Height=720)
 
void SaveCurrentFrameToDisk ()
 
int GetCameraWidth () const
 
int GetCameraHeight () const
 
void SetUseGimbal (bool UseGimbal)
 
virtual FString GetParametersAsString () const override
 
- Public Member Functions inherited from ASensor
 ASensor (const FObjectInitializer &ObjectInitializer)
 
FString ExportToJsonFile (const FString &FileName)
 
virtual ESensorTypes GetSensorType () const
 
FString GetSensorIdentifier () const
 
void SetSensorIdentifier (const FString newIdentifier)
 
FString GetSensorName () const
 
virtual FString GetParametersAsString () const
 
AVehicleIsAttachedToVehicle () const
 
void SetSensorName (const FString newName)
 
virtual FString GetTopicName ()
 
UTopic * GetROSTopic () const
 
void SetSimulateSensor (bool SimulateSensor)
 
bool CanSimulateSensor () const
 
ASensorModelGetSensorModel () const
 
void SetSensorModel (ASensorModel *NewSensorModel)
 
FORCEINLINE bool IsROSConnected () const
 
UROSIntegrationGameInstance * GetROSGameInstance () const
 
virtual FString GetActorID_Implementation () const override
 
virtual FString GetActorName_Implementation () const override
 
virtual FString GetActorInformation_Implementation () const override
 
virtual void SetActorName_Implementation (const FString &NewActorName) override
 
virtual void SetActorIDAndName_Implementation (const FString &NewActorName, const FString &NewID) override
 
void SetParentActorPtr (AActor *ParentActorPtr)
 
- Public Member Functions inherited from IActorInformation
FString GetActorID () const
 
FString GetActorName () const
 
FString GetActorInformation () const
 
void SetActorName (const FString &NewActorName)
 
void SetActorIDAndName (const FString &NewActorName, const FString &NewID)
 

Public Attributes

TEnumAsByte< ETextureRenderTargetFormat > TextureFormat = ETextureRenderTargetFormat::RTF_RGBA8
 
FCameraDelegate_OnWindowClosed OnCameraWindowClosed
 
FCameraDelegate_OnWindowResized OnCameraWindowResized
 
- Public Attributes inherited from ASensor
FSensorDestroy OnSensorDestroy
 
FString AttachedToComponent
 
FName AttachedToBone
 

Protected Member Functions

virtual void BeginPlay () override
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
virtual void PreActorTick (UWorld *World, ELevelTick TickType, float DeltaSeconds)
 
virtual void EndOfFrame (UWorld *World, ELevelTick TickType, float DeltaSeconds)
 
virtual void EndOfFrameParellel (float DeltaTime)
 
virtual void AddProcessingToFrameBuffer (TArray< FColor > &buffer)
 
virtual void SendImageDataToROS (const TArray< FColor > &FrameBuffer, int32 Width, int32 Height)
 
void HidePrimitiveComponent (UPrimitiveComponent *PrimitiveComponent)
 
void SaveImageToDisk (const TArray< FColor > FrameBuffer, int32 Width, int32 Height)
 
void SaveCameraMetaDataToDisk (const FString &ImageName)
 
void CreateLogFile () override
 
- Protected Member Functions inherited from ASensor
virtual void BeginPlay () override
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
FString CreateTimeStampString () const
 
virtual void CreateROSTopic ()
 
virtual void DestroyROSTopic ()
 
virtual void CreateDataSavePath ()
 
bool IsLogFileCreated ()
 
virtual void CreateLogFile ()
 
void WriteToLogFile (const FString &Message)
 

Protected Attributes

bool UseParallelLateTick = true
 
FDelegateHandle OnPreTickDelegate
 
FDelegateHandle OnPostTickDelegate
 
FString CameraName = "Camera "
 
FString FilePrefix = "Data/Camera_"
 
UTextureRenderTarget2D * CaptureRenderTarget = nullptr
 
USceneCaptureComponent2D * CaptureComponent2D = nullptr
 
UTexture2D * CaptureFrameTexture
 
TSharedPtr< FUnrealWindowUnrealWindow
 
FTickEntry TickEntry
 
TWeakObjectPtr< UMaterialInstanceDynamic > IceMaterialInstance
 
TWeakObjectPtr< UMaterial > PhysicLensDistortion
 
APIDDroneDronePtr = nullptr
 
FRotator SensorSetRotation
 
bool AllowGimbal = true
 
- Protected Attributes inherited from ASensor
UTopic * ROSTopic = nullptr
 
bool SendDataToROS = true
 
ULogFileLogFile = nullptr
 
AActor * ParentActor = nullptr
 
FString FileSavePath
 
UROSIntegrationGameInstance * ROSInstance = nullptr
 

Private Member Functions

void StartFrameGrabber ()
 
void ReleaseFrameGrabber ()
 
void FrameGrabberCapture ()
 
void OnWindowClosed (const TSharedRef< SWindow > &Window)
 
void SetupCamera (FCameraBaseParameters parameters)
 
bool ShouldSimulate (const float DeltaSeconds)
 

Private Attributes

TSharedPtr< FFrameGrabber > FrameGrabber
 
FCameraBaseParameters CameraParameters
 
FCameraBaseParameters TempParams
 
AGeoReferencingSystem * GeoReferencingSystem = nullptr
 
bool ParametersChanged = false
 
FOnWindowClosed OnWindowClosedDelegate
 
TSharedPtr< ROSMessages::sensor_msgs::Image > ImageMsg
 
int32 ImageWidth = 1280
 
int32 ImageHeight = 720
 
bool SaveCurrentFrameToDiskRequested = false
 
bool ShouldSimulateCamera = true
 
float CameraFrameRate = 0.0f
 
float FrameRateTimer = 0.0f
 
int32 ImageNumber = 0
 
uint8 * BGR8Buffer = nullptr
 
int32 CurrentBufferSize = 0
 

Additional Inherited Members

- Static Public Member Functions inherited from ASensor
static void HideComponentForAllCameras (UPrimitiveComponent *PrimitiveComponent)
 
static TMap< FString, FColor > GetSemanticColors ()
 
static TArray< TWeakObjectPtr< UPrimitiveComponent > > GetComponentsToHide ()
 
- Static Public Member Functions inherited from IActorInformation
static void SetAndValidateActorIDAndName (FString &ActorName, FString &ActorID, TWeakObjectPtr< AActor > Actor)
 
static bool DestroyActorByID (const FString &ID)
 
static AActor * GetActorByID (const FString &ID)
 
template<typename T >
static TArray< T * > GetActorsWithInterface ()
 
static void PrintAllIds ()
 
- Static Protected Member Functions inherited from ASensor
template<typename InStructType >
static FString StructToString (const InStructType &InStruct)
 
- Static Protected Attributes inherited from ASensor
static FPrimitiveAdded OnPrimitiveAdded
 
static const FName NiagaraPointsInt = "User.PointCount"
 
static const FName NiagaraHitPoints = "User.HitPoints"
 
static const FName NiagaraHitColors = "User.HitColors"
 
static const FName NiagaraPointsFloat = "User.Test"
 

Detailed Description

Camera sensor base class. All other Camera sensors are inherited from this class.

This creates custom Unreal Engine Window and renders USceneCaptureComponent2D into it. Then the Window screen pixels are read by FrameGrabber API which depending on the Camera type, might add processing on the read pixels. The pixels are then saved to disk if SaveDataToDisk is set to true and data is sent to ROS.

Definition at line 52 of file Camera.h.

Constructor & Destructor Documentation

◆ ACamera()

ACamera::ACamera ( const FObjectInitializer &  ObjectInitializer)

Setup new ACamera class

Parameters
FObjectInitializerdefault ObjectInitializer

Definition at line 34 of file Camera.cpp.

34 : Super(ObjectInitializer)
35{
36 PrimaryActorTick.bCanEverTick = true;
37 PrimaryActorTick.TickGroup = TG_PostUpdateWork;
38
39 CaptureRenderTarget = CreateDefaultSubobject<UTextureRenderTarget2D>(FName(*FString::Printf(TEXT("CaptureRenderTarget"))));
40 CaptureRenderTarget->CompressionSettings = TextureCompressionSettings::TC_Default;
41 CaptureRenderTarget->SRGB = false;
42 CaptureRenderTarget->bAutoGenerateMips = false;
43 CaptureRenderTarget->bGPUSharedFlag = true;
44 CaptureRenderTarget->AddressX = TextureAddress::TA_Clamp;
45 CaptureRenderTarget->AddressY = TextureAddress::TA_Clamp;
46
47 CaptureComponent2D = CreateDefaultSubobject<USceneCaptureComponent2D>(FName(*FString::Printf(TEXT("SceneCaptureComponent2D"))));
48 CaptureComponent2D->SetupAttachment(RootComponent);
49 CaptureComponent2D->PrimitiveRenderMode = ESceneCapturePrimitiveRenderMode::PRM_RenderScenePrimitives;
50 CaptureComponent2D->bCaptureOnMovement = false;
51 CaptureComponent2D->bCaptureEveryFrame = false;
52 CaptureComponent2D->bAlwaysPersistRenderingState = true;
53}
USceneCaptureComponent2D * CaptureComponent2D
Definition: Camera.h:282
UTextureRenderTarget2D * CaptureRenderTarget
Definition: Camera.h:279

References CaptureComponent2D, and CaptureRenderTarget.

Member Function Documentation

◆ AddPostProcessingMaterial()

void ACamera::AddPostProcessingMaterial ( const FString &  Path,
float  Weight = 1.0f 
)

Adds a post-processing material from the specified file path.

Parameters
PathThe file path to the post-processing material.
WeightThe weight or influence of the material. Default is 1.0f.

Definition at line 60 of file Camera.cpp.

61{
62 UMaterial* PostProcessingMat = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
63 if (PostProcessingMat && CaptureComponent2D)
64 {
65 FPostProcessSettings& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
66 PostProcessSettings.AddBlendable(PostProcessingMat, Weight);
67 }
68 else
69 {
70 FString Sensor = GetSensorName();
71 FString Msg = "Failed to add Post processing material to " + Sensor;
73 }
74}
FString GetSensorName() const
Definition: Sensor.h:96
static void Log(const FString &Message, bool LogToTextFile=true, bool LogToROS=true)

References CaptureComponent2D, ASensor::GetSensorName(), and SimulatorLog::Log().

Referenced by ASemanticSegmentationCamera::Init(), and ADepthCamera::SetupDepthMaterial().

◆ AddProcessingToFrameBuffer()

void ACamera::AddProcessingToFrameBuffer ( TArray< FColor > &  buffer)
protectedvirtual

Reimplemented in ADepthCamera, and ADVSCamera.

Definition at line 586 of file Camera.cpp.

587{
588 // Only DVSCamera adds processing to the frame buffer
589 return;
590}

Referenced by FrameGrabberCapture().

◆ AddWidgetToWindow()

void ACamera::AddWidgetToWindow ( UWidget *  WidgetToAdd)

Add Widget to custom Unreal Window

Definition at line 794 of file Camera.cpp.

795{
796 if (UnrealWindow.IsValid() && WidgetToAdd)
797 {
798 UnrealWindow->AddUWidgetToWindow(WidgetToAdd);
799 }
800}
TSharedPtr< FUnrealWindow > UnrealWindow
Definition: Camera.h:291

References UnrealWindow.

Referenced by SetupCamera().

◆ BeginPlay()

void ACamera::BeginPlay ( )
overrideprotectedvirtual

Reimplemented from ASensor.

Definition at line 384 of file Camera.cpp.

385{
386 Super::BeginPlay();
387
388 // Register to PreActorTick where USceneCaptureComponent2D will get rendered.
389 OnPreTickDelegate = FWorldDelegates::OnWorldPreActorTick.AddUObject(this, &ACamera::PreActorTick);
390
391 // Check if we should use ATickManager which ticks in parallel, or use Post actor tick
392 // In there we capture the screen pixels with FrameGrabber API,
393 // might do some extra processing, save image to disk and send data to ROS.
395 {
396 SetActorTickEnabled(false);
397 TickEntry = ATickManager::AddTick(this, BindTick(this, &ACamera::EndOfFrameParellel), ETickType::LateTickParallel);
398 }
399 else
400 {
401 SetActorTickEnabled(true);
402 OnPostTickDelegate = FWorldDelegates::OnWorldPostActorTick.AddUObject(this, &ACamera::EndOfFrame);
403 }
404
405 // Get all existing components set to be hidden for all Camera sensors (like Lidar point cloud visualization).
406 auto Components = ASensor::GetComponentsToHide();
407 for (int32 i = 0; i < Components.Num(); i++)
408 {
409 UPrimitiveComponent* Primitive = Components[i].Get();
410 if (Primitive)
411 {
412 HidePrimitiveComponent(Primitive);
413 }
414 }
415
416 OnPrimitiveAdded.AddUniqueDynamic(this, &ACamera::HidePrimitiveComponent);
417
418 GetWorld()->GetTimerManager().SetTimerForNextTick([this]()
419 {
420 if (IsValid(this))
421 {
422 DronePtr = Cast<APIDDrone>(GetAttachParentActor());
423 if (!DronePtr)
424 {
425 AllowGimbal = false;
426 }
427 }
428 });
429}
static auto BindTick(ObjectType *Object, FunctionType Function)
Definition: TickManager.h:162
bool UseParallelLateTick
Definition: Camera.h:232
FTickEntry TickEntry
Definition: Camera.h:293
APIDDrone * DronePtr
Definition: Camera.h:300
FDelegateHandle OnPostTickDelegate
Definition: Camera.h:237
FDelegateHandle OnPreTickDelegate
Definition: Camera.h:234
void HidePrimitiveComponent(UPrimitiveComponent *PrimitiveComponent)
Definition: Camera.cpp:592
virtual void EndOfFrameParellel(float DeltaTime)
Definition: Camera.cpp:514
virtual void EndOfFrame(UWorld *World, ELevelTick TickType, float DeltaSeconds)
Definition: Camera.cpp:509
virtual void PreActorTick(UWorld *World, ELevelTick TickType, float DeltaSeconds)
Definition: Camera.cpp:479
bool AllowGimbal
Definition: Camera.h:302
static FPrimitiveAdded OnPrimitiveAdded
Definition: Sensor.h:377
static TArray< TWeakObjectPtr< UPrimitiveComponent > > GetComponentsToHide()
Definition: Sensor.h:270
static FTickEntry AddTick(UObject *Object, std::function< void(float)> Function, ETickType Type)
Definition: TickManager.cpp:51

References ATickManager::AddTick(), AllowGimbal, BindTick(), DronePtr, EndOfFrame(), EndOfFrameParellel(), ASensor::GetComponentsToHide(), HidePrimitiveComponent(), OnPostTickDelegate, OnPreTickDelegate, ASensor::OnPrimitiveAdded, PreActorTick(), TickEntry, and UseParallelLateTick.

◆ ChangeCameraParameters()

void ACamera::ChangeCameraParameters ( FCameraBaseParameters  newParameters)

Change Camera parameters on the fly. Callable from blueprint.

Parameters
FCameraBaseParametersCameraParameters struct

Definition at line 55 of file Camera.cpp.

56{
57 SetupCamera(newParameters);
58}
void SetupCamera(FCameraBaseParameters parameters)
Definition: Camera.cpp:128

References SetupCamera().

Referenced by ADepthCamera::ChangeDepthCameraParameters(), ADVSCamera::ChangeParametersInternal(), AThermalCamera::ChangeThermalCameraParameters(), ResizeCamera(), and ADataCapture::SetupDataCapture().

◆ CreateLogFile()

void ACamera::CreateLogFile ( )
overrideprotectedvirtual

Create Text file for this sensor if it has not been created already. Text file will be created to ROOT/Data/Run/Logs directory. Filename will be SensorName_ID_UnixTimestamp.txt Can be overriden by individual sensor if needed.

Reimplemented from ASensor.

Definition at line 92 of file Camera.cpp.

93{
94 if (IsValid(LogFile))
95 {
96 // File has already been created, return
97 return;
98 }
99
100 FLogFileSettings Settings;
103 Settings.QueueLength = MAX_int32; // Only write the log after destroying the sensor
104 Settings.KeepFileOpen = false;
105 Settings.Timestamp = false;
106 Settings.OverrideFilePath = true;
107 Settings.FilePath = FileSavePath;
108
109 LogFile = NewObject<ULogFile>(ULogFile::StaticClass());
110 if (IsValid(LogFile))
111 {
112 FString FileName = "camera_metadata";
113 LogFile->Create(FileName, Settings);
114
115 // Write camera metadata first line to explain the values.
116 GeoReferencingSystem = AGeoReferencingSystem::GetGeoReferencingSystem(GetWorld());
118 {
119 WriteToLogFile("timestamp, image_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation, GPS latitude, GPS longitude, GPS altitude");
120 }
121 else
122 {
123 WriteToLogFile("timestamp, image_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation");
124 }
125 }
126}
AGeoReferencingSystem * GeoReferencingSystem
Definition: Camera.h:355
ULogFile * LogFile
Definition: Sensor.h:367
FString FileSavePath
Definition: Sensor.h:372
void WriteToLogFile(const FString &Message)
Definition: Sensor.cpp:294
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

References ULogFile::Create(), FLogFileSettings::FileCreationOptions, FLogFileSettings::FilePath, ASensor::FileSavePath, FLogFileSettings::FileWriteOptions, GeoReferencingSystem, FLogFileSettings::KeepFileOpen, ASensor::LogFile, FLogFileSettings::OverrideFilePath, Overwrite, Queue, FLogFileSettings::QueueLength, FLogFileSettings::Timestamp, and ASensor::WriteToLogFile().

Referenced by FrameGrabberCapture(), and SetupCamera().

◆ DisableShowFlags()

void ACamera::DisableShowFlags ( )

Definition at line 842 of file Camera.cpp.

843{
845 {
846 return;
847 }
848
849 auto& ShowFlags = CaptureComponent2D->ShowFlags;
850
851 ShowFlags.SetAntiAliasing(false);
852 ShowFlags.SetVolumetricFog(false);;
853 ShowFlags.SetBloom(false);
854 ShowFlags.SetCameraImperfections(false);
855 ShowFlags.SetCameraInterpolation(false);
856 ShowFlags.SetColorGrading(false);
857 ShowFlags.SetDepthOfField(false);
858 ShowFlags.SetDiffuse(false);
859 ShowFlags.SetDirectionalLights(false);
860 ShowFlags.SetDirectLighting(false);
861 ShowFlags.SetDynamicShadows(false);
862 ShowFlags.SetEyeAdaptation(false);
863 ShowFlags.SetFog(false);
864 ShowFlags.SetGlobalIllumination(false);
865 ShowFlags.SetGrain(false);
866 ShowFlags.SetHLODColoration(false);
867 ShowFlags.SetHMDDistortion(false);
868 ShowFlags.SetLensFlares(false);
869 ShowFlags.SetLightComplexity(false);
870 ShowFlags.SetLightFunctions(false);
871 ShowFlags.SetLightInfluences(false);
872 ShowFlags.SetLighting(false);
873 ShowFlags.SetLightMapDensity(false);
874 ShowFlags.SetLightRadius(false);
875 ShowFlags.SetLightShafts(false);
876 ShowFlags.SetLODColoration(false);
877 ShowFlags.SetMotionBlur(false);
878 ShowFlags.SetOnScreenDebug(false);
879 ShowFlags.SetParticles(false);
880 ShowFlags.SetPointLights(false);
881 ShowFlags.SetRefraction(false);
882 ShowFlags.SetSceneColorFringe(false);
883 ShowFlags.SetScreenSpaceAO(false);
884 ShowFlags.SetScreenSpaceReflections(false);
885 ShowFlags.SetSkyLighting(false);
886 ShowFlags.SetSpotLights(false);
887 ShowFlags.SetStationaryLightOverlap(false);
888 ShowFlags.SetSubsurfaceScattering(false);
889 ShowFlags.SetTonemapper(false);
890 ShowFlags.SetVisualizeBuffer(false);
891 ShowFlags.SetVisualizeDistanceFieldAO(false);
892 ShowFlags.SetVisualizeDOF(false);
893 ShowFlags.SetVisualizeHDR(false);
894 ShowFlags.SetVisualizeLightCulling(false);
895 ShowFlags.SetVisualizeMeshDistanceFields(false);
896 ShowFlags.SetVisualizeMotionBlur(false);
897 ShowFlags.SetVisualizeOutOfBoundsPixels(false);
898 ShowFlags.SetVisualizeSenses(false);
899 ShowFlags.SetVisualizeShadingModels(false);
900 ShowFlags.SetVisualizeSSR(false);
901 ShowFlags.SetVisualizeSSS(false);
902}

References CaptureComponent2D.

Referenced by ADepthCamera::Init(), and ASemanticSegmentationCamera::Init().

◆ EndOfFrame()

void ACamera::EndOfFrame ( UWorld *  World,
ELevelTick  TickType,
float  DeltaSeconds 
)
protectedvirtual

Definition at line 509 of file Camera.cpp.

510{
512}
void FrameGrabberCapture()
Definition: Camera.cpp:546

References FrameGrabberCapture().

Referenced by BeginPlay().

◆ EndOfFrameParellel()

void ACamera::EndOfFrameParellel ( float  DeltaTime)
protectedvirtual

Definition at line 514 of file Camera.cpp.

515{
517}

References FrameGrabberCapture().

Referenced by BeginPlay().

◆ EndPlay()

void ACamera::EndPlay ( const EEndPlayReason::Type  EndPlayReason)
overrideprotectedvirtual

Reimplemented from ASensor.

Reimplemented in ADepthCamera, ADVSCamera, and AThermalCamera.

Definition at line 431 of file Camera.cpp.

432{
433 Super::EndPlay(EndPlayReason);
434
435 FWorldDelegates::OnWorldPreActorTick.Remove(OnPreTickDelegate);
436
438 {
440 }
441 else
442 {
443 FWorldDelegates::OnWorldPostActorTick.Remove(OnPostTickDelegate);
444 }
445
446 if (UnrealWindow.IsValid())
447 {
448 OnWindowClosedDelegate.Unbind();
449 UnrealWindow->DestroyWindow();
450 UnrealWindow.Reset();
451 }
452
454
456 {
457 CaptureRenderTarget->ConditionalBeginDestroy();
458 CaptureRenderTarget = nullptr;
459 }
460
462 {
463 CaptureComponent2D->UnregisterComponent();
464 CaptureComponent2D->ConditionalBeginDestroy();
465 CaptureComponent2D = nullptr;
466 }
467
468 ImageMsg.Reset();
469 IceMaterialInstance.Reset();
470
471 if (BGR8Buffer)
472 {
473 delete[] BGR8Buffer;
474 BGR8Buffer = nullptr;
475 }
477}
FOnWindowClosed OnWindowClosedDelegate
Definition: Camera.h:359
TSharedPtr< ROSMessages::sensor_msgs::Image > ImageMsg
Definition: Camera.h:361
int32 CurrentBufferSize
Definition: Camera.h:377
void ReleaseFrameGrabber()
Definition: Camera.cpp:631
uint8 * BGR8Buffer
Definition: Camera.h:375
TWeakObjectPtr< UMaterialInstanceDynamic > IceMaterialInstance
Definition: Camera.h:295
static void RemoveTick(FTickEntry TickEntry)
Definition: TickManager.cpp:80

References BGR8Buffer, CaptureComponent2D, CaptureRenderTarget, CurrentBufferSize, IceMaterialInstance, ImageMsg, OnPostTickDelegate, OnPreTickDelegate, OnWindowClosedDelegate, ReleaseFrameGrabber(), ATickManager::RemoveTick(), TickEntry, UnrealWindow, and UseParallelLateTick.

◆ FrameGrabberCapture()

void ACamera::FrameGrabberCapture ( )
private

Capture screen pixels with FrameGrabber

Definition at line 546 of file Camera.cpp.

547{
548 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::FrameGrabberCapture);
549
550 if (!ShouldSimulateCamera || !FrameGrabber.IsValid())
551 {
552 return;
553 }
554
556 {
557 return;
558 }
559
560 TArray<FCapturedFrameData> Frames = FrameGrabber->GetCapturedFrames();
561 if (Frames.Num())
562 {
563 FCapturedFrameData& LastFrame = Frames.Last();
564 TArray<FColor>& ImageBuffer = LastFrame.ColorBuffer;
565
566 AddProcessingToFrameBuffer(ImageBuffer);
567
569 {
571 {
574 }
575
576 AsyncTask(ENamedThreads::AnyBackgroundThreadNormalTask, [this, ImageBuffer]()
577 {
579 });
580 }
581
583 }
584}
TSharedPtr< FFrameGrabber > FrameGrabber
Definition: Camera.h:330
FCameraBaseParameters CameraParameters
Definition: Camera.h:346
void SaveImageToDisk(const TArray< FColor > FrameBuffer, int32 Width, int32 Height)
Definition: Camera.cpp:704
bool ShouldSimulateCamera
Definition: Camera.h:368
virtual void SendImageDataToROS(const TArray< FColor > &FrameBuffer, int32 Width, int32 Height)
Definition: Camera.cpp:648
bool SaveCurrentFrameToDiskRequested
Definition: Camera.h:366
void CreateLogFile() override
Definition: Camera.cpp:92
virtual void AddProcessingToFrameBuffer(TArray< FColor > &buffer)
Definition: Camera.cpp:586
int32 ImageHeight
Definition: Camera.h:364
int32 ImageWidth
Definition: Camera.h:363
bool SendDataToROS
Definition: Sensor.h:364

References AddProcessingToFrameBuffer(), CameraParameters, CreateLogFile(), FrameGrabber, FrameGrabberCapture(), ImageHeight, ImageWidth, SaveCurrentFrameToDiskRequested, SaveImageToDisk(), FCameraBaseParameters::SaveImageToDisk, ASensor::SendDataToROS, SendImageDataToROS(), and ShouldSimulateCamera.

Referenced by EndOfFrame(), EndOfFrameParellel(), and FrameGrabberCapture().

◆ GetCameraHeight()

int ACamera::GetCameraHeight ( ) const
inline

Definition at line 204 of file Camera.h.

205 {
206 return ImageHeight;
207 }

Referenced by ADVSCamera::ChangeParametersInternal(), ADVSCamera::Init(), and ADVSCamera::SimulateDVS().

◆ GetCameraParameters()

FCameraBaseParameters ACamera::GetCameraParameters ( )
inline

Get current Camera parameters

Returns
FCameraBaseParameters struct

Definition at line 91 of file Camera.h.

92 {
93 return CameraParameters;
94 }

Referenced by USimulatorJsonExporter::ExportSensorToJSON(), and ADataCapture::SetupDataCapture().

◆ GetCameraWidth()

int ACamera::GetCameraWidth ( ) const
inline

Definition at line 198 of file Camera.h.

199 {
200 return ImageWidth;
201 }

Referenced by ADVSCamera::ChangeParametersInternal(), ADVSCamera::Init(), and ADVSCamera::SimulateDVS().

◆ GetCaptureComponent2D()

USceneCaptureComponent2D * ACamera::GetCaptureComponent2D ( ) const
inline

Get CaptureComponent USceneCaptureComponent2D pointer.

Returns
USceneCaptureComponent2D pointer

Definition at line 114 of file Camera.h.

115 {
116 return CaptureComponent2D;
117 }

Referenced by ADepthCamera::SetupDepthMaterial(), and AThermalCamera::SetupMaterial().

◆ GetCaptureRenderTarget2D()

UTextureRenderTarget2D * ACamera::GetCaptureRenderTarget2D ( ) const
inline

Get UTextureRenderTarget2D pointer.

Returns
UTextureRenderTarget2D pointer

Definition at line 124 of file Camera.h.

125 {
126 return CaptureRenderTarget;
127 }

◆ GetParametersAsString()

virtual FString ACamera::GetParametersAsString ( ) const
inlineoverridevirtual

Get current LidarParameters struct fields as one string.

Reimplemented from ASensor.

Reimplemented in ADepthCamera, ADVSCamera, and AThermalCamera.

Definition at line 218 of file Camera.h.

219 {
221 }
static FString StructToString(const InStructType &InStruct)
Definition: Sensor.h:325

◆ GetSensorType()

virtual ESensorTypes ACamera::GetSensorType ( ) const
inlineoverridevirtual

Get type of the sensor

Returns
Sensor's type

Reimplemented from ASensor.

Reimplemented in ADepthCamera, ADVSCamera, ASemanticSegmentationCamera, and AThermalCamera.

Definition at line 74 of file Camera.h.

75 {
77 }

References RGBCamera.

Referenced by SetupCamera(), and StartFrameGrabber().

◆ HidePrimitiveComponent()

void ACamera::HidePrimitiveComponent ( UPrimitiveComponent *  PrimitiveComponent)
protected

Definition at line 592 of file Camera.cpp.

593{
594 if (PrimitiveComponent && CaptureComponent2D)
595 {
596 CaptureComponent2D->HideComponent(PrimitiveComponent);
597 }
598}

References CaptureComponent2D.

Referenced by BeginPlay().

◆ Init()

void ACamera::Init ( FCameraBaseParameters  parameters,
bool  SimulateSensor = true 
)
virtual

Initialize new Camera sensor

Parameters
FCameraBaseParametersCameraParameters struct

Reimplemented in ADepthCamera, ADVSCamera, ASemanticSegmentationCamera, and AThermalCamera.

Definition at line 85 of file Camera.cpp.

86{
88 SetSimulateSensor(SimulateSensor);
89 SetupCamera(parameters);
90}
virtual void CreateDataSavePath()
Definition: Sensor.cpp:246
void SetSimulateSensor(bool SimulateSensor)
Definition: Sensor.h:160

References ASensor::CreateDataSavePath(), ASensor::SetSimulateSensor(), and SetupCamera().

◆ OnWindowClosed()

void ACamera::OnWindowClosed ( const TSharedRef< SWindow > &  Window)
private

On camera window closed event

Parameters
Windowreference to SWindow pointer

Definition at line 781 of file Camera.cpp.

782{
783#if WITH_EDITOR
784 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Camera window closed. Destroying Camera sensor.."));
785#endif
786
787 // Broadcast event that this Camera sensor is about be destroyed when user has clicked Window Close button.
788 OnCameraWindowClosed.Broadcast(this);
789
790 // Destroy this camera sensor
791 this->Destroy();
792}
FCameraDelegate_OnWindowClosed OnCameraWindowClosed
Definition: Camera.h:141

References Destroy, and OnCameraWindowClosed.

Referenced by SetupCamera().

◆ PreActorTick()

void ACamera::PreActorTick ( UWorld *  World,
ELevelTick  TickType,
float  DeltaSeconds 
)
protectedvirtual

Definition at line 479 of file Camera.cpp.

480{
481 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::PreActorTick);
482
483 // If this Camera sensor is attached to Drone, keep the camera steady kind of like a Gimbal.
485 {
486 if (SensorSetRotation == FRotator::ZeroRotator)
487 {
488 // Save garage sensor values
489 SensorSetRotation = GetTransform().Rotator();
490 }
491 FRotator gimbalRot = FRotator(SensorSetRotation.Pitch, GetActorRotation().Yaw, SensorSetRotation.Roll);
492 SetActorRotation(gimbalRot);
493 }
494
495 if (ShouldSimulate(DeltaSeconds) && CaptureComponent2D)
496 {
497 // Capture scene now.
498 // We could use CaptureSceneDeferred but it would not work if World (Spectator) Rendering is disabled.
499 CaptureComponent2D->CaptureScene();
500
501 // Inform FrameGrabber to capture this frame
502 if (FrameGrabber.IsValid())
503 {
504 FrameGrabber->CaptureThisFrame(FFramePayloadPtr());
505 }
506 }
507}
FRotator SensorSetRotation
Definition: Camera.h:301
bool ShouldSimulate(const float DeltaSeconds)
Definition: Camera.cpp:519
bool IsVehicleInGarage() const
Definition: Vehicle.h:124

References AllowGimbal, CaptureComponent2D, DronePtr, FrameGrabber, AVehicle::IsVehicleInGarage(), PreActorTick(), SensorSetRotation, and ShouldSimulate().

Referenced by BeginPlay(), and PreActorTick().

◆ ReleaseFrameGrabber()

void ACamera::ReleaseFrameGrabber ( )
private

Release FrameGrabber and destroy UTexture2D

Definition at line 631 of file Camera.cpp.

632{
633 if (FrameGrabber.IsValid())
634 {
635 FrameGrabber->StopCapturingFrames();
636 FrameGrabber->Shutdown();
637 FrameGrabber.Reset();
638 }
639
641 {
642 CaptureFrameTexture->RemoveFromRoot();
643 CaptureFrameTexture->ConditionalBeginDestroy();
644 CaptureFrameTexture = nullptr;
645 }
646}
UTexture2D * CaptureFrameTexture
Definition: Camera.h:289

References CaptureFrameTexture, and FrameGrabber.

Referenced by EndPlay(), and StartFrameGrabber().

◆ RemovePostProcessingMaterial()

void ACamera::RemovePostProcessingMaterial ( UMaterial *  Material)

Removes a specified post-processing material.

Parameters
MaterialA pointer to the material to be removed.

Definition at line 76 of file Camera.cpp.

77{
79 {
80 FPostProcessSettings& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
81 PostProcessSettings.RemoveBlendable(Material);
82 }
83}

References CaptureComponent2D.

Referenced by ADepthCamera::SetupDepthMaterial().

◆ RemoveWidgetFromWindow()

void ACamera::RemoveWidgetFromWindow ( UWidget *  WidgetToRemove)

Remove Widget from custom Unreal Window

Definition at line 802 of file Camera.cpp.

803{
804 if (UnrealWindow.IsValid() && WidgetToRemove)
805 {
806 UnrealWindow->RemoveUWidgetFromWindow(WidgetToRemove);
807 }
808}

References UnrealWindow.

◆ ResizeCamera()

void ACamera::ResizeCamera ( int  Width = 1280,
int  Height = 720 
)

Resize camera and custom Unreal Window certain size

Definition at line 830 of file Camera.cpp.

831{
832 if (Width == 0 || Height == 0)
833 {
834 return;
835 }
836
837 CameraParameters.Width = Width;
838 CameraParameters.Height = Height;
840}
void ChangeCameraParameters(FCameraBaseParameters newParameters)
Definition: Camera.cpp:55

References CameraParameters, ChangeCameraParameters(), FCameraBaseParameters::Height, and FCameraBaseParameters::Width.

◆ SaveCameraMetaDataToDisk()

void ACamera::SaveCameraMetaDataToDisk ( const FString &  ImageName)
protected

Definition at line 745 of file Camera.cpp.

746{
747 if (!IsValid(LogFile))
748 {
749 // If the log file located in base class is not valid, return here.
750 return;
751 }
752
753 const FVector ActorPosition = GetActorLocation();
754 const FRotator ActorRotation = GetActorRotation();
755
756 FString MetaData;
757
758 FString TimeStamp = CreateTimeStampString();
759
761 {
762 FGeographicCoordinates GeoCoordinates = UCoordinateConversionUtilities::UnrealToGeographicCoordinates(GeoReferencingSystem, ActorPosition);
763 MetaData = FString::Printf(TEXT("%s, %s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.8f, %.8f, %.8f"),
764 *TimeStamp, *ImageName,
765 ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
766 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll,
767 GeoCoordinates.Latitude, GeoCoordinates.Longitude, GeoCoordinates.Altitude);
768 }
769 else
770 {
771 MetaData = FString::Printf(TEXT("%s, %s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f"),
772 *TimeStamp, *ImageName,
773 ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
774 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll);
775 }
776
777 // Write to the log file (this is written after sensor is destroyed)
778 WriteToLogFile(MetaData);
779}
FString CreateTimeStampString() const
Definition: Sensor.cpp:322
static FGeographicCoordinates UnrealToGeographicCoordinates(AGeoReferencingSystem *GeoReferencingSystem, const FVector &Position)

References ASensor::CreateTimeStampString(), GeoReferencingSystem, ASensor::LogFile, UCoordinateConversionUtilities::UnrealToGeographicCoordinates(), and ASensor::WriteToLogFile().

Referenced by SaveImageToDisk().

◆ SaveCurrentFrameToDisk()

void ACamera::SaveCurrentFrameToDisk ( )
inline

Saves this frame to disk even if CameraParameters.SaveImageToDisk is set to false.

Definition at line 189 of file Camera.h.

190 {
192 {
194 }
195 }

Referenced by ADataCapture::CaptureDataNow().

◆ SaveImageToDisk()

void ACamera::SaveImageToDisk ( const TArray< FColor >  FrameBuffer,
int32  Width,
int32  Height 
)
protected

Save Image data as png to disk

Parameters
FrameBufferImage buffer
widthImage width
heightImage height

Definition at line 704 of file Camera.cpp.

705{
706 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::SaveImageToDisk);
707
708 if (FrameBuffer.IsEmpty() || Width == 0 || Height == 0)
709 {
710 return;
711 }
712
713 int32 Size = Width * Height;
714 if (FrameBuffer.Num() != Size)
715 {
716 FString Msg = "Camera sensor: Unable to save Image to disk. FrameBuffer size and resolution don't match!";
718 return;
719 }
720
721 FString ImageName = FString::Printf(TEXT("image_%d.png"), ImageNumber);
722 FString fullFileName = FString::Printf(TEXT("%s%s"), *FileSavePath, *ImageName);
723 ++ImageNumber;
724
725 SaveCameraMetaDataToDisk(ImageName);
726
727 FIntPoint DestSize(Width, Height);
728 TImagePixelData<FColor> PixelData(DestSize);
729 PixelData.Pixels = FrameBuffer;
730
731 // Create ImageTask
732 TUniquePtr<FImageWriteTask> ImageTask = MakeUnique<FImageWriteTask>();
733 ImageTask->PixelData = MakeUnique<TImagePixelData<FColor>>(PixelData);
734 ImageTask->Filename = fullFileName;
735 ImageTask->Format = EImageFormat::PNG;
736 ImageTask->CompressionQuality = (int32)EImageCompressionQuality::Default;
737 ImageTask->bOverwriteFile = true;
738 ImageTask->PixelPreProcessors.Add(TAsyncAlphaWrite<FColor>(255));
739
740 // Get Screenshot config and enqueue image save task
741 FHighResScreenshotConfig& HighResScreenshotConfig = GetHighResScreenshotConfig();
742 TFuture<bool> CompletionFuture = HighResScreenshotConfig.ImageWriteQueue->Enqueue(MoveTemp(ImageTask));
743}
int32 ImageNumber
Definition: Camera.h:373
void SaveCameraMetaDataToDisk(const FString &ImageName)
Definition: Camera.cpp:745

References ASensor::FileSavePath, ImageNumber, SimulatorLog::Log(), SaveCameraMetaDataToDisk(), and SaveImageToDisk().

Referenced by FrameGrabberCapture(), and SaveImageToDisk().

◆ SendImageDataToROS()

void ACamera::SendImageDataToROS ( const TArray< FColor > &  FrameBuffer,
int32  Width,
int32  Height 
)
protectedvirtual

Construct ROS Image msg and send data to ROS topic

Parameters
FrameBufferPixel array
widthImage width
heightImage height

Definition at line 648 of file Camera.cpp.

649{
650 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::SendImageDataToROS);
651
652 UTopic* Topic = GetROSTopic();
653 if (!SendDataToROS
654 || !Topic
655 || !IsROSConnected()
656 || FrameBuffer.IsEmpty()
657 || !ImageMsg.IsValid())
658 {
659 return;
660 }
661
662 ImageMsg->height = Height;
663 ImageMsg->width = Width;
664
665 // Cast TArray<FColor> into uint8[] data with all channels (RBGA)
666 // Currently not in use but left here incase this is ever needed again.
667 //ImageMsg->encoding = "bgra8";
668 //ImageMsg->step = Width * 4;
669 //ImageMsg->data = const_cast<uint8*>(reinterpret_cast<const uint8*>(FrameBuffer.GetData()));
670
671 // Convert TArray<FColor> to uint8[] data without alpha channel
672 // By removing alpha channel, we reduce ~25% of ROS bandwidth,
673 // but costs a bit more in processing time here
674 const int32 BufferSize = Width * Height * 3;
675 if (!BGR8Buffer || CurrentBufferSize != BufferSize)
676 {
677 // Resize buffer if needed
678 delete[] BGR8Buffer;
679 BGR8Buffer = new uint8[BufferSize];
680 CurrentBufferSize = BufferSize;
681 }
682
683 uint8* Dest = BGR8Buffer;
684
685 const FColor* Source = FrameBuffer.GetData();
686 const int32 PixelCount = FrameBuffer.Num();
687
688 for (int32 i = 0; i < PixelCount; ++i)
689 {
690 const FColor& Pixel = Source[i];
691 *Dest++ = Pixel.B;
692 *Dest++ = Pixel.G;
693 *Dest++ = Pixel.R;
694 }
695
696 ImageMsg->step = Width * 3;
697 ImageMsg->data = BGR8Buffer;
698 ImageMsg->header.time = FROSTime::Now();
699
700 // Send Image to ROS
701 Topic->Publish(ImageMsg);
702}
UTopic * GetROSTopic() const
Definition: Sensor.h:150
FORCEINLINE bool IsROSConnected() const
Definition: Sensor.h:201

References BGR8Buffer, CurrentBufferSize, ASensor::GetROSTopic(), ImageMsg, ASensor::IsROSConnected(), ASensor::SendDataToROS, and SendImageDataToROS().

Referenced by FrameGrabberCapture(), and SendImageDataToROS().

◆ SetShadowRendering()

void ACamera::SetShadowRendering ( bool  RenderShadows)

Set should this camera USceneCaptureComponent2D render shadows

Definition at line 810 of file Camera.cpp.

811{
813 {
814 auto& CameraShowFlags = CaptureComponent2D->ShowFlags;
815 CameraShowFlags.SetDynamicShadows(RenderShadows);
816 CameraShowFlags.SetContactShadows(RenderShadows);
817 CameraShowFlags.SetCapsuleShadows(RenderShadows);
818 }
819}

References CaptureComponent2D.

Referenced by ADepthCamera::Init(), ASemanticSegmentationCamera::Init(), and AThermalCamera::Init().

◆ SetTemporalAA()

void ACamera::SetTemporalAA ( bool  SetTemporal)

Set USceneCaptureComponent2D TemporalAA on or off.

Definition at line 821 of file Camera.cpp.

822{
824 {
825 auto& CameraShowFlags = CaptureComponent2D->ShowFlags;
826 CameraShowFlags.SetTemporalAA(SetTemporal);
827 }
828}

References CaptureComponent2D.

Referenced by SetupCamera().

◆ SetupCamera()

void ACamera::SetupCamera ( FCameraBaseParameters  parameters)
private

Setup all needed things to make Camera operate.

Definition at line 128 of file Camera.cpp.

129{
131 {
132#if WITH_EDITOR
133 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: CaptureComponent2D is nullptr!"));
134#endif
135 return;
136 }
137
138 CameraParameters = parameters;
139
141
143 {
145 }
146
147 const bool UsePostProcessingEffects = CameraParameters.PostProcessingEffects;
148 auto& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
149
150 if (parameters.UsePhysicLensDistortionEffect)
151 {
152 if (!PhysicLensDistortion.IsValid())
153 {
154 const FString Path = "/Game/Agrarsense/Materials/PostProcessingMaterials/PhysicLensDistortion.PhysicLensDistortion";
155 PhysicLensDistortion = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
156
157 if (PhysicLensDistortion.IsValid())
158 {
159 PostProcessSettings.AddBlendable(PhysicLensDistortion.Get(), 1.0f);
160#if WITH_EDITOR
161 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Added physics lens distortion effect."));
162#endif
163 }
164 }
165 }
166 else if (PhysicLensDistortion.IsValid())
167 {
168 PostProcessSettings.RemoveBlendable(PhysicLensDistortion.Get());
169 PhysicLensDistortion.Reset();
170#if WITH_EDITOR
171 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Removed physics lens distortion effect."));
172#endif
173 }
174
175 if (parameters.UseIceLensEffect)
176 {
177 if (!IceMaterialInstance.IsValid())
178 {
179 const FString Path = "/Game/Agrarsense/Materials/PostProcessingMaterials/CameraPostProcessEffects/m_ice_lens_effect";
180 UMaterial* LoadedIceMaterial = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
181
182 // Create UMaterialInstanceDynamic from LoadedIceMaterial
183 IceMaterialInstance = UMaterialInstanceDynamic::Create(LoadedIceMaterial, nullptr);
184 if (IceMaterialInstance.IsValid())
185 {
186 // Add material to CaptureComponent2D PostProcessSettings
187 PostProcessSettings.AddBlendable(IceMaterialInstance.Get(), 1.0f);
188#if WITH_EDITOR
189 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Added ice lens effect."));
190#endif
191 }
192 }
193
194 UMaterialInstanceDynamic* IceMatInstance = IceMaterialInstance.Get();
195 if (IceMatInstance)
196 {
197 // Set IceMaterialInstance scalar parameters values
198 IceMatInstance->SetScalarParameterValue(FName("Strength"), parameters.IceLensEffectStrength);
199 IceMatInstance->SetScalarParameterValue(FName("Angle"), parameters.IceLensEffectAngle);
200#if WITH_EDITOR
201 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Changed ice lens effect parameters."));
202#endif
203 }
204 }
205 else if (IceMaterialInstance.IsValid())
206 {
207 UMaterialInstanceDynamic* IceMatInstance = IceMaterialInstance.Get();
208 if (IceMatInstance)
209 {
210 // Remove material from CaptureComponent2D PostProcessSettings
211 PostProcessSettings.RemoveBlendable(IceMatInstance);
212 IceMaterialInstance.Reset();
213
214#if WITH_EDITOR
215 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Removed ice lens effect."));
216#endif
217 }
218 }
219
222 const float TargetGamma = CameraParameters.TargetGamma;
223 const bool Enable16BitFormat = CameraParameters.Enable16BitFormat;
224
225 CaptureRenderTarget->InitCustomFormat(ImageWidth, ImageHeight, Enable16BitFormat ? PF_FloatRGB : PF_B8G8R8A8, !UsePostProcessingEffects);
226
227 CaptureRenderTarget->TargetGamma = TargetGamma;
228
229 // Set PostProcessSettings override (on or off)
230 PostProcessSettings.bOverride_AutoExposureMethod = UsePostProcessingEffects;
231 PostProcessSettings.bOverride_AutoExposureBias = UsePostProcessingEffects;
232 PostProcessSettings.bOverride_AutoExposureMinBrightness = UsePostProcessingEffects;
233 PostProcessSettings.bOverride_AutoExposureMaxBrightness = UsePostProcessingEffects;
234 PostProcessSettings.bOverride_AutoExposureSpeedUp = UsePostProcessingEffects;
235 PostProcessSettings.bOverride_AutoExposureSpeedDown = UsePostProcessingEffects;
236 PostProcessSettings.bOverride_HistogramLogMin = UsePostProcessingEffects;
237 PostProcessSettings.bOverride_HistogramLogMax = UsePostProcessingEffects;
238 PostProcessSettings.bOverride_CameraShutterSpeed = UsePostProcessingEffects;
239 PostProcessSettings.bOverride_CameraISO = UsePostProcessingEffects;
240 PostProcessSettings.bOverride_DepthOfFieldFstop = UsePostProcessingEffects;
241 PostProcessSettings.bOverride_DepthOfFieldMinFstop = UsePostProcessingEffects;
242 PostProcessSettings.bOverride_DepthOfFieldBladeCount = UsePostProcessingEffects;
243 PostProcessSettings.bOverride_FilmSlope = UsePostProcessingEffects;
244 PostProcessSettings.bOverride_FilmToe = UsePostProcessingEffects;
245 PostProcessSettings.bOverride_FilmShoulder = UsePostProcessingEffects;
246 PostProcessSettings.bOverride_FilmWhiteClip = UsePostProcessingEffects;
247 PostProcessSettings.bOverride_FilmBlackClip = UsePostProcessingEffects;
248 PostProcessSettings.bOverride_MotionBlurAmount = UsePostProcessingEffects;
249 PostProcessSettings.bOverride_MotionBlurMax = UsePostProcessingEffects;
250 PostProcessSettings.bOverride_MotionBlurPerObjectSize = UsePostProcessingEffects;
251 PostProcessSettings.bOverride_WhiteTemp = UsePostProcessingEffects;
252 PostProcessSettings.bOverride_WhiteTint = UsePostProcessingEffects;
253 PostProcessSettings.bOverride_ColorContrast = UsePostProcessingEffects;
254 PostProcessSettings.bOverride_SceneFringeIntensity = UsePostProcessingEffects;
255 PostProcessSettings.bOverride_ChromaticAberrationStartOffset = UsePostProcessingEffects;
256 PostProcessSettings.bOverride_AmbientOcclusionIntensity = UsePostProcessingEffects;
257 PostProcessSettings.bOverride_AmbientOcclusionRadius = UsePostProcessingEffects;
258 PostProcessSettings.bOverride_AmbientOcclusionStaticFraction = UsePostProcessingEffects;
259 PostProcessSettings.bOverride_AmbientOcclusionFadeDistance = UsePostProcessingEffects;
260 PostProcessSettings.bOverride_AmbientOcclusionPower = UsePostProcessingEffects;
261 PostProcessSettings.bOverride_AmbientOcclusionBias = UsePostProcessingEffects;
262 PostProcessSettings.bOverride_AmbientOcclusionQuality = UsePostProcessingEffects;
263 PostProcessSettings.bOverride_BloomMethod = UsePostProcessingEffects;
264 PostProcessSettings.bOverride_BloomIntensity = UsePostProcessingEffects;
265 PostProcessSettings.bOverride_BloomThreshold = UsePostProcessingEffects;
266 PostProcessSettings.bOverride_LensFlareIntensity = UsePostProcessingEffects;
267 PostProcessSettings.bOverride_DepthOfFieldFocalDistance = UsePostProcessingEffects;
268 PostProcessSettings.bOverride_DepthOfFieldDepthBlurAmount = UsePostProcessingEffects;
269 PostProcessSettings.bOverride_DepthOfFieldDepthBlurRadius = UsePostProcessingEffects;
270
271 // Set PostProcessSettings values
272 PostProcessSettings.CameraShutterSpeed = CameraParameters.ShutterSpeed;
273 PostProcessSettings.CameraISO = CameraParameters.ISO;
274 PostProcessSettings.DepthOfFieldFstop = CameraParameters.Aperture;
275 PostProcessSettings.DepthOfFieldFocalDistance = CameraParameters.FocalDistance;
276 PostProcessSettings.DepthOfFieldDepthBlurAmount = CameraParameters.DepthBlurAmount;
277 PostProcessSettings.DepthOfFieldDepthBlurRadius = CameraParameters.DepthBlurRadius;
278 PostProcessSettings.DepthOfFieldMinFstop = CameraParameters.DofMinFStop;
279 PostProcessSettings.DepthOfFieldBladeCount = CameraParameters.DofBladeCount;
280 PostProcessSettings.FilmSlope = CameraParameters.FilmSlope;
281 PostProcessSettings.FilmToe = CameraParameters.FilmToe;
282 PostProcessSettings.FilmShoulder = CameraParameters.FilmShoulder;
283 PostProcessSettings.FilmBlackClip = CameraParameters.FilmBlackClip;
284 PostProcessSettings.FilmWhiteClip = CameraParameters.FilmWhiteClip;
285 PostProcessSettings.AutoExposureMinBrightness = CameraParameters.ExposureMinBrightness;
286 PostProcessSettings.AutoExposureMaxBrightness = CameraParameters.ExposureMaxBrightness;
287 PostProcessSettings.AutoExposureSpeedUp = CameraParameters.ExposureSpeedUp;
288 PostProcessSettings.AutoExposureSpeedDown = CameraParameters.ExposureSpeedDown;
289 PostProcessSettings.MotionBlurAmount = CameraParameters.MotionBlurIntensity;
290 PostProcessSettings.MotionBlurMax = CameraParameters.MotionBlurMax;
291 PostProcessSettings.MotionBlurPerObjectSize = CameraParameters.MotionBlurMinObjSize;
292 PostProcessSettings.LensFlareIntensity = CameraParameters.LensFlareIntensity;
293 PostProcessSettings.BloomIntensity = CameraParameters.BloomIntensity;
294 PostProcessSettings.WhiteTemp = CameraParameters.WhiteTemp;
295 PostProcessSettings.WhiteTint = CameraParameters.WhiteTint;
296 PostProcessSettings.SceneFringeIntensity = CameraParameters.ChromAberrIntensity;
297 PostProcessSettings.ChromaticAberrationStartOffset = CameraParameters.ChromAberrOffset;
298
301
303 {
304 // Enable HDR on CaptureSource, only allowed for RGB Camera for now.
305 CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_FinalToneCurveHDR;
306 }
307 else
308 {
309 CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR;
310 }
311
312 CaptureComponent2D->bUseRayTracingIfEnabled = true;
313 CaptureComponent2D->UpdateContent();
314 CaptureComponent2D->Activate();
315
317
318 FString Encoding = "bgr8";
319
320 // Create ROS Image message
321 ImageMsg.Reset();
322 ImageMsg = MakeShared<ROSMessages::sensor_msgs::Image>();
323 ImageMsg->header.frame_id = "world";
324 ImageMsg->height = ImageWidth;
325 ImageMsg->width = ImageHeight;
326 ImageMsg->encoding = Encoding;
327 ImageMsg->is_bigendian = 0;
328 ImageMsg->step = ImageWidth * 4;
329
331
332 if (!UnrealWindow.IsValid())
333 {
334 // Create and setup UnrealWindow
335 FString windowName = GetSensorIdentifier() + " Window";
337
338 // Set on Window closed event
340 UnrealWindow->GetSWindow()->SetOnWindowClosed(OnWindowClosedDelegate);
341
342 // try to create Camera parameter Widget from path
343 FSoftClassPath WidgetClassPath(TEXT("/Game/Agrarsense/Widgets/Camera/WBP_CameraControlsMenu.WBP_CameraControlsMenu_C"));
344 UClass* WidgetClass = WidgetClassPath.TryLoadClass<UUserWidget>();
345
346 APlayerController* PlayerController = UGameplayStatics::GetPlayerController(GetWorld(), 0);
347
348 if (WidgetClass && PlayerController)
349 {
350 UCameraWidgetBase* WidgetInstance = CreateWidget<UCameraWidgetBase>(PlayerController, WidgetClass);
351 if (WidgetInstance)
352 {
353 bool ShowGuide = false;
354 WidgetInstance->Setup(this, ShowGuide);
355 this->AddWidgetToWindow(WidgetInstance);
356 }
357 }
358 }
359
360 bool Resized = false;
361 if (UnrealWindow.IsValid())
362 {
363 UnrealWindow->SetupComponent(CaptureRenderTarget);
364 if (UnrealWindow->GetWindowWidth() != ImageWidth || UnrealWindow->GetWindowHeight() != ImageHeight)
365 {
366 UnrealWindow->ResizeWindow(ImageWidth, ImageHeight);
367 Resized = true;
368 }
369 }
370
372
373 if (Resized)
374 {
376 }
377
379 {
381 }
382}
virtual ESensorTypes GetSensorType() const override
Definition: Camera.h:74
void OnWindowClosed(const TSharedRef< SWindow > &Window)
Definition: Camera.cpp:781
void StartFrameGrabber()
Definition: Camera.cpp:600
void AddWidgetToWindow(UWidget *WidgetToAdd)
Definition: Camera.cpp:794
void SetTemporalAA(bool SetTemporal)
Definition: Camera.cpp:821
TWeakObjectPtr< UMaterial > PhysicLensDistortion
Definition: Camera.h:297
FCameraDelegate_OnWindowResized OnCameraWindowResized
Definition: Camera.h:148
float CameraFrameRate
Definition: Camera.h:370
FString GetSensorIdentifier() const
Definition: Sensor.h:75
virtual void CreateROSTopic()
Definition: Sensor.cpp:190
static bool ShouldStartWindowMinimized()
virtual void Setup(ACamera *CameraRef, bool ShowOnStartup=true)

References AddWidgetToWindow(), FCameraBaseParameters::Aperture, FCameraBaseParameters::BloomIntensity, CameraFrameRate, CameraParameters, CaptureComponent2D, CaptureRenderTarget, FCameraBaseParameters::ChromAberrIntensity, FCameraBaseParameters::ChromAberrOffset, CreateLogFile(), ASensor::CreateROSTopic(), FCameraBaseParameters::DepthBlurAmount, FCameraBaseParameters::DepthBlurRadius, FCameraBaseParameters::DofBladeCount, FCameraBaseParameters::DofMinFStop, FCameraBaseParameters::Enable16BitFormat, FCameraBaseParameters::ExposureMaxBrightness, FCameraBaseParameters::ExposureMinBrightness, FCameraBaseParameters::ExposureSpeedDown, FCameraBaseParameters::ExposureSpeedUp, FCameraBaseParameters::FilmBlackClip, FCameraBaseParameters::FilmShoulder, FCameraBaseParameters::FilmSlope, FCameraBaseParameters::FilmToe, FCameraBaseParameters::FilmWhiteClip, FCameraBaseParameters::FocalDistance, FCameraBaseParameters::FOV, ASensor::GetSensorIdentifier(), GetSensorType(), FCameraBaseParameters::Height, FCameraBaseParameters::IceLensEffectAngle, FCameraBaseParameters::IceLensEffectStrength, IceMaterialInstance, ImageHeight, ImageMsg, ImageWidth, FCameraBaseParameters::ISO, FCameraBaseParameters::LensFlareIntensity, FCameraBaseParameters::MotionBlurIntensity, FCameraBaseParameters::MotionBlurMax, FCameraBaseParameters::MotionBlurMinObjSize, OnCameraWindowResized, OnWindowClosed(), OnWindowClosedDelegate, PhysicLensDistortion, FCameraBaseParameters::PostProcessingEffects, RGBCamera, FCameraBaseParameters::SaveImageToDisk, FCameraBaseParameters::SendDataToROS, ASensor::SendDataToROS, SetTemporalAA(), UCameraWidgetBase::Setup(), UAgrarsenseSettings::ShouldStartWindowMinimized(), FCameraBaseParameters::ShutterSpeed, StartFrameGrabber(), FCameraBaseParameters::TargetFrameRate, FCameraBaseParameters::TargetGamma, UnrealWindow, FCameraBaseParameters::UseHDR, FCameraBaseParameters::UseIceLensEffect, FCameraBaseParameters::UsePhysicLensDistortionEffect, FCameraBaseParameters::UseTemporalAA, FCameraBaseParameters::WhiteTemp, FCameraBaseParameters::WhiteTint, and FCameraBaseParameters::Width.

Referenced by ChangeCameraParameters(), and Init().

◆ SetUseGimbal()

void ACamera::SetUseGimbal ( bool  UseGimbal)
inline

Definition at line 210 of file Camera.h.

211 {
212 AllowGimbal = UseGimbal;
213 }

◆ ShouldSimulate()

bool ACamera::ShouldSimulate ( const float  DeltaSeconds)
private

Should this camera sensor be simulated this frame

Definition at line 519 of file Camera.cpp.

520{
521 if (!CanSimulateSensor())
522 {
523 ShouldSimulateCamera = false;
525 }
526
528 {
531 }
532
533 FrameRateTimer += DeltaSeconds;
535 {
536 FrameRateTimer = 0.0f;
539 }
540
541 ShouldSimulateCamera = false;
542
544}
float FrameRateTimer
Definition: Camera.h:371
bool CanSimulateSensor() const
Definition: Sensor.h:170

References CameraFrameRate, CameraParameters, ASensor::CanSimulateSensor(), FrameRateTimer, ShouldSimulateCamera, and FCameraBaseParameters::TargetFrameRate.

Referenced by PreActorTick().

◆ StartFrameGrabber()

void ACamera::StartFrameGrabber ( )
private

Setup and start FrameGrabber

Definition at line 600 of file Camera.cpp.

601{
602 if (!UnrealWindow.IsValid())
603 {
604#if WITH_EDITOR
605 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: UnrealWindow is nullptr!"));
606#endif
607 return;
608 }
609
610 // Destroy old FrameGrabber
612
613 TSharedPtr<FSceneViewport> SceneViewport = UnrealWindow->GetSceneViewport();
614 if (SceneViewport.IsValid() && CaptureRenderTarget)
615 {
616 EPixelFormat PixelFormat = GetPixelFormatFromRenderTargetFormat(TextureFormat);
617 FIntPoint Size = SceneViewport->GetSize();
618
620 {
621 // Currently only DVS camera needs this texture to render DVS output into separate FUnrealWindow.
622 CaptureFrameTexture = UTexture2D::CreateTransient(Size.X, Size.Y, PixelFormat);
623 CaptureFrameTexture->UpdateResource();
624 }
625
626 FrameGrabber = MakeShareable(new FFrameGrabber(SceneViewport.ToSharedRef(), Size, PixelFormat));
627 FrameGrabber->StartCapturingFrames();
628 }
629}
TEnumAsByte< ETextureRenderTargetFormat > TextureFormat
Definition: Camera.h:134

References CaptureFrameTexture, CaptureRenderTarget, DVSCamera, FrameGrabber, GetSensorType(), ReleaseFrameGrabber(), TextureFormat, and UnrealWindow.

Referenced by SetupCamera().

Member Data Documentation

◆ AllowGimbal

bool ACamera::AllowGimbal = true
protected

Definition at line 302 of file Camera.h.

Referenced by BeginPlay(), and PreActorTick().

◆ BGR8Buffer

uint8* ACamera::BGR8Buffer = nullptr
private

Definition at line 375 of file Camera.h.

Referenced by EndPlay(), and SendImageDataToROS().

◆ CameraFrameRate

float ACamera::CameraFrameRate = 0.0f
private

Definition at line 370 of file Camera.h.

Referenced by SetupCamera(), and ShouldSimulate().

◆ CameraName

FString ACamera::CameraName = "Camera "
protected

Camera title name for the new Unreal Window For example: "Camera 2 Window" or "ThermalCamera 1 Window" Accessible in inherited classes.

Definition at line 274 of file Camera.h.

Referenced by ADepthCamera::Init(), ADVSCamera::Init(), ASemanticSegmentationCamera::Init(), and AThermalCamera::Init().

◆ CameraParameters

FCameraBaseParameters ACamera::CameraParameters
private

Current Camera parameters.

Definition at line 346 of file Camera.h.

Referenced by FrameGrabberCapture(), ResizeCamera(), SetupCamera(), and ShouldSimulate().

◆ CaptureComponent2D

USceneCaptureComponent2D* ACamera::CaptureComponent2D = nullptr
protected

◆ CaptureFrameTexture

UTexture2D* ACamera::CaptureFrameTexture
protected

public UTexture2D variable pointer BlueprintReadOnly.

Definition at line 289 of file Camera.h.

Referenced by ReleaseFrameGrabber(), StartFrameGrabber(), and ADVSCamera::UpdateDVSWindowOutput().

◆ CaptureRenderTarget

UTextureRenderTarget2D* ACamera::CaptureRenderTarget = nullptr
protected

Definition at line 279 of file Camera.h.

Referenced by ACamera(), EndPlay(), SetupCamera(), and StartFrameGrabber().

◆ CurrentBufferSize

int32 ACamera::CurrentBufferSize = 0
private

Definition at line 377 of file Camera.h.

Referenced by EndPlay(), and SendImageDataToROS().

◆ DronePtr

APIDDrone* ACamera::DronePtr = nullptr
protected

Definition at line 300 of file Camera.h.

Referenced by BeginPlay(), and PreActorTick().

◆ FilePrefix

FString ACamera::FilePrefix = "Data/Camera_"
protected

◆ FrameGrabber

TSharedPtr<FFrameGrabber> ACamera::FrameGrabber
private

FrameGrabber TSharedPtr

Definition at line 330 of file Camera.h.

Referenced by FrameGrabberCapture(), PreActorTick(), ReleaseFrameGrabber(), and StartFrameGrabber().

◆ FrameRateTimer

float ACamera::FrameRateTimer = 0.0f
private

Definition at line 371 of file Camera.h.

Referenced by ShouldSimulate().

◆ GeoReferencingSystem

AGeoReferencingSystem* ACamera::GeoReferencingSystem = nullptr
private

Definition at line 355 of file Camera.h.

Referenced by CreateLogFile(), and SaveCameraMetaDataToDisk().

◆ IceMaterialInstance

TWeakObjectPtr<UMaterialInstanceDynamic> ACamera::IceMaterialInstance
protected

Definition at line 295 of file Camera.h.

Referenced by EndPlay(), and SetupCamera().

◆ ImageHeight

int32 ACamera::ImageHeight = 720
private

Definition at line 364 of file Camera.h.

Referenced by FrameGrabberCapture(), and SetupCamera().

◆ ImageMsg

TSharedPtr<ROSMessages::sensor_msgs::Image> ACamera::ImageMsg
private

Definition at line 361 of file Camera.h.

Referenced by EndPlay(), SendImageDataToROS(), and SetupCamera().

◆ ImageNumber

int32 ACamera::ImageNumber = 0
private

Definition at line 373 of file Camera.h.

Referenced by SaveImageToDisk().

◆ ImageWidth

int32 ACamera::ImageWidth = 1280
private

Definition at line 363 of file Camera.h.

Referenced by FrameGrabberCapture(), and SetupCamera().

◆ OnCameraWindowClosed

FCameraDelegate_OnWindowClosed ACamera::OnCameraWindowClosed

On Camera sensor destroyed event. BlueprintAssignable.

Returns
ACamera pointer

Definition at line 141 of file Camera.h.

Referenced by OnWindowClosed().

◆ OnCameraWindowResized

FCameraDelegate_OnWindowResized ACamera::OnCameraWindowResized

On Camera sensor window resized event. BlueprintAssignable.

Returns
ACamera pointer

Definition at line 148 of file Camera.h.

Referenced by ADVSCamera::EndPlay(), ADVSCamera::Init(), and SetupCamera().

◆ OnPostTickDelegate

FDelegateHandle ACamera::OnPostTickDelegate
protected

Definition at line 237 of file Camera.h.

Referenced by BeginPlay(), and EndPlay().

◆ OnPreTickDelegate

FDelegateHandle ACamera::OnPreTickDelegate
protected

Definition at line 234 of file Camera.h.

Referenced by BeginPlay(), and EndPlay().

◆ OnWindowClosedDelegate

FOnWindowClosed ACamera::OnWindowClosedDelegate
private

Definition at line 359 of file Camera.h.

Referenced by EndPlay(), and SetupCamera().

◆ ParametersChanged

bool ACamera::ParametersChanged = false
private

Definition at line 357 of file Camera.h.

◆ PhysicLensDistortion

TWeakObjectPtr<UMaterial> ACamera::PhysicLensDistortion
protected

Definition at line 297 of file Camera.h.

Referenced by SetupCamera().

◆ SaveCurrentFrameToDiskRequested

bool ACamera::SaveCurrentFrameToDiskRequested = false
private

Definition at line 366 of file Camera.h.

Referenced by FrameGrabberCapture().

◆ SensorSetRotation

FRotator ACamera::SensorSetRotation
protected

Definition at line 301 of file Camera.h.

Referenced by PreActorTick().

◆ ShouldSimulateCamera

bool ACamera::ShouldSimulateCamera = true
private

Definition at line 368 of file Camera.h.

Referenced by FrameGrabberCapture(), and ShouldSimulate().

◆ TempParams

FCameraBaseParameters ACamera::TempParams
private

Definition at line 352 of file Camera.h.

◆ TextureFormat

TEnumAsByte<ETextureRenderTargetFormat> ACamera::TextureFormat = ETextureRenderTargetFormat::RTF_RGBA8

public TEnumAsByte<ETextureRenderTargetFormat> variable BlueprintReadOnly.

Definition at line 134 of file Camera.h.

Referenced by StartFrameGrabber().

◆ TickEntry

FTickEntry ACamera::TickEntry
protected

Definition at line 293 of file Camera.h.

Referenced by BeginPlay(), and EndPlay().

◆ UnrealWindow

TSharedPtr<FUnrealWindow> ACamera::UnrealWindow
protected

◆ UseParallelLateTick

bool ACamera::UseParallelLateTick = true
protected

Definition at line 232 of file Camera.h.

Referenced by ADVSCamera::ADVSCamera(), BeginPlay(), and EndPlay().


The documentation for this class was generated from the following files: