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

#include <Lidar.h>

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

Public Member Functions

 ALidar (const FObjectInitializer &ObjectInitializer)
 
void Init (FLidarParameters parameters, bool SimulateSensor=true)
 
virtual ESensorTypes GetSensorType () const override
 
void ChangeLidarParameters (FLidarParameters newLidarParameters)
 
void SetVisualizeLidarParticles (bool Visualize)
 
void SetParticleLifeTime (float ParticleLifeTime)
 
FLidarParameters GetLidarParameters () const
 
UNiagaraComponent * GetNiagaraComponent () const
 
virtual FString GetParametersAsString () const override
 
void ForceClearContainers ()
 
void SaveCurrentPointCloudToDisk ()
 
- 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)
 

Protected Member Functions

virtual void BeginPlay () override
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
void CreateLogFile () override
 
void SaveLidarMetaDataToDisk (const FString &FileName)
 
- 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)
 

Private Member Functions

std::vector< FPointDataSimulateRaycastLidar (const float DeltaTime)
 
void SetNiagaraRendering (bool Enabled)
 
void VisualizeLidarParticles (std::vector< FPointData > HitPoints)
 
void ChangeParameters ()
 
FORCEINLINE bool ShootLaser (const UWorld *World, FHitResult &HitResult, const FVector &EndTrace, const FCollisionQueryParams &TraceParams, const FVector &LidarBodyLocation, const int32 Channel, const bool Semantic, const uint32 RGBDefault, const bool UseLidarNoiseModel)
 
void ResetRecordedHits (int32 MaxPointsPerChannel)
 
FORCEINLINE uint32 GetSemanticData (const FHitResult &HitResult) const
 
void SendData (const float DeltaTime)
 
bool CanSendData (const float DeltaTime)
 
void SendDataToTopic (const std::vector< FPointData > &points)
 
void SaveDataToDisk ()
 
void AddProcessingToHitResult (FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise, const bool UseSnowTerrainAdjustment)
 
void AddDistanceNoise (FHitResult &HitResult, const FVector &LidarBodyLocation)
 
void AddLateralNoise (FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise)
 
void AddSnowTerrainAdjustment (FHitResult &HitResult, const FVector &LidarBodyLocation)
 
void UpdateLidarParticles (int32 NumberOfHits, const TArray< FVector > &HitPoints, const TArray< FLinearColor > &Colors)
 
void OnWeatherChanged (FWeatherParameters WeatherParams)
 

Private Attributes

UNiagaraComponent * NiagaraComponent = nullptr
 
AGeoReferencingSystem * GeoReferencingSystem = nullptr
 
FLidarParameters LidarParameters
 
FLidarParameters TempLidarParameters
 
FWeatherParameters CurrentWeatherParameters
 
TMap< FName, FColor > SemanticColors
 
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
 
std::vector< std::vector< FPointData > > PreProcessedHitImpactPoints
 
std::vector< std::vector< FPointData > > Points
 
std::vector< FPointDataPointsFlattened
 
std::vector< float > LaserAngles
 
std::random_device RandomDevice
 
std::mt19937 Generator
 
bool NeedToSavePointCloudWithoutNoise = false
 
bool LidarParametersChanged = false
 
bool SendDataEveryFrame = false
 
const FName TerrainTag = "Terrain"
 
float CurrentHorizontalAngle = 0.0f
 
float SensorHzFrequency = 0.1f
 
float SensorHzTimer = 0.0f
 
float SnowHeightOffset = 0.0f
 
int32 LidarSaves = 0
 
uint32 CachedNoneColor
 
uint32 CachedSnowflakeColor
 
bool SaveCurrentPointCloudToDiskRequested = false
 
bool ClearContainers = true
 

Friends

class ALidarManager
 

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 ()
 
- Public Attributes inherited from ASensor
FSensorDestroy OnSensorDestroy
 
FString AttachedToComponent
 
FName AttachedToBone
 
- Static Protected Member Functions inherited from ASensor
template<typename InStructType >
static FString StructToString (const InStructType &InStruct)
 
- Protected Attributes inherited from ASensor
UTopic * ROSTopic = nullptr
 
bool SendDataToROS = true
 
ULogFileLogFile = nullptr
 
AActor * ParentActor = nullptr
 
FString FileSavePath
 
UROSIntegrationGameInstance * ROSInstance = nullptr
 
- 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

Parameterized linetrace based Lidar sensor. Parameters defined in FLidarParameters struct. This Sensor Actor is ticked by LidarManager where all added Lidar sensors are ticked in parallel.

Definition at line 34 of file Lidar.h.

Constructor & Destructor Documentation

◆ ALidar()

ALidar::ALidar ( const FObjectInitializer &  ObjectInitializer)

Definition at line 34 of file Lidar.cpp.

34 : Super(ObjectInitializer)
35{
36 // Lidar sensors are ticked by LidarManager.cpp
37 PrimaryActorTick.bCanEverTick = false;
38}

Member Function Documentation

◆ AddDistanceNoise()

void ALidar::AddDistanceNoise ( FHitResult &  HitResult,
const FVector &  LidarBodyLocation 
)
private

Definition at line 390 of file Lidar.cpp.

391{
392 std::normal_distribution<float> Distribution(0.0f, LidarParameters.DistanceNoiseStdDev);
393 float NoiseValue = Distribution(Generator);
394 const FVector DirectionToSensor = ((LidarBodyLocation * 1e-2) - HitResult.ImpactPoint).GetSafeNormal();
395 const FVector Noise = DirectionToSensor * NoiseValue;
396 HitResult.ImpactPoint += Noise;
397}
std::mt19937 Generator
Definition: Lidar.h:276
FLidarParameters LidarParameters
Definition: Lidar.h:257

References FLidarParameters::DistanceNoiseStdDev, Generator, and LidarParameters.

Referenced by AddProcessingToHitResult().

◆ AddLateralNoise()

void ALidar::AddLateralNoise ( FHitResult &  HitResult,
const FVector &  LidarBodyLocation,
const bool  UseHorizontalNoise 
)
private

Definition at line 399 of file Lidar.cpp.

400{
401 const FVector ForwardVector = (HitResult.ImpactPoint - LidarBodyLocation).GetSafeNormal();
402 const FVector RightVector = FVector::CrossProduct(ForwardVector, FVector::UpVector).GetSafeNormal();
403
404 FVector ChosenDirection;
405 if (UseHorizontalNoise)
406 {
407 ChosenDirection = RightVector;
408 }
409 else
410 {
411 FVector UpVector = FVector::CrossProduct(ForwardVector, RightVector).GetSafeNormal();
412 ChosenDirection = UpVector;
413 }
414
415 std::normal_distribution<float> Distribution(0.0f, LidarParameters.LateralNoiseStdDev);
416 const float NoiseValue = Distribution(Generator);
417
418 HitResult.ImpactPoint += ChosenDirection * NoiseValue;
419}

References Generator, FLidarParameters::LateralNoiseStdDev, and LidarParameters.

Referenced by AddProcessingToHitResult().

◆ AddProcessingToHitResult()

