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 SetTemporalAA (bool SetTemporal)
 
void ResizeCamera (int Width=1280, int Height=720)
 
void SaveCurrentFrameToDisk ()
 
int GetCameraWidth () const
 
int GetCameraHeight () const
 
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
 
void SetSensorName (const FString newName)
 
virtual FString GetTopicName ()
 
UTopic * GetROSTopic () const
 
void SetSimulateSensor (bool SimulateSensor)
 
bool CanSimulateSensor () const
 
ASensorModelGetSensorModel () const
 
void SetSensorModel (ASensorModel *NewSensorModel)
 
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
 
- 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
 
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
 
- Protected Attributes inherited from ASensor
UTopic * ROSTopic = nullptr
 
bool SendDataToROS = true
 
ULogFileLogFile = 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
 
int ImageWidth = 1280
 
int ImageHeight = 720
 
bool SaveCurrentFrameToDiskRequested = false
 
bool ShouldSimulateCamera = true
 
float CameraFrameRate = 0.0f
 
float FrameRateTimer = 0.0f
 
int ImageNumber = 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 51 of file Camera.h.

Constructor & Destructor Documentation

◆ ACamera()

ACamera::ACamera ( const FObjectInitializer &  ObjectInitializer)

Setup new ACamera class

Parameters
FObjectInitializerdefault ObjectInitializer

Definition at line 29 of file Camera.cpp.

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

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 55 of file Camera.cpp.

56{
57 UMaterial* PostProcessingMat = Cast<UMaterial>(StaticLoadObject(UMaterial::StaticClass(), nullptr, *Path));
58 if (PostProcessingMat && CaptureComponent2D)
59 {
60 FPostProcessSettings& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
61 PostProcessSettings.AddBlendable(PostProcessingMat, Weight);
62 }
63 else
64 {
65 FString Sensor = GetSensorName();
66 FString Msg = "Failed to add Post processing material to " + Sensor;
68 }
69}
FString GetSensorName() const
Definition: Sensor.h:95
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 ADVSCamera.

Definition at line 541 of file Camera.cpp.

542{
543 // Only DVSCamera adds processing to the frame buffer
544 return;
545}

Referenced by FrameGrabberCapture().

◆ AddWidgetToWindow()

void ACamera::AddWidgetToWindow ( UWidget *  WidgetToAdd)

Add Widget to custom Unreal Window

Definition at line 714 of file Camera.cpp.

715{
716 if (UnrealWindow.IsValid() && WidgetToAdd)
717 {
718 UnrealWindow->AddUWidgetToWindow(WidgetToAdd);
719 }
720}
TSharedPtr< FUnrealWindow > UnrealWindow
Definition: Camera.h:279

References UnrealWindow.

Referenced by SetupCamera().

◆ BeginPlay()

void ACamera::BeginPlay ( )
overrideprotectedvirtual

Reimplemented from ASensor.

Definition at line 376 of file Camera.cpp.