void ALidar::AddProcessingToHitResult ( FHitResult &  HitResult,
const FVector &  LidarBodyLocation,
const bool  UseHorizontalNoise,
const bool  UseSnowTerrainAdjustment 
)
private

Definition at line 372 of file Lidar.cpp.

373{
374 if (UseSnowTerrainAdjustment)
375 {
376 AddSnowTerrainAdjustment(HitResult, LidarBodyLocation);
377 }
378
380 {
381 AddDistanceNoise(HitResult, LidarBodyLocation);
382 }
383
385 {
386 AddLateralNoise(HitResult, LidarBodyLocation, UseHorizontalNoise);
387 }
388}
void AddLateralNoise(FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise)
Definition: Lidar.cpp:399
void AddDistanceNoise(FHitResult &HitResult, const FVector &LidarBodyLocation)
Definition: Lidar.cpp:390
void AddSnowTerrainAdjustment(FHitResult &HitResult, const FVector &LidarBodyLocation)
Definition: Lidar.cpp:421

References AddDistanceNoise(), AddLateralNoise(), AddSnowTerrainAdjustment(), FLidarParameters::DistanceNoiseStdDev, FLidarParameters::LateralNoiseStdDev, and LidarParameters.

Referenced by SimulateRaycastLidar().

◆ AddSnowTerrainAdjustment()

void ALidar::AddSnowTerrainAdjustment ( FHitResult &  HitResult,
const FVector &  LidarBodyLocation 
)
private

Definition at line 421 of file Lidar.cpp.

422{
423 AActor* HitActor = HitResult.GetActor();
424
425 // Terrain should have tag "Terrain" in order to make this work.
426 if (HitActor && HitActor->Tags.Contains(TerrainTag))
427 {
428 // Scale the Z value of ImpactPoint based on SnowHeightOffset.
429 HitResult.ImpactPoint.Z += SnowHeightOffset;
430 }
431}
const FName TerrainTag
Definition: Lidar.h:282
float SnowHeightOffset
Definition: Lidar.h:288

References SnowHeightOffset, and TerrainTag.

Referenced by AddProcessingToHitResult().

◆ BeginPlay()

void ALidar::BeginPlay ( )
overrideprotectedvirtual

Reimplemented from ASensor.

Definition at line 56 of file Lidar.cpp.

57{
58 Super::BeginPlay();
59
60 UWorld* World = GetWorld();
61
62 // Create the SemanticColors TMap
63 TMap<FString, FColor> Colors = GetSemanticColors();
64 for (const auto& ColorEntry : Colors)
65 {
66 FName SemanticName = FName(*ColorEntry.Key);
67 SemanticColors.Add(SemanticName, ColorEntry.Value);
68 }
69
70 // Cache "None" and "Snowflake" colors for Semantic
71 FColor NoneColor = SemanticColors.FindRef("None");
72 FColor SnowflakeColor = SemanticColors.FindRef("Snowflake");
73 CachedNoneColor = (NoneColor.R << 16) | (NoneColor.G << 8) | (NoneColor.B << 0);
74 CachedSnowflakeColor = (SnowflakeColor.R << 16) | (SnowflakeColor.G << 8) | (SnowflakeColor.B << 0);
75
76 // Add this lidar to LidarManager that handles ticking of this sensor in parallel.
78 if (LidarManager)
79 {
80 LidarManager->AddRaycastLidar(this);
81 }
82
84 if (Weather)
85 {
87 Weather->OnWeatherChanged.AddUniqueDynamic(this, &ALidar::OnWeatherChanged);
88 }
89
90 // Load pointcloud Niagara particle system
91 UNiagaraSystem* NS = LoadObject<UNiagaraSystem>(nullptr, TEXT("/Game/Agrarsense/Particles/PointCloud/NS_PointCloudSemanticFast"), nullptr, LOAD_None, nullptr);
92 if (NS)
93 {
94 NiagaraComponent = UNiagaraFunctionLibrary::SpawnSystemAtLocation(World, NS, GetActorLocation());
96 {
97 // Hide this NiagaraComponent for all Camera sensors.
98 HideComponentForAllCameras(Cast<UPrimitiveComponent>(NiagaraComponent));
99
100 NiagaraComponent->SetAffectDynamicIndirectLighting(false);
101 NiagaraComponent->SetAffectDistanceFieldLighting(false);
102 NiagaraComponent->SetCastContactShadow(false);
103 NiagaraComponent->SetCastShadow(false);
104
106 }
107 }
108#if WITH_EDITOR
109 else
110 {
111 UE_LOG(LogTemp, Warning, TEXT("Lidar.cpp: Couldn't find Niagara particle system."));
112 }
113#endif
114}
void AddRaycastLidar(ALidar *lidarPtr)
UNiagaraComponent * NiagaraComponent
Definition: Lidar.h:148
TMap< FName, FColor > SemanticColors
Definition: Lidar.h:264
FWeatherParameters CurrentWeatherParameters
Definition: Lidar.h:261
uint32 CachedSnowflakeColor
Definition: Lidar.h:294
void SetParticleLifeTime(float ParticleLifeTime)
Definition: Lidar.cpp:239
void OnWeatherChanged(FWeatherParameters WeatherParams)
Definition: Lidar.cpp:153
uint32 CachedNoneColor
Definition: Lidar.h:292
static void HideComponentForAllCameras(UPrimitiveComponent *PrimitiveComponent)
Definition: Sensor.cpp:307
static TMap< FString, FColor > GetSemanticColors()
Definition: Sensor.cpp:317
const FWeatherParameters & GetCurrentWeather() const
Definition: Weather.h:76
FLevelEventDelegate_WeatherChanged OnWeatherChanged
Definition: Weather.h:91
static AWeather * GetWeatherActor(const UObject *WorldContextObject)
static ALidarManager * GetLidarManager(const UObject *WorldContextObject)

References ALidarManager::AddRaycastLidar(), CachedNoneColor, CachedSnowflakeColor, CurrentWeatherParameters, AWeather::GetCurrentWeather(), UAgrarsenseStatics::GetLidarManager(), ASensor::GetSemanticColors(), UAgrarsenseStatics::GetWeatherActor(), ASensor::HideComponentForAllCameras(), NiagaraComponent, OnWeatherChanged(), AWeather::OnWeatherChanged, SemanticColors, and SetParticleLifeTime().

◆ CanSendData()

bool ALidar::CanSendData ( const float  DeltaTime)
private

Checks can sensor send data in this tick

Definition at line 526 of file Lidar.cpp.

527{
529 {
530 ClearContainers = true;
531 return true;
532 }
533
534 SensorHzTimer += DeltaTime;
536 {
537 SensorHzTimer = 0.0f;
538 ClearContainers = true;
539 return true;
540 }
541 else
542 {
543 ClearContainers = false;
544 return false;
545 }
546}
float SensorHzFrequency
Definition: Lidar.h:285
bool ClearContainers
Definition: Lidar.h:298
bool SendDataEveryFrame
Definition: Lidar.h:280
float SensorHzTimer
Definition: Lidar.h:286

References ClearContainers, SendDataEveryFrame, SensorHzFrequency, and SensorHzTimer.

Referenced by SendData().

◆ ChangeLidarParameters()

void ALidar::ChangeLidarParameters ( FLidarParameters  newLidarParameters)

Change Lidar parameter for this sensor.

Parameters
newLidarParametersFLidarParameters struct

Definition at line 548 of file Lidar.cpp.

549{
550 if (!CanSimulateSensor())
551 {
552 // We are not currently simulating sensor, we can safely change parameters here
553 LidarParameters = newLidarParameters;
555 }
556 else
557 {
558 // Change parameters at the end of the frame
559 TempLidarParameters = newLidarParameters;
561 }
562}
bool LidarParametersChanged
Definition: Lidar.h:279
void ChangeParameters()
Definition: Lidar.cpp:165
FLidarParameters TempLidarParameters
Definition: Lidar.h:259
bool CanSimulateSensor() const
Definition: Sensor.h:170

References ASensor::CanSimulateSensor(), ChangeParameters(), LidarParameters, LidarParametersChanged, and TempLidarParameters.

◆ ChangeParameters()

void ALidar::ChangeParameters ( )
private

Change this Lidar sensor parameters

Definition at line 165 of file Lidar.cpp.

166{
167 // Ensure certain parameters are valid ranges
168 LidarParameters.HorizontalFov = FMath::Clamp(LidarParameters.HorizontalFov, 0.1f, 360.0f);
172
173 const int32 NumberOfLasers = LidarParameters.Channels;
174
175 // Resize arrays
176 PreProcessedHitImpactPoints.resize(NumberOfLasers);
177 Points.resize(NumberOfLasers);
178
179 // Create Lidar linetrace angles
180 LaserAngles.clear();
181 const float DeltaAngle = NumberOfLasers == 1u ? 0.f : (LidarParameters.UpperFovLimit - LidarParameters.LowerFovLimit) / static_cast<float>(NumberOfLasers - 1);
182
183 for (int32 i = 0; i < NumberOfLasers; ++i)
184 {
185 const float VerticalAngle = LidarParameters.UpperFovLimit - static_cast<float>(i) * DeltaAngle;
186 LaserAngles.emplace_back(VerticalAngle);
187 }
188
192
193 if (LidarParameters.PointsPerSecond > 1000000)
194 {
195 SimulatorLog::Log("Lidar sensor: It's highly advisable to turn off VisualizePointcloud when PointsPerSecond exceed 1 million.");
196
197 if (LidarParameters.PointsPerSecond > 2000000)
198 {
200 SimulatorLog::Log("Lidar sensor: VisualizePointcloud has been set to false due PointsPerSecond exceeding 2 million.");
201 }
202 }
203
206}
std::vector< std::vector< FPointData > > PreProcessedHitImpactPoints
Definition: Lidar.h:268
std::vector< float > LaserAngles
Definition: Lidar.h:273
std::vector< std::vector< FPointData > > Points
Definition: Lidar.h:270
void SetVisualizeLidarParticles(bool Visualize)
Definition: Lidar.cpp:208
bool SendDataToROS
Definition: Sensor.h:364
virtual void CreateROSTopic()
Definition: Sensor.cpp:190
static void Log(const FString &Message, bool LogToTextFile=true, bool LogToROS=true)
bool SendDataAtRotationFrequency

References FLidarParameters::Channels, ASensor::CreateROSTopic(), FLidarParameters::DistanceNoiseStdDev, FLidarParameters::HorizontalFov, LaserAngles, FLidarParameters::LateralNoiseStdDev, LidarParameters, SimulatorLog::Log(), FLidarParameters::LowerFovLimit, Points, FLidarParameters::PointsPerSecond, PreProcessedHitImpactPoints, FLidarParameters::RotationFrequency, FLidarParameters::SendDataAtRotationFrequency, SendDataEveryFrame, FLidarParameters::SendDataToROS, ASensor::SendDataToROS, SensorHzFrequency, SetVisualizeLidarParticles(), FLidarParameters::UpperFovLimit, and FLidarParameters::VisualizePointcloud.

Referenced by ChangeLidarParameters(), Init(), and SimulateRaycastLidar().

◆ CreateLogFile()

void ALidar::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 751 of file Lidar.cpp.

752{
753 if (IsValid(LogFile))
754 {
755 // File has already been created, return
756 return;
757 }
758
759 FLogFileSettings Settings;
762 Settings.QueueLength = MAX_int32; // Only write the log after destroying the sensor
763 Settings.KeepFileOpen = false;
764 Settings.Timestamp = false;
765 Settings.OverrideFilePath = true;
766 Settings.FilePath = FileSavePath;
767
768 LogFile = NewObject<ULogFile>(ULogFile::StaticClass());
769 if (IsValid(LogFile))
770 {
771 FString FileName = "lidar_metadata";
772 LogFile->Create(FileName, Settings);
773
774 // Write camera metadata first line to explain the values.
775 GeoReferencingSystem = AGeoReferencingSystem::GetGeoReferencingSystem(GetWorld());
777 {
778 WriteToLogFile("timestamp, pointcloud_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation, GPS latitude, GPS longitude, GPS altitude");
779 }
780 else
781 {
782 WriteToLogFile("timestamp, pointcloud_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation");
783 }
784 }
785}
AGeoReferencingSystem * GeoReferencingSystem
Definition: Lidar.h:254
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 Init().

◆ EndPlay()

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

Reimplemented from ASensor.

Definition at line 116 of file Lidar.cpp.

117{
118 Super::EndPlay(EndPlayReason);
119
120 UWorld* World = GetWorld();
121
122 // Remove this lidar from LidarManager
124 if (LidarManager)
125 {
126 LidarManager->RemoveRaycastLidar(this);
127 }
128
129 // Unbind from Weather changed event
131 if (Weather)
132 {
133 Weather->OnWeatherChanged.RemoveDynamic(this, &ALidar::OnWeatherChanged);
134 }
135
137 {
138 SetNiagaraRendering(false);
139
140 // Destroy component
141 NiagaraComponent->UnregisterComponent();
142 NiagaraComponent->DestroyComponent();
143 NiagaraComponent = nullptr;
144 }
145
146 PointCloudMessage.Reset();
148 PointsFlattened.clear();
149 LaserAngles.clear();
150 Points.clear();
151}
void RemoveRaycastLidar(ALidar *lidarPtr)
void SetNiagaraRendering(bool Enabled)
Definition: Lidar.cpp:213
std::vector< FPointData > PointsFlattened
Definition: Lidar.h:271
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: Lidar.h:266

References UAgrarsenseStatics::GetLidarManager(), UAgrarsenseStatics::GetWeatherActor(), LaserAngles, NiagaraComponent, OnWeatherChanged(), AWeather::OnWeatherChanged, PointCloudMessage, Points, PointsFlattened, PreProcessedHitImpactPoints, ALidarManager::RemoveRaycastLidar(), and SetNiagaraRendering().

◆ ForceClearContainers()

void ALidar::ForceClearContainers ( )
inline

Definition at line 110 of file Lidar.h.

111 {
112 ClearContainers = true;
113 }