377{
378 Super::BeginPlay();
379
380 // Register to PreActorTick where USceneCaptureComponent2D will get rendered.
381 OnPreTickDelegate = FWorldDelegates::OnWorldPreActorTick.AddUObject(this, &ACamera::PreActorTick);
382
383 // Check if we should use ATickManager which ticks in parallel, or use Post actor tick
384 // In there we capture the screen pixels with FrameGrabber API,
385 // might do some extra processing, save image to disk and send data to ROS.
387 {
388 SetActorTickEnabled(false);
389 TickEntry = ATickManager::AddTick(this, BindTick(this, &ACamera::EndOfFrameParellel), ETickType::LateTickParallel);
390 }
391 else
392 {
393 SetActorTickEnabled(true);
394 OnPostTickDelegate = FWorldDelegates::OnWorldPostActorTick.AddUObject(this, &ACamera::EndOfFrame);
395 }
396
397 // Get all existing components set to be hidden for all Camera sensors (like Lidar point cloud visualization).
398 auto Components = ASensor::GetComponentsToHide();
399 for (int32 i = 0; i < Components.Num(); i++)
400 {
401 UPrimitiveComponent* Primitive = Components[i].Get();
402 if (Primitive)
403 {
404 HidePrimitiveComponent(Primitive);
405 }
406 }
407
408 OnPrimitiveAdded.AddUniqueDynamic(this, &ACamera::HidePrimitiveComponent);
409}
static auto BindTick(ObjectType *Object, FunctionType Function)
Definition: TickManager.h:182
bool UseParallelLateTick
Definition: Camera.h:220
FTickEntry TickEntry
Definition: Camera.h:281
FDelegateHandle OnPostTickDelegate
Definition: Camera.h:225
FDelegateHandle OnPreTickDelegate
Definition: Camera.h:222
void HidePrimitiveComponent(UPrimitiveComponent *PrimitiveComponent)
Definition: Camera.cpp:547
virtual void EndOfFrameParellel(float DeltaTime)
Definition: Camera.cpp:474
virtual void EndOfFrame(UWorld *World, ELevelTick TickType, float DeltaSeconds)
Definition: Camera.cpp:469
virtual void PreActorTick(UWorld *World, ELevelTick TickType, float DeltaSeconds)
Definition: Camera.cpp:452
static FPrimitiveAdded OnPrimitiveAdded
Definition: Sensor.h:354
static TArray< TWeakObjectPtr< UPrimitiveComponent > > GetComponentsToHide()
Definition: Sensor.h:256
static FTickEntry AddTick(UObject *Object, std::function< void(float)> Function, ETickType Type)
Definition: TickManager.cpp:55

References ATickManager::AddTick(), BindTick(), 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 50 of file Camera.cpp.

51{
52 SetupCamera(newParameters);
53}
void SetupCamera(FCameraBaseParameters parameters)
Definition: Camera.cpp:125

References SetupCamera().

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

◆ 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 89 of file Camera.cpp.

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

◆ EndOfFrame()

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

Definition at line 469 of file Camera.cpp.

470{
472}
void FrameGrabberCapture()
Definition: Camera.cpp:506

References FrameGrabberCapture().

Referenced by BeginPlay().

◆ EndOfFrameParellel()

void ACamera::EndOfFrameParellel ( float  DeltaTime)
protectedvirtual

Definition at line 474 of file Camera.cpp.

475{
477}

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 411 of file Camera.cpp.

412{
413 Super::EndPlay(EndPlayReason);
414
415 FWorldDelegates::OnWorldPreActorTick.Remove(OnPreTickDelegate);
416
418 {
420 }
421 else
422 {
423 FWorldDelegates::OnWorldPostActorTick.Remove(OnPostTickDelegate);
424 }
425
426 if (UnrealWindow.IsValid())
427 {
428 OnWindowClosedDelegate.Unbind();
429 UnrealWindow->DestroyWindow();
430 UnrealWindow.Reset();
431 }
432
434
436 {
437 CaptureRenderTarget->ConditionalBeginDestroy();
438 CaptureRenderTarget = nullptr;
439 }
440
442 {
443 CaptureComponent2D->UnregisterComponent();
444 CaptureComponent2D->ConditionalBeginDestroy();
445 CaptureComponent2D = nullptr;
446 }
447
448 ImageMsg.Reset();
449 IceMaterialInstance.Reset();
450}
FOnWindowClosed OnWindowClosedDelegate
Definition: Camera.h:339
TSharedPtr< ROSMessages::sensor_msgs::Image > ImageMsg
Definition: Camera.h:341
void ReleaseFrameGrabber()
Definition: Camera.cpp:589
TWeakObjectPtr< UMaterialInstanceDynamic > IceMaterialInstance
Definition: Camera.h:283
static void RemoveTick(FTickEntry TickEntry)
Definition: TickManager.cpp:90