Referenced by ADataCapture::UpdatePositions().

◆ GetLidarParameters()

FLidarParameters ALidar::GetLidarParameters ( ) const
inline

Get current Lidar parameters

Returns
FLidarParameters struct

Definition at line 83 of file Lidar.h.

84 {
85 return LidarParameters;
86 }

Referenced by USimulatorJsonExporter::ExportSensorToJSON().

◆ GetNiagaraComponent()

UNiagaraComponent * ALidar::GetNiagaraComponent ( ) const
inline

Retrieves the Niagara component associated with this sensor.

Returns
A pointer to the UNiagaraComponent instance associated with this sensor.

Definition at line 93 of file Lidar.h.

94 {
95 return NiagaraComponent;
96 }

◆ GetParametersAsString()

virtual FString ALidar::GetParametersAsString ( ) const
inlineoverridevirtual

Get current LidarParameters struct fields as one string.

Reimplemented from ASensor.

Definition at line 101 of file Lidar.h.

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

◆ GetSemanticData()

uint32 ALidar::GetSemanticData ( const FHitResult &  HitResult) const
private

Retrieve semantic data based on the object hit by the line trace.

Parameters
HitResultThe result of the line trace indicating the object hit.
Returns
The semantic data associated with the hit object.

Definition at line 564 of file Lidar.cpp.

565{
566 auto* HitComponent = HitResult.Component.Get();
567
568 if (HitComponent)
569 {
570 TArray<FName>& CompTags = HitComponent->ComponentTags;
571 if (!CompTags.IsEmpty())
572 {
573 FName Tag = CompTags[0]; // First component tag should be the tag we want.
574 FColor Color = SemanticColors.FindRef(Tag);
575 return (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
576 }
577 else
578 {
579 return CachedNoneColor;
580 }
581 }
582 else
583 {
585 }
586}

References CachedNoneColor, CachedSnowflakeColor, and SemanticColors.

Referenced by ShootLaser(), and SimulateRaycastLidar().

◆ GetSensorType()

virtual ESensorTypes ALidar::GetSensorType ( ) const
inlineoverridevirtual

Get type of the sensor

Returns
Sensor's type

Reimplemented from ASensor.

Definition at line 52 of file Lidar.h.

53 {
55 }

References Lidar.

◆ Init()

void ALidar::Init ( FLidarParameters  parameters,
bool  SimulateSensor = true 
)

Initialize new Lidar sensor

Parameters
parametersFLidarParameters struct

Definition at line 40 of file Lidar.cpp.

41{
42 LidarParameters = parameters;
43 SetSimulateSensor(SimulateSensor);
47
48 // Initialize PointCloudMessage
49 PointCloudMessage.Reset();
50 PointCloudMessage = MakeShared<ROSMessages::sensor_msgs::PointCloud2>();
51 PointCloudMessage->CreateDefaultPointCloud2Message();
52
53 Generator.seed(RandomDevice());
54}
std::random_device RandomDevice
Definition: Lidar.h:275
void CreateLogFile() override
Definition: Lidar.cpp:751
virtual void CreateDataSavePath()
Definition: Sensor.cpp:246
void SetSimulateSensor(bool SimulateSensor)
Definition: Sensor.h:160

References ChangeParameters(), ASensor::CreateDataSavePath(), CreateLogFile(), Generator, LidarParameters, PointCloudMessage, RandomDevice, and ASensor::SetSimulateSensor().

Referenced by USensorFactory::SpawnLidarSensor().

◆ OnWeatherChanged()

void ALidar::OnWeatherChanged ( FWeatherParameters  WeatherParams)
private

Definition at line 153 of file Lidar.cpp.

154{
155 CurrentWeatherParameters = WeatherParams;
156
157 // Here we recalculate SnowHeightOffset when Weather changes.
158 // This is fine-tuned by hand. If the Snow implementation would change meaningfully,
159 // we would need to change this implementation as well.
160 // See AddSnowTerrainAdjustment() function how SnowHeightOffset is used.
162 SnowHeightOffset *= 1e-2;
163}

References CurrentWeatherParameters, FWeatherParameters::SnowAmount, and SnowHeightOffset.

Referenced by BeginPlay(), and EndPlay().

◆ ResetRecordedHits()

void ALidar::ResetRecordedHits ( int32  MaxPointsPerChannel)
private

Reset and possibly re-allocate needed arrays.

Definition at line 649 of file Lidar.cpp.

650{
651 if (!ClearContainers)
652 {
653 return;
654 }
655
656 // Visualize Lidar particles on main thread because,
657 // in some instances NiagaraComponent crashes when updating points from background thread.
658 std::vector<FPointData> CopiedPoints = PointsFlattened;
659 AsyncTask(ENamedThreads::GameThread, [this, CopiedPoints]()
660 {
661 VisualizeLidarParticles(CopiedPoints);
662 });
663
665 {
666 // If we only send data at Lidar sensor rotation frequency
667 // reserve enough points to fill all points
669 }
670
671 // Clear all containers
673 {
674 for (std::vector<FPointData>& ImpactPoints : PreProcessedHitImpactPoints)
675 {
676 ImpactPoints.clear();
677 ImpactPoints.reserve(MaxPointsPerChannel);
678 }
679 }
680
681 for (std::vector<FPointData>& ImpactPoints : Points)
682 {
683 ImpactPoints.clear();
684 ImpactPoints.reserve(MaxPointsPerChannel);
685 }
686
687 PointsFlattened.clear();
688}
void VisualizeLidarParticles(std::vector< FPointData > HitPoints)
Definition: Lidar.cpp:433
bool SavePointcloudWithoutNoiseModel

References FLidarParameters::Channels, ClearContainers, LidarParameters, Points, PointsFlattened, FLidarParameters::PointsPerSecond, PreProcessedHitImpactPoints, FLidarParameters::SavePointcloudWithoutNoiseModel, SendDataEveryFrame, and VisualizeLidarParticles().

Referenced by SimulateRaycastLidar().

◆ SaveCurrentPointCloudToDisk()

void ALidar::SaveCurrentPointCloudToDisk ( )
inline

Definition at line 118 of file Lidar.h.

119 {
121 }
bool SaveCurrentPointCloudToDiskRequested
Definition: Lidar.h:296

Referenced by ADataCapture::CaptureDataNow().

◆ SaveDataToDisk()

void ALidar::SaveDataToDisk ( )
private

Definition at line 713 of file Lidar.cpp.

714{
715 if (PointsFlattened.size() == 0)
716 {
717 return;
718 }
719
720 // Save point cloud to disk
721 FString Filename = FString::Printf(TEXT("%sLidar_%d.ply"), *FileSavePath, LidarSaves);
723 SaveLidarMetaDataToDisk(Filename);
724
726 {
727 // Flatten 2D std::vector to 1D std::vector
728 std::vector<FPointData> PointsWithOutNoiseModel;
729
730 size_t totalSize = 0;
731 for (const std::vector<FPointData>& Vec : PreProcessedHitImpactPoints)
732 {
733 totalSize += Vec.size();
734 }
735 PointsWithOutNoiseModel.reserve(totalSize);
736
737 for (const std::vector<FPointData>& Vec : PreProcessedHitImpactPoints)
738 {
739 PointsWithOutNoiseModel.insert(PointsWithOutNoiseModel.end(), Vec.begin(), Vec.end());
740 }
741
742 // Save pointcloud to disk without any noise
743 FString PreprocessedFilename = FString::Printf(TEXT("%sLidar_%d_without_noise_model.ply"), *FileSavePath, LidarSaves);
744 UPointcloudUtilities::SaveVectorArrayAsPlyAsync(PreprocessedFilename, PointsWithOutNoiseModel);
745 SaveLidarMetaDataToDisk(PreprocessedFilename);
746 }
747
748 ++LidarSaves;
749}
void SaveLidarMetaDataToDisk(const FString &FileName)
Definition: Lidar.cpp:787
int32 LidarSaves
Definition: Lidar.h:290
bool NeedToSavePointCloudWithoutNoise
Definition: Lidar.h:278
static void SaveVectorArrayAsPlyAsync(FString FullFileName, const std::vector< FPointData > points)

References ASensor::FileSavePath, LidarSaves, NeedToSavePointCloudWithoutNoise, PointsFlattened, PreProcessedHitImpactPoints, SaveLidarMetaDataToDisk(), and UPointcloudUtilities::SaveVectorArrayAsPlyAsync().

Referenced by SendData().

◆ SaveLidarMetaDataToDisk()

void ALidar::SaveLidarMetaDataToDisk ( const FString &  FileName)
protected

Definition at line 787 of file Lidar.cpp.

788{
789 if (!IsValid(LogFile))
790 {
791 // If the log file located in base class is not valid, return here.
792 return;
793 }
794
795 const FVector ActorPosition = GetActorLocation();
796 const FRotator ActorRotation = GetActorRotation();
797
798 FString MetaData;
799
800 FString TimeStamp = CreateTimeStampString();
801
803 {
804 FGeographicCoordinates GeoCoordinates = UCoordinateConversionUtilities::UnrealToGeographicCoordinates(GeoReferencingSystem, ActorPosition);
805 MetaData = FString::Printf(TEXT("%s, %s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f, %.8f, %.8f, %.8f"),
806 *TimeStamp, *FileName,
807 ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
808 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll,
809 GeoCoordinates.Latitude, GeoCoordinates.Longitude, GeoCoordinates.Altitude);
810 }
811 else
812 {
813 MetaData = FString::Printf(TEXT("%s, %s, %.2f, %.2f, %.2f, %.2f, %.2f, %.2f"),
814 *TimeStamp, *FileName,
815 ActorPosition.X, ActorPosition.Y, ActorPosition.Z,
816 ActorRotation.Pitch, ActorRotation.Yaw, ActorRotation.Roll);
817 }
818
819 // Write to the log file (this is written after sensor is destroyed)
820 WriteToLogFile(MetaData);
821}
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 SaveDataToDisk().

◆ SendData()

void ALidar::SendData ( const float  DeltaTime)
private

Send data to topics and save point cloud to disk if that's enabled. Before sending and saving, CanSendData is checked.

Definition at line 490 of file Lidar.cpp.

491{
492 if (!CanSendData(DeltaTime))
493 {
494 return;
495 }
496
497 // Preallocate PointsFlattened size
498 // and fill PointsFlattened
499 size_t TotalSize = 0;
500 for (const std::vector<FPointData>& Vec : Points)
501 {
502 TotalSize += Vec.size();
503 }
504 PointsFlattened.reserve(TotalSize);
505
506 for (std::vector<FPointData>& HitPoints : Points)
507 {
508 PointsFlattened.insert(PointsFlattened.end(), std::make_move_iterator(HitPoints.begin()), std::make_move_iterator(HitPoints.end()));
509 }
510
512 {
514
517 }
518 }
519
520 if (SendDataToROS)
521 {
523 }
524}
bool CanSendData(const float DeltaTime)
Definition: Lidar.cpp:526
void SaveDataToDisk()
Definition: Lidar.cpp:713
void SendDataToTopic(const std::vector< FPointData > &points)
Definition: Lidar.cpp:690

References CanSendData(), LidarParameters, Points, PointsFlattened, SaveCurrentPointCloudToDiskRequested, SaveDataToDisk(), FLidarParameters::SaveDataToDisk, ASensor::SendDataToROS, and SendDataToTopic().

Referenced by SimulateRaycastLidar().

◆ SendDataToTopic()

void ALidar::SendDataToTopic ( const std::vector< FPointData > &  points)
private

Definition at line 690 of file Lidar.cpp.

691{
692 UTopic* Topic = GetROSTopic();
693
694 if (!IsROSConnected()
695 || !Topic
696 || !SendDataToROS
697 || !PointCloudMessage.IsValid()
698 || points.empty())
699 {
700 return;
701 }
702
703 const size_t PointsSize = points.size();
704 const size_t DataSize = PointsSize * sizeof(FPointData);
705
706 PointCloudMessage->width = static_cast<uint32>(PointsSize);
707 PointCloudMessage->row_step = static_cast<uint32>(DataSize);
708 PointCloudMessage->data_ptr = reinterpret_cast<uint8*>(const_cast<FPointData*>(points.data()));
709 PointCloudMessage->header.time = FROSTime::Now();
710 Topic->Publish(PointCloudMessage);
711}
UTopic * GetROSTopic() const
Definition: Sensor.h:150
FORCEINLINE bool IsROSConnected() const
Definition: Sensor.h:201

References ASensor::GetROSTopic(), ASensor::IsROSConnected(), PointCloudMessage, and ASensor::SendDataToROS.

Referenced by SendData().

◆ SetNiagaraRendering()

void ALidar::SetNiagaraRendering ( bool  Enabled)
private

Set Niagara component rendering on/off

Parameters
bEnabledboolean to set Niagara rendering on/off

Definition at line 213 of file Lidar.cpp.

214{
216 {
217 if (!Enabled)
218 {
219 TArray<FVector> EmptyHitpoints;
220 TArray<FLinearColor> EmptyColors;
221 UpdateLidarParticles(0, EmptyHitpoints, EmptyColors);
222 }
223
224 NiagaraComponent->SetRenderingEnabled(Enabled);
225 }
226}
void UpdateLidarParticles(int32 NumberOfHits, const TArray< FVector > &HitPoints, const TArray< FLinearColor > &Colors)
Definition: Lidar.cpp:228

References NiagaraComponent, and UpdateLidarParticles().

Referenced by EndPlay(), and SetVisualizeLidarParticles().

◆ SetParticleLifeTime()

void ALidar::SetParticleLifeTime ( float  ParticleLifeTime)

Set Niagara particle lifetime (default 2 seconds)

Parameters
particleLifeTimenew lifetime as float

Definition at line 239 of file Lidar.cpp.

240{
242 {
243 NiagaraComponent->SetVariableFloat(FName("User.LifeTime"), ParticleLifeTime);
244 }
245}

References NiagaraComponent.

Referenced by BeginPlay().

◆ SetVisualizeLidarParticles()