References CaptureComponent2D, CaptureRenderTarget, 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 506 of file Camera.cpp.

507{
508 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::FrameGrabberCapture);
509
510 if (!ShouldSimulateCamera || !FrameGrabber.IsValid())
511 {
512 return;
513 }
514
516 {
517 return;
518 }
519
520 TArray<FCapturedFrameData> Frames = FrameGrabber->GetCapturedFrames();
521 if (Frames.Num())
522 {
523 FCapturedFrameData& LastFrame = Frames.Last();
524 TArray<FColor>& ImageBuffer = LastFrame.ColorBuffer;
525
526 AddProcessingToFrameBuffer(ImageBuffer);
527
529 {
531 AsyncTask(ENamedThreads::AnyBackgroundThreadNormalTask, [this, ImageBuffer]()
532 {
534 });
535 }
536
538 }
539}
TSharedPtr< FFrameGrabber > FrameGrabber
Definition: Camera.h:313
FCameraBaseParameters CameraParameters
Definition: Camera.h:330
int ImageWidth
Definition: Camera.h:343
void SaveImageToDisk(const TArray< FColor > FrameBuffer, int32 Width, int32 Height)
Definition: Camera.cpp:630
bool ShouldSimulateCamera
Definition: Camera.h:348
virtual void SendImageDataToROS(const TArray< FColor > &FrameBuffer, int32 Width, int32 Height)
Definition: Camera.cpp:607
int ImageHeight
Definition: Camera.h:344
bool SaveCurrentFrameToDiskRequested
Definition: Camera.h:346
virtual void AddProcessingToFrameBuffer(TArray< FColor > &buffer)
Definition: Camera.cpp:541
bool SendDataToROS
Definition: Sensor.h:344

References AddProcessingToFrameBuffer(), CameraParameters, 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 198 of file Camera.h.

199 {
200 return ImageHeight;
201 }

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

◆ GetCameraParameters()

FCameraBaseParameters ACamera::GetCameraParameters ( )
inline

Get current Camera parameters

Returns
FCameraBaseParameters struct

Definition at line 90 of file Camera.h.

91 {
92 return CameraParameters;
93 }

Referenced by USimulatorJsonExporter::ExportSensorToJSON().

◆ GetCameraWidth()

int ACamera::GetCameraWidth ( ) const
inline

Definition at line 192 of file Camera.h.

193 {
194 return ImageWidth;
195 }

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 113 of file Camera.h.

114 {
115 return CaptureComponent2D;
116 }

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

◆ GetCaptureRenderTarget2D()

UTextureRenderTarget2D * ACamera::GetCaptureRenderTarget2D ( ) const
inline

Get UTextureRenderTarget2D pointer.

Returns
UTextureRenderTarget2D pointer

Definition at line 123 of file Camera.h.

124 {
125 return CaptureRenderTarget;
126 }

◆ 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 206 of file Camera.h.

207 {
209 }
static FString StructToString(const InStructType &InStruct)
Definition: Sensor.h:305

◆ 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 73 of file Camera.h.

74 {
76 }

References RGBCamera.

Referenced by SetupCamera(), and StartFrameGrabber().

◆ HidePrimitiveComponent()

void ACamera::HidePrimitiveComponent ( UPrimitiveComponent *  PrimitiveComponent)
protected

Definition at line 547 of file Camera.cpp.

548{
549 if (PrimitiveComponent && CaptureComponent2D)
550 {
551 CaptureComponent2D->HideComponent(PrimitiveComponent);
552 }
553}

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 80 of file Camera.cpp.

81{
83 SetSimulateSensor(SimulateSensor);
84 SetupCamera(parameters);
85
87}
void CreateLogFile() override
Definition: Camera.cpp:89
virtual void CreateDataSavePath()
Definition: Sensor.cpp:202
void SetSimulateSensor(bool SimulateSensor)
Definition: Sensor.h:151

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

Referenced by USensorFactory::SpawnCamera().

◆ OnWindowClosed()

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

On camera window closed event

Parameters
Windowreference to SWindow pointer

Definition at line 701 of file Camera.cpp.

702{
703#if WITH_EDITOR
704 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: Camera window closed. Destroying Camera sensor.."));
705#endif
706
707 // Broadcast event that this Camera sensor is about be destroyed when user has clicked Window Close button.
708 OnCameraWindowClosed.Broadcast(this);
709
710 // Destroy this camera sensor
711 this->Destroy();
712}
FCameraDelegate_OnWindowClosed OnCameraWindowClosed
Definition: Camera.h:140

References Destroy, and OnCameraWindowClosed.

Referenced by SetupCamera().

◆ PreActorTick()

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

Definition at line 452 of file Camera.cpp.

453{
454 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::PreActorTick);
455
456 if (ShouldSimulate(DeltaSeconds) && CaptureComponent2D)
457 {
458 // Capture scene now.
459 // We could use CaptureSceneDeferred but it would not work if World (Spectator) Rendering is disabled.
460 CaptureComponent2D->CaptureScene();
461
462 if (FrameGrabber.IsValid())
463 {
464 FrameGrabber->CaptureThisFrame(FFramePayloadPtr());
465 }
466 }
467}
bool ShouldSimulate(const float DeltaSeconds)
Definition: Camera.cpp:479

References CaptureComponent2D, FrameGrabber, PreActorTick(), and ShouldSimulate().

Referenced by BeginPlay(), and PreActorTick().

◆ ReleaseFrameGrabber()

void ACamera::ReleaseFrameGrabber ( )
private

Release FrameGrabber and destroy UTexture2D

Definition at line 589 of file Camera.cpp.

590{
591 if (FrameGrabber.IsValid())
592 {
593 FrameGrabber->StopCapturingFrames();
594 FrameGrabber->Shutdown();
595 FrameGrabber.Reset();
596 }
597
599 {
600 CaptureFrameTexture->RemoveFromRoot();
601 CaptureFrameTexture->ConditionalBeginDestroy();
602 CaptureFrameTexture = nullptr;
603 }
604}
UTexture2D * CaptureFrameTexture
Definition: Camera.h:277

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 71 of file Camera.cpp.

72{
74 {
75 FPostProcessSettings& PostProcessSettings = CaptureComponent2D->PostProcessSettings;
76 PostProcessSettings.RemoveBlendable(Material);
77 }
78}

References CaptureComponent2D.

Referenced by ADepthCamera::SetupDepthMaterial().

◆ RemoveWidgetFromWindow()

void ACamera::RemoveWidgetFromWindow ( UWidget *  WidgetToRemove)

Remove Widget from custom Unreal Window

Definition at line 722 of file Camera.cpp.

723{
724 if (UnrealWindow.IsValid() && WidgetToRemove)
725 {
726 UnrealWindow->RemoveUWidgetFromWindow(WidgetToRemove);
727 }
728}

References UnrealWindow.

◆ ResizeCamera()

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

Resize camera and custom Unreal Window certain size

Definition at line 750 of file Camera.cpp.

751{
752 if (Width == 0 || Height == 0)
753 {
754 return;
755 }
756
757 CameraParameters.Width = Width;
758 CameraParameters.Height = Height;
760}
void ChangeCameraParameters(FCameraBaseParameters newParameters)
Definition: Camera.cpp:50

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

◆ SaveCameraMetaDataToDisk()

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

Definition at line 671 of file Camera.cpp.