void ALidar::SetVisualizeLidarParticles ( bool  Visualize)

Set boolean whether Lidar sensors be visualized

Parameters
bVisualizeboolean to set visualization on/off

Definition at line 208 of file Lidar.cpp.

209{
210 SetNiagaraRendering(Visualize);
211}

References SetNiagaraRendering().

Referenced by ChangeParameters().

◆ ShootLaser()

bool ALidar::ShootLaser ( const UWorld *  World,
FHitResult &  HitResult,
const FVector &  EndTrace,
const FCollisionQueryParams &  TraceParams,
const FVector &  LidarBodyLocation,
const int32  Channel,
const bool  Semantic,
const uint32  RGBDefault,
const bool  UseLidarNoiseModel 
)
private

This function calculates the impact point of the laser shot based on provided parameters, considering the specified vertical and horizontal angles, collision parameters, Lidar body location, Lidar body rotation, and the specified range.

Returns
true if the laser shot hits a valid target, false otherwise.

Definition at line 588 of file Lidar.cpp.

590{
591#ifdef ParallelLineTraceSingleByChannel_EXISTS
592 // Defined and implemented in our AGRARSENSE Unreal Engine fork
593 // This LineTrace method doesn't block the physics scene which improves linetrace performance.
594 World->ParallelLineTraceSingleByChannel(
595 HitResult,
596 LidarBodyLocation,
597 EndTrace,
598 ECC_GameTraceChannel3,
599 TraceParams,
600 FCollisionResponseParams::DefaultResponseParam);
601#else
602 // If not using our fork of the engine, use default LineTrace method.
603 World->LineTraceSingleByChannel(
604 HitResult,
605 LidarBodyLocation,
606 EndTrace,
607 ECC_GameTraceChannel3,
608 TraceParams,
609 FCollisionResponseParams::DefaultResponseParam);
610#endif
611
612 bool BlockingHit = HitResult.IsValidBlockingHit();
613 if (!BlockingHit && !UseLidarNoiseModel)
614 {
615 return false;
616 }
617
618 // Scale the pointcloud
619 HitResult.ImpactPoint *= 1e-2;
620
621 // Flip Y axis
622 HitResult.ImpactPoint.Y *= -1;
623
625 {
626 // Save Original FHitResult to separate array
627 FHitResult OriginalHitResultCopy = HitResult;
628 uint32 RGB = RGBDefault;
629 if (Semantic)
630 {
631 // If Lidar is set to Semantic, set point color
632 RGB = GetSemanticData(OriginalHitResultCopy);
633 }
634 const FVector& HitPoint = OriginalHitResultCopy.ImpactPoint;
635 FPointData point = { HitPoint.X, HitPoint.Y, HitPoint.Z, RGB };
636 PreProcessedHitImpactPoints[Channel].emplace_back(point);
637 }
638
639 if (UseLidarNoiseModel)
640 {
641 // Check whether we "hit" snowflake by using LUAS formula
642 bool HitSnowFlake = LidarNoiseModel::CheckSnowflakeHit(HitResult, EndTrace, LidarBodyLocation, CurrentWeatherParameters);
643 BlockingHit = HitResult.bBlockingHit || HitSnowFlake;
644 }
645
646 return BlockingHit;
647}
FORCEINLINE uint32 GetSemanticData(const FHitResult &HitResult) const
Definition: Lidar.cpp:564
static bool CheckSnowflakeHit(FHitResult &HitInfo, const FVector EndTrace, const FVector LidarLocation, const FWeatherParameters &WeatherParameters)
float X
Definition: PointData.h:15

References LidarNoiseModel::CheckSnowflakeHit(), CurrentWeatherParameters, GetSemanticData(), NeedToSavePointCloudWithoutNoise, PreProcessedHitImpactPoints, and FPointData::X.

Referenced by SimulateRaycastLidar().

◆ SimulateRaycastLidar()

std::vector< FPointData > ALidar::SimulateRaycastLidar ( const float  DeltaTime)
private

Simulate this Lidar sensor. Should only be called by LidarManager.

Parameters
DeltaTimecurrent DeltaTime

Definition at line 247 of file Lidar.cpp.