672{
673 if (!IsValid(LogFile))
674 {
675 // If the log file located in base class is not valid, return here.
676 return;
677 }
678
679 const FVector ActorPosition = GetActorLocation();
680 const FRotator ActorRotation = GetActorRotation();
681
682 FString MetaData;
683
685 {
686 FGeographicCoordinates GeoCoordinates = UCoordinateConversionUtilities::UnrealToGeographicCoordinates(GeoReferencingSystem, ActorPosition);
687 MetaData = FString::Printf(TEXT("%s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.6f, %.6f, %.2f"), *ImageName, ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
688 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll,
689 GeoCoordinates.Latitude, GeoCoordinates.Longitude, GeoCoordinates.Altitude);
690 }
691 else
692 {
693 MetaData = FString::Printf(TEXT("%s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f"), *ImageName, ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
694 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll);
695 }
696
697 // Write to the log file (this is written after sensor is destroyed)
698 WriteToLogFile(MetaData);
699}
static FGeographicCoordinates UnrealToGeographicCoordinates(AGeoReferencingSystem *GeoReferencingSystem, const FVector &Position)

References 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 183 of file Camera.h.

184 {
186 {
188 }
189 }

◆ 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 630 of file Camera.cpp.

631{
632 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::SaveImageToDisk);
633
634 if (FrameBuffer.IsEmpty() || Width == 0 || Height == 0)
635 {
636 return;
637 }
638
639 int32 Size = Width * Height;
640 if (FrameBuffer.Num() != Size)
641 {
642 FString Msg = "Camera sensor: Unable to save Image to disk. FrameBuffer size and resolution don't match!";
644 return;
645 }
646
647 FString ImageName = FString::Printf(TEXT("image_%d.png"), ImageNumber);
648 FString fullFileName = FString::Printf(TEXT("%s%s"), *FileSavePath, *ImageName);
649 ++ImageNumber;
650
651 SaveCameraMetaDataToDisk(ImageName);
652
653 FIntPoint DestSize(Width, Height);
654 TImagePixelData<FColor> PixelData(DestSize);
655 PixelData.Pixels = FrameBuffer;
656
657 // Create ImageTask
658 TUniquePtr<FImageWriteTask> ImageTask = MakeUnique<FImageWriteTask>();
659 ImageTask->PixelData = MakeUnique<TImagePixelData<FColor>>(PixelData);
660 ImageTask->Filename = fullFileName;
661 ImageTask->Format = EImageFormat::PNG;
662 ImageTask->CompressionQuality = (int32)EImageCompressionQuality::Default;
663 ImageTask->bOverwriteFile = true;
664 ImageTask->PixelPreProcessors.Add(TAsyncAlphaWrite<FColor>(255));
665
666 // Get Screenshot config and enqueue image save task
667 FHighResScreenshotConfig& HighResScreenshotConfig = GetHighResScreenshotConfig();
668 TFuture<bool> CompletionFuture = HighResScreenshotConfig.ImageWriteQueue->Enqueue(MoveTemp(ImageTask));
669}
void SaveCameraMetaDataToDisk(const FString &ImageName)
Definition: Camera.cpp:671
int ImageNumber
Definition: Camera.h:353

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 607 of file Camera.cpp.

608{
609 TRACE_CPUPROFILER_EVENT_SCOPE(ACamera::SendImageDataToROS);
610
611 UTopic* Topic = GetROSTopic();
612 if (!SendDataToROS
613 || !Topic
614 || !IsROSConnected()
615 || FrameBuffer.IsEmpty())
616 {
617 return;
618 }
619
620 if (ImageMsg.IsValid())
621 {
622 ImageMsg->height = Height;
623 ImageMsg->width = Width;
624 ImageMsg->step = Width * 4;
625 ImageMsg->data = const_cast<uint8*>(reinterpret_cast<const uint8*>(FrameBuffer.GetData()));
626 Topic->Publish(ImageMsg);
627 }
628}
UTopic * GetROSTopic() const
Definition: Sensor.h:141
bool IsROSConnected() const
Definition: Sensor.h:192

References 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 730 of file Camera.cpp.

731{
733 {
734 auto& CameraShowFlags = CaptureComponent2D->ShowFlags;
735 CameraShowFlags.SetDynamicShadows(RenderShadows);
736 CameraShowFlags.SetContactShadows(RenderShadows);
737 CameraShowFlags.SetCapsuleShadows(RenderShadows);
738 }
739}

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 741 of file Camera.cpp.