248{
249 TRACE_CPUPROFILER_EVENT_SCOPE(ALidar::SimulateRaycastLidar);
250
251 std::vector<FPointData> HitPoints;
252
253 if (!CanSimulateSensor())
254 {
255 return HitPoints;
256 }
257
258 // Get sensor position and rotation
259 const FTransform& ActorTransform = GetTransform();
260 const FVector LidarBodyLocation = ActorTransform.GetLocation();
261 const FRotator LidarBodyRotation = ActorTransform.Rotator();
262 const FMatrix LidarRotationMatrix = FRotationMatrix(FQuat(LidarBodyRotation).Rotator());
263
264 // Prepare needed variables for processing
265 const int32 ChannelCount = LidarParameters.Channels;
266 const int32 PointsToScanWithOneChannel = FMath::RoundHalfFromZero(LidarParameters.PointsPerSecond * DeltaTime / float(ChannelCount));
267 const float HorizontalAngle = CurrentHorizontalAngle;
268 const float AngleDistanceOfTick = LidarParameters.RotationFrequency * LidarParameters.HorizontalFov * DeltaTime;
269 const float AngleDistanceOfLaserMeasure = AngleDistanceOfTick / PointsToScanWithOneChannel;
270 const float Range = LidarParameters.Range * 100; // to meters
271
272 const FColor Color = FColor(255, 255, 255);
273 const int32 RgbDefault = (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
274
275 FCollisionQueryParams TraceParams = FCollisionQueryParams(FName(TEXT("Laser_Trace")), true, this);
276 TraceParams.bReturnPhysicalMaterial = false;
277 TraceParams.bReturnFaceIndex = false;
278
279 // Note. can become very expensive with high vertice meshes.
280 // Any very high vertice mesh should have simpler collision mesh (Tree for example)
281 TraceParams.bTraceComplex = LidarParameters.UseComplexCollisionTrace;
282
283 // Check if we are going to add any noise
287
288 // Check if separate point cloud should be saved without the noise
289 NeedToSavePointCloudWithoutNoise = ShouldAddNoise
292
293 const bool Semantic = LidarParameters.Semantic;
295 const bool NeedsExtraProcessing = UseSnowTerrainAdjustment || LidarParameters.DistanceNoiseStdDev > 0.0f || LidarParameters.LateralNoiseStdDev > 0.0f;
296 const bool UseLidarNoiseModel = LidarParameters.UseLidarNoiseModel;
297
298 const float HorizontalFOV = LidarParameters.HorizontalFov;
299 const float HorizontalFOVHalf = HorizontalFOV / 2;
300
301 const UWorld* World = GetWorld();
302
303 ResetRecordedHits(PointsToScanWithOneChannel);
304
305 // Loop Lidar channels in Parallel
306 ParallelFor(ChannelCount, [&](int32 Channel)
307 {
308 const float VerticalAngle = LaserAngles[Channel];
309 int32 RGB = RgbDefault;
310 FHitResult HitResult;
311
312 // Generate random bool which we use later in AddLateralNoise
313 const bool UseHorizontalNoise = FMath::RandBool();
314
315 // Cache the reference to Points[idxChannel]
316 std::vector<FPointData>& ChannelPoints = Points[Channel];
317
318 // Loop through this channel linetraces
319 for (int32 i = 0; i < PointsToScanWithOneChannel; i++)
320 {
321 //HitResult.Reset();
322
323 // Calculate the EndTrace point for this linetrace
324 const float LaserHorizontalAngle = std::fmod(HorizontalAngle + AngleDistanceOfLaserMeasure * i, HorizontalFOV) - HorizontalFOVHalf;
325 const float VerticalRad = FMath::DegreesToRadians(VerticalAngle);
326 const float HorizontalRad = FMath::DegreesToRadians(LaserHorizontalAngle);
327
328 const FVector LocalDirection(FMath::Cos(VerticalRad) * FMath::Cos(HorizontalRad),
329 FMath::Cos(VerticalRad) * FMath::Sin(HorizontalRad),
330 FMath::Sin(VerticalRad));
331
332 const FVector EndTrace = LidarBodyLocation + Range * LidarRotationMatrix.TransformVector(LocalDirection);
333
334 if (ShootLaser(World, HitResult, EndTrace, TraceParams, LidarBodyLocation, Channel, Semantic, RgbDefault, UseLidarNoiseModel))
335 {
336 if (Semantic)
337 {
338 RGB = GetSemanticData(HitResult);
339 }
340
341 if (NeedsExtraProcessing)
342 {
343 AddProcessingToHitResult(HitResult, LidarBodyLocation, UseHorizontalNoise, UseSnowTerrainAdjustment);
344 }
345
346 // Add HitResult impact point to the current channel's point list
347 const FVector& HitPoint = HitResult.ImpactPoint;
348 ChannelPoints.emplace_back(HitPoint.X, HitPoint.Y, HitPoint.Z, RGB);
349 }
350 }
351 }, EParallelForFlags::Unbalanced);
352
353 CurrentHorizontalAngle = FMath::Fmod(HorizontalAngle + AngleDistanceOfTick, LidarParameters.HorizontalFov);
354
355 SendData(DeltaTime);
356
358 {
362 }
363
365 {
366 return PointsFlattened;
367 }
368
369 return HitPoints;
370}
FORCEINLINE bool ShootLaser(const UWorld *World, FHitResult &HitResult, const FVector &EndTrace, const FCollisionQueryParams &TraceParams, const FVector &LidarBodyLocation, const int32 Channel, const bool Semantic, const uint32 RGBDefault, const bool UseLidarNoiseModel)
Definition: Lidar.cpp:588
void SendData(const float DeltaTime)
Definition: Lidar.cpp:490
void ResetRecordedHits(int32 MaxPointsPerChannel)
Definition: Lidar.cpp:649
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
Definition: Lidar.cpp:247
void AddProcessingToHitResult(FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise, const bool UseSnowTerrainAdjustment)
Definition: Lidar.cpp:372
float CurrentHorizontalAngle
Definition: Lidar.h:284
bool UseTerrainSnowHitAdjustment

References AddProcessingToHitResult(), ASensor::CanSimulateSensor(), ChangeParameters(), FLidarParameters::Channels, ClearContainers, CurrentHorizontalAngle, CurrentWeatherParameters, FLidarParameters::DistanceNoiseStdDev, GetSemanticData(), FLidarParameters::HorizontalFov, FWeatherParameters::IsLidarNoiseModelCondition(), FWeatherParameters::IsWinterSnowCondition(), LaserAngles, FLidarParameters::LateralNoiseStdDev, LidarParameters, LidarParametersChanged, NeedToSavePointCloudWithoutNoise, Points, PointsFlattened, FLidarParameters::PointsPerSecond, FLidarParameters::Range, ResetRecordedHits(), FLidarParameters::RotationFrequency, FLidarParameters::SaveDataToDisk, FLidarParameters::SavePointcloudWithoutNoiseModel, FLidarParameters::Semantic, SendData(), FLidarParameters::SendDataToCombinedROSTopic, ShootLaser(), SimulateRaycastLidar(), TempLidarParameters, FLidarParameters::UseComplexCollisionTrace, FLidarParameters::UseLidarNoiseModel, and FLidarParameters::UseTerrainSnowHitAdjustment.

Referenced by ALidarManager::SimulateLidars(), and SimulateRaycastLidar().

◆ UpdateLidarParticles()

void ALidar::UpdateLidarParticles ( int32  NumberOfHits,
const TArray< FVector > &  HitPoints,
const TArray< FLinearColor > &  Colors 
)
private

Definition at line 228 of file Lidar.cpp.

229{
231 {
232 NiagaraComponent->SetVariableFloat(NiagaraPointsFloat, float(NumberOfHits));
233 NiagaraComponent->SetVariableInt(NiagaraPointsInt, NumberOfHits);
234 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayVector(NiagaraComponent, NiagaraHitPoints, HitPoints);
235 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayColor(NiagaraComponent, NiagaraHitColors, Colors);
236 }
237}
static const FName NiagaraHitPoints
Definition: Sensor.h:381
static const FName NiagaraPointsFloat
Definition: Sensor.h:383
static const FName NiagaraHitColors
Definition: Sensor.h:382
static const FName NiagaraPointsInt
Definition: Sensor.h:380

References NiagaraComponent, ASensor::NiagaraHitColors, ASensor::NiagaraHitPoints, ASensor::NiagaraPointsFloat, and ASensor::NiagaraPointsInt.

Referenced by SetNiagaraRendering(), and VisualizeLidarParticles().

◆ VisualizeLidarParticles()

void ALidar::VisualizeLidarParticles ( std::vector< FPointData HitPoints)
private

Visualize Lidar particles with Niagara particle system

Definition at line 433 of file Lidar.cpp.

434{
435 TRACE_CPUPROFILER_EVENT_SCOPE(ALidar::VisualizeLidarParticles);
436
437 if (!LidarParameters.VisualizePointcloud || !NiagaraComponent || HitPoints.empty())
438 {
439 return;
440 }
441
442 if (GEngine && GEngine->GameViewport && GEngine->GameViewport->bDisableWorldRendering)
443 {
444 // If world rendering (Spectator camera) is disabled, no need to update the particle system.
445 return;
446 }
447
448 // Convert std::vector<FPointData> to
449 // TArray<FVector> and TArray<FLinearColor> for Niagara visualization.
450 int32 NumberOfHits = HitPoints.size();
451
452 // Create and allocate HitLocations TArray
453 TArray<FVector> HitLocations;
454 HitLocations.SetNumUninitialized(NumberOfHits);
455
456 // Create and set initial colors to green
457 TArray<FLinearColor> Colors;
458 Colors.Init(FLinearColor::Green, NumberOfHits);
459
460 // Pointer access for reduced overhead
461 FVector* HitLocationPtr = HitLocations.GetData();
462 FLinearColor* ColorsPtr = Colors.GetData();
463
464 const bool Semantic = LidarParameters.Semantic;
465
466 for (int32 i = 0; i < NumberOfHits; ++i)
467 {
468 const FPointData& point = HitPoints[i];
469
470 HitLocationPtr[i].X = point.X;
471 HitLocationPtr[i].Y = (point.Y * -1);
472 HitLocationPtr[i].Z = point.Z;
473
474 if (Semantic)
475 {
476 // Convert point.RGB (uint32) to FLinearColor
477 uint8 R = (point.RGB >> 16) & 0xFF;
478 uint8 G = (point.RGB >> 8) & 0xFF;
479 uint8 B = point.RGB & 0xFF;
480
481 ColorsPtr[i].R = R / 255.0f;
482 ColorsPtr[i].G = G / 255.0f;
483 ColorsPtr[i].B = B / 255.0f;
484 //ColorsPtr[i].A = 1.0f;
485 }
486 }
487 UpdateLidarParticles(NumberOfHits, HitLocations, Colors);
488}
float Z
Definition: PointData.h:19
float Y
Definition: PointData.h:17
uint32 RGB
Definition: PointData.h:21

References LidarParameters, NiagaraComponent, FPointData::RGB, FLidarParameters::Semantic, UpdateLidarParticles(), VisualizeLidarParticles(), FLidarParameters::VisualizePointcloud, FPointData::X, FPointData::Y, and FPointData::Z.

Referenced by ResetRecordedHits(), and VisualizeLidarParticles().

Friends And Related Function Documentation

◆ ALidarManager

friend class ALidarManager
friend

Definition at line 135 of file Lidar.h.

Member Data Documentation

◆ CachedNoneColor

uint32 ALidar::CachedNoneColor
private

Definition at line 292 of file Lidar.h.

Referenced by BeginPlay(), and GetSemanticData().

◆ CachedSnowflakeColor

uint32 ALidar::CachedSnowflakeColor
private

Definition at line 294 of file Lidar.h.

Referenced by BeginPlay(), and GetSemanticData().

◆ ClearContainers

bool ALidar::ClearContainers = true
private

Definition at line 298 of file Lidar.h.

Referenced by CanSendData(), ResetRecordedHits(), and SimulateRaycastLidar().

◆ CurrentHorizontalAngle

float ALidar::CurrentHorizontalAngle = 0.0f
private

Definition at line 284 of file Lidar.h.

Referenced by SimulateRaycastLidar().

◆ CurrentWeatherParameters

FWeatherParameters ALidar::CurrentWeatherParameters
private

Definition at line 261 of file Lidar.h.

Referenced by BeginPlay(), OnWeatherChanged(), ShootLaser(), and SimulateRaycastLidar().

◆ Generator

std::mt19937 ALidar::Generator
private

Definition at line 276 of file Lidar.h.

Referenced by AddDistanceNoise(), AddLateralNoise(), and Init().

◆ GeoReferencingSystem

AGeoReferencingSystem* ALidar::GeoReferencingSystem = nullptr
private

Definition at line 254 of file Lidar.h.

Referenced by CreateLogFile(), and SaveLidarMetaDataToDisk().

◆ LaserAngles

std::vector<float> ALidar::LaserAngles
private

Definition at line 273 of file Lidar.h.

Referenced by ChangeParameters(), EndPlay(), and SimulateRaycastLidar().

◆ LidarParameters

FLidarParameters ALidar::LidarParameters
private

◆ LidarParametersChanged

bool ALidar::LidarParametersChanged = false
private

Definition at line 279 of file Lidar.h.

Referenced by ChangeLidarParameters(), and SimulateRaycastLidar().

◆ LidarSaves

int32 ALidar::LidarSaves = 0
private

Definition at line 290 of file Lidar.h.

Referenced by SaveDataToDisk().

◆ NeedToSavePointCloudWithoutNoise

bool ALidar::NeedToSavePointCloudWithoutNoise = false
private

Definition at line 278 of file Lidar.h.

Referenced by SaveDataToDisk(), ShootLaser(), and SimulateRaycastLidar().

◆ NiagaraComponent

UNiagaraComponent* ALidar::NiagaraComponent = nullptr
private

NiagaraComponent for visualizing Lidar particles. Particles are only visible on Spectator camera.

Definition at line 148 of file Lidar.h.

Referenced by BeginPlay(), EndPlay(), SetNiagaraRendering(), SetParticleLifeTime(), UpdateLidarParticles(), and VisualizeLidarParticles().

◆ PointCloudMessage

TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> ALidar::PointCloudMessage
private

Definition at line 266 of file Lidar.h.

Referenced by EndPlay(), Init(), and SendDataToTopic().

◆ Points

std::vector<std::vector<FPointData> > ALidar::Points
private

Definition at line 270 of file Lidar.h.

Referenced by ChangeParameters(), EndPlay(), ResetRecordedHits(), SendData(), and SimulateRaycastLidar().

◆ PointsFlattened

std::vector<FPointData> ALidar::PointsFlattened
private

Definition at line 271 of file Lidar.h.

Referenced by EndPlay(), ResetRecordedHits(), SaveDataToDisk(), SendData(), and SimulateRaycastLidar().

◆ PreProcessedHitImpactPoints

std::vector<std::vector<FPointData> > ALidar::PreProcessedHitImpactPoints
private

Definition at line 268 of file Lidar.h.

Referenced by ChangeParameters(), EndPlay(), ResetRecordedHits(), SaveDataToDisk(), and ShootLaser().

◆ RandomDevice

std::random_device ALidar::RandomDevice
private

Definition at line 275 of file Lidar.h.

Referenced by Init().

◆ SaveCurrentPointCloudToDiskRequested

bool ALidar::SaveCurrentPointCloudToDiskRequested = false
private

Definition at line 296 of file Lidar.h.

Referenced by SendData().

◆ SemanticColors

TMap<FName, FColor> ALidar::SemanticColors
private

Definition at line 264 of file Lidar.h.

Referenced by BeginPlay(), and GetSemanticData().

◆ SendDataEveryFrame

bool ALidar::SendDataEveryFrame = false
private

Definition at line 280 of file Lidar.h.

Referenced by CanSendData(), ChangeParameters(), and ResetRecordedHits().

◆ SensorHzFrequency

float ALidar::SensorHzFrequency = 0.1f
private

Definition at line 285 of file Lidar.h.

Referenced by CanSendData(), and ChangeParameters().

◆ SensorHzTimer

float ALidar::SensorHzTimer = 0.0f
private

Definition at line 286 of file Lidar.h.

Referenced by CanSendData().

◆ SnowHeightOffset

float ALidar::SnowHeightOffset = 0.0f
private

Definition at line 288 of file Lidar.h.

Referenced by AddSnowTerrainAdjustment(), and OnWeatherChanged().

◆ TempLidarParameters

FLidarParameters ALidar::TempLidarParameters
private

Definition at line 259 of file Lidar.h.

Referenced by ChangeLidarParameters(), and SimulateRaycastLidar().

◆ TerrainTag

const FName ALidar::TerrainTag = "Terrain"
private

Definition at line 282 of file Lidar.h.

Referenced by AddSnowTerrainAdjustment().


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