742{
744 {
745 auto& CameraShowFlags = CaptureComponent2D->ShowFlags;
746 CameraShowFlags.SetTemporalAA(SetTemporal);
747 }
748}

References CaptureComponent2D.

Referenced by SetupCamera().

◆ SetupCamera()

void ACamera::SetupCamera ( FCameraBaseParameters  parameters)
private

Setup all needed things to make Camera operate.

Definition at line 125 of file Camera.cpp.

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

References AddWidgetToWindow(), FCameraBaseParameters::Aperture, FCameraBaseParameters::BloomIntensity, CameraFrameRate, CameraParameters, CaptureComponent2D, CaptureRenderTarget, FCameraBaseParameters::ChromAberrIntensity, FCameraBaseParameters::ChromAberrOffset, ASensor::CreateROSTopic(), FCameraBaseParameters::DepthBlurAmount, FCameraBaseParameters::DepthBlurRadius, DepthCamera, 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::SendDataToROS, ASensor::SendDataToROS, SetTemporalAA(), UCameraWidgetBase::Setup(), FCameraBaseParameters::ShutterSpeed, StartFrameGrabber(), FCameraBaseParameters::TargetFrameRate, FCameraBaseParameters::TargetGamma, UnrealWindow, FCameraBaseParameters::UseIceLensEffect, FCameraBaseParameters::UsePhysicLensDistortionEffect, FCameraBaseParameters::UseTemporalAA, FCameraBaseParameters::WhiteTemp, FCameraBaseParameters::WhiteTint, and FCameraBaseParameters::Width.

Referenced by ChangeCameraParameters(), and Init().

◆ ShouldSimulate()

bool ACamera::ShouldSimulate ( const float  DeltaSeconds)
private

Should this camera sensor be simulated this frame

Definition at line 479 of file Camera.cpp.

480{
481 if (!CanSimulateSensor())
482 {
483 ShouldSimulateCamera = false;
485 }
486
488 {
491 }
492
493 FrameRateTimer += DeltaSeconds;
495 {
496 FrameRateTimer = 0.0f;
499 }
500
501 ShouldSimulateCamera = false;
502
504}
float FrameRateTimer
Definition: Camera.h:351
bool CanSimulateSensor() const
Definition: Sensor.h:161

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 555 of file Camera.cpp.

556{
557 if (!UnrealWindow.IsValid())
558 {
559#if WITH_EDITOR
560 UE_LOG(LogTemp, Warning, TEXT("Camera.cpp: UnrealWindow is nullptr!"));
561#endif
562 return;
563 }
564
565 // Destroy old FrameGrabber
567
568 // Get SceneViewport TSharedPtr
569 auto SceneViewport = UnrealWindow->GetSceneViewport();
570
571 if (SceneViewport.IsValid())
572 {
573 EPixelFormat pixelFormat = GetPixelFormatFromRenderTargetFormat(TextureFormat);
574
575 FIntPoint Size = SceneViewport->GetSize();
576
578 {
579 // Currently only DVS camera needs this texture to render DVS output into separate FUnrealWindow.
580 CaptureFrameTexture = UTexture2D::CreateTransient(Size.X, Size.Y, pixelFormat);
581 CaptureFrameTexture->UpdateResource();
582 }
583
584 FrameGrabber = MakeShareable(new FFrameGrabber(SceneViewport.ToSharedRef(), Size, pixelFormat));
585 FrameGrabber->StartCapturingFrames();
586 }
587}
TEnumAsByte< ETextureRenderTargetFormat > TextureFormat
Definition: Camera.h:133

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

Referenced by SetupCamera().

Member Data Documentation

◆ CameraFrameRate

float ACamera::CameraFrameRate = 0.0f
private

Definition at line 350 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 262 of file Camera.h.

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

◆ CameraParameters

FCameraBaseParameters ACamera::CameraParameters
private

Current Camera parameters. If you wish to change Camera parameters, call ChangeCameraParameters() method.

Definition at line 330 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 277 of file Camera.h.

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

◆ CaptureRenderTarget

UTextureRenderTarget2D* ACamera::CaptureRenderTarget = nullptr
protected

Definition at line 267 of file Camera.h.

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

◆ FilePrefix

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

◆ FrameGrabber

TSharedPtr<FFrameGrabber> ACamera::FrameGrabber
private

FrameGrabber TSharedPtr

Definition at line 313 of file Camera.h.

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

◆ FrameRateTimer

float ACamera::FrameRateTimer = 0.0f
private

Definition at line 351 of file Camera.h.

Referenced by ShouldSimulate().

◆ GeoReferencingSystem

AGeoReferencingSystem* ACamera::GeoReferencingSystem = nullptr
private

Definition at line 335 of file Camera.h.

Referenced by CreateLogFile(), and SaveCameraMetaDataToDisk().

◆ IceMaterialInstance

TWeakObjectPtr<UMaterialInstanceDynamic> ACamera::IceMaterialInstance
protected

Definition at line 283 of file Camera.h.

Referenced by EndPlay(), and SetupCamera().

◆ ImageHeight

int ACamera::ImageHeight = 720
private

Definition at line 344 of file Camera.h.

Referenced by FrameGrabberCapture(), and SetupCamera().

◆ ImageMsg

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

Definition at line 341 of file Camera.h.

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

◆ ImageNumber

int ACamera::ImageNumber = 0
private

Definition at line 353 of file Camera.h.

Referenced by SaveImageToDisk().

◆ ImageWidth

int ACamera::ImageWidth = 1280
private

Definition at line 343 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 140 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 147 of file Camera.h.

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

◆ OnPostTickDelegate

FDelegateHandle ACamera::OnPostTickDelegate
protected

Definition at line 225 of file Camera.h.

Referenced by BeginPlay(), and EndPlay().

◆ OnPreTickDelegate

FDelegateHandle ACamera::OnPreTickDelegate
protected

Definition at line 222 of file Camera.h.

Referenced by BeginPlay(), and EndPlay().

◆ OnWindowClosedDelegate

FOnWindowClosed ACamera::OnWindowClosedDelegate
private

Definition at line 339 of file Camera.h.

Referenced by EndPlay(), and SetupCamera().

◆ ParametersChanged

bool ACamera::ParametersChanged = false
private

Definition at line 337 of file Camera.h.

◆ PhysicLensDistortion

TWeakObjectPtr<UMaterial> ACamera::PhysicLensDistortion
protected

Definition at line 285 of file Camera.h.

Referenced by SetupCamera().

◆ SaveCurrentFrameToDiskRequested

bool ACamera::SaveCurrentFrameToDiskRequested = false
private

Definition at line 346 of file Camera.h.

Referenced by FrameGrabberCapture().

◆ ShouldSimulateCamera

bool ACamera::ShouldSimulateCamera = true
private

Definition at line 348 of file Camera.h.

Referenced by FrameGrabberCapture(), and ShouldSimulate().

◆ TempParams

FCameraBaseParameters ACamera::TempParams
private

Definition at line 332 of file Camera.h.

◆ TextureFormat

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

public TEnumAsByte<ETextureRenderTargetFormat> variable BlueprintReadOnly.

Definition at line 133 of file Camera.h.

Referenced by StartFrameGrabber().

◆ TickEntry

FTickEntry ACamera::TickEntry
protected

Definition at line 281 of file Camera.h.

Referenced by BeginPlay(), and EndPlay().

◆ UnrealWindow

TSharedPtr<FUnrealWindow> ACamera::UnrealWindow
protected

◆ UseParallelLateTick

bool ACamera::UseParallelLateTick = true
protected

Definition at line 220 of file Camera.h.

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


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