17#include "Runtime/Engine/Classes/Kismet/KismetMathLibrary.h"
18#include "NiagaraDataInterfaceArrayFunctionLibrary.h"
19#include "Math/UnrealMathUtility.h"
20#include "NiagaraFunctionLibrary.h"
21#include <Misc/FileHelper.h>
22#include "NiagaraComponent.h"
23#include "Components/PrimitiveComponent.h"
25#include "Async/ParallelFor.h"
26#include "Engine/GameViewportClient.h"
27#include "Engine/Engine.h"
31ALidar::ALidar(
const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
34 PrimaryActorTick.bCanEverTick =
false;
60 for (
const auto& ColorEntry : Colors)
62 FName SemanticName = FName(*ColorEntry.Key);
69 CachedNoneColor = (NoneColor.R << 16) | (NoneColor.G << 8) | (NoneColor.B << 0);
70 CachedSnowflakeColor = (SnowflakeColor.R << 16) | (SnowflakeColor.G << 8) | (SnowflakeColor.B << 0);
87 UNiagaraSystem* NS = LoadObject<UNiagaraSystem>(
nullptr, TEXT(
"/Game/Agrarsense/Particles/PointCloud/NS_PointCloudSemanticFast"),
nullptr, LOAD_None,
nullptr);
107 UE_LOG(LogTemp, Warning, TEXT(
"Lidar.cpp: Couldn't find Niagara particle system."));
114 Super::EndPlay(EndPlayReason);
177 Points.resize(NumberOfLasers);
183 for (int32 i = 0; i < NumberOfLasers; ++i)
195 SimulatorLog::Log(
"Lidar sensor: It's highly advisable to turn off VisualizePointcloud when PointsPerSecond exceed 1 million.");
200 SimulatorLog::Log(
"Lidar sensor: VisualizePointcloud has been set to false due PointsPerSecond exceeding 2 million.");
219 TArray<FVector> EmptyHitpoints;
220 TArray<FLinearColor> EmptyColors;
243 NiagaraComponent->SetVariableFloat(FName(
"User.LifeTime"), ParticleLifeTime);
251 std::vector<FPointData> HitPoints;
259 const FTransform ActorTransform = GetTransform();
260 const FVector LidarBodyLocation = ActorTransform.GetLocation();
261 const FRotator LidarBodyRotation = ActorTransform.Rotator();
262 const FQuat LidarBodyQuat = FQuat(LidarBodyRotation);
269 const float AngleDistanceOfLaserMeasure = AngleDistanceOfTick / PointsToScanWithOneChannel;
272 const FColor Color = FColor(255, 255, 255);
273 const int32 RgbDefault = (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
275 FCollisionQueryParams TraceParams = FCollisionQueryParams(FName(TEXT(
"Laser_Trace")),
true,
this);
276 TraceParams.bReturnPhysicalMaterial =
false;
298 const float HorizontalFOVHalf = HorizontalFOV / 2;
303 ParallelFor(ChannelCount, [&](int32 Channel)
306 int32 RGB = RgbDefault;
308 FRotator LaserRotation;
309 FHitResult HitResult;
313 const bool UseHorizontalNoise = FMath::RandBool();
316 std::vector<FPointData>& ChannelPoints =
Points[Channel];
319 for (int32 i = 0; i < PointsToScanWithOneChannel; i++)
324 const float LaserHorizontalAngle = std::fmod(HorizontalAngle + AngleDistanceOfLaserMeasure * i, HorizontalFOV) - HorizontalFOVHalf;
325 LaserRotation = FRotator(VerticalAngle, LaserHorizontalAngle, 0);
326 const FQuat LaserQuat = FQuat(LaserRotation);
327 const FQuat ResultQuat = LaserQuat * LidarBodyQuat;
328 EndTrace = Range * ResultQuat.Vector() + LidarBodyLocation;
330 if (
ShootLaser(HitResult, EndTrace, TraceParams, LidarBodyLocation, Channel, Semantic, RgbDefault, UseLidarNoiseModel))
337 if (NeedsExtraProcessing)
343 const FVector& HitPoint = HitResult.ImpactPoint;
344 ChannelPoints.emplace_back(HitPoint.X, HitPoint.Y, HitPoint.Z, RGB);
347 }, EParallelForFlags::Unbalanced);
370 if (UseSnowTerrainAdjustment)
389 float NoiseValue = Distribution(
Generator);
390 const FVector DirectionToSensor = ((LidarBodyLocation * 1e-2) - HitResult.ImpactPoint).GetSafeNormal();
391 const FVector Noise = DirectionToSensor * NoiseValue;
392 HitResult.ImpactPoint += Noise;
397 const FVector ForwardVector = (HitResult.ImpactPoint - LidarBodyLocation).GetSafeNormal();
398 const FVector RightVector = FVector::CrossProduct(ForwardVector, FVector::UpVector).GetSafeNormal();
400 FVector ChosenDirection;
401 if (UseHorizontalNoise)
403 ChosenDirection = RightVector;
407 FVector UpVector = FVector::CrossProduct(ForwardVector, RightVector).GetSafeNormal();
408 ChosenDirection = UpVector;
412 const float NoiseValue = Distribution(
Generator);
414 HitResult.ImpactPoint += ChosenDirection * NoiseValue;
419 AActor* HitActor = HitResult.GetActor();
422 if (HitActor && HitActor->Tags.Contains(
TerrainTag))
438 if (GEngine && GEngine->GameViewport && GEngine->GameViewport->bDisableWorldRendering)
446 int32 NumberOfHits = HitPoints.size();
449 TArray<FVector> HitLocations;
450 HitLocations.SetNumUninitialized(NumberOfHits);
453 TArray<FLinearColor> Colors;
454 Colors.Init(FLinearColor::Green, NumberOfHits);
457 FVector* HitLocationPtr = HitLocations.GetData();
458 FLinearColor* ColorsPtr = Colors.GetData();
462 for (int32 i = 0; i < NumberOfHits; ++i)
466 HitLocationPtr[i].
X = point.
X;
467 HitLocationPtr[i].Y = (point.
Y * -1);
468 HitLocationPtr[i].Z = point.
Z;
473 uint8 R = (point.
RGB >> 16) & 0xFF;
474 uint8 G = (point.
RGB >> 8) & 0xFF;
475 uint8 B = point.
RGB & 0xFF;
477 ColorsPtr[i].R = R / 255.0f;
478 ColorsPtr[i].G = G / 255.0f;
479 ColorsPtr[i].B = B / 255.0f;
495 size_t TotalSize = 0;
496 for (
const std::vector<FPointData>& Vec :
Points)
498 TotalSize += Vec.size();
502 for (std::vector<FPointData>& HitPoints :
Points)
558 auto* HitComponent = HitResult.Component.Get();
562 TArray<FName>& CompTags = HitComponent->ComponentTags;
563 if (!CompTags.IsEmpty())
565 FName Tag = CompTags[0];
567 return (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
580bool ALidar::ShootLaser(FHitResult& HitResult,
const FVector& EndTrace,
const FCollisionQueryParams& TraceParams,
581 const FVector& LidarBodyLocation,
const int32 Channel,
const bool Semantic,
const uint32 RGBDefault,
const bool UseLidarNoiseModel)
583#ifdef ParallelLineTraceSingleByChannel_EXISTS
586 World->ParallelLineTraceSingleByChannel(
590 ECC_GameTraceChannel3,
592 FCollisionResponseParams::DefaultResponseParam);
595 World->LineTraceSingleByChannel(
599 ECC_GameTraceChannel3,
601 FCollisionResponseParams::DefaultResponseParam);
605 HitResult.ImpactPoint *= 1e-2;
608 HitResult.ImpactPoint.Y *= -1;
613 FHitResult OriginalHitResultCopy = HitResult;
614 uint32 RGB = RGBDefault;
620 const FVector& HitPoint = OriginalHitResultCopy.ImpactPoint;
621 FPointData point = { HitPoint.
X, HitPoint.Y, HitPoint.Z, RGB };
625 bool BlockingHit =
false;
626 if (UseLidarNoiseModel)
630 BlockingHit = HitResult.bBlockingHit || HitSnowFlake;
634 BlockingHit = HitResult.IsValidBlockingHit();
650 AsyncTask(ENamedThreads::GameThread, [
this, CopiedPoints]()
667 ImpactPoints.clear();
668 ImpactPoints.reserve(MaxPointsPerChannel);
672 for (std::vector<FPointData>& ImpactPoints :
Points)
674 ImpactPoints.clear();
675 ImpactPoints.reserve(MaxPointsPerChannel);
694 const size_t PointsSize = points.size();
695 const size_t DataSize = PointsSize *
sizeof(
FPointData);
717 std::vector<FPointData> PointsWithOutNoiseModel;
719 size_t totalSize = 0;
722 totalSize += Vec.size();
724 PointsWithOutNoiseModel.reserve(totalSize);
728 PointsWithOutNoiseModel.insert(PointsWithOutNoiseModel.end(), Vec.begin(), Vec.end());
732 FString PreprocessedFilename = FString::Printf(TEXT(
"%sLidar_%d_without_noise_model.ply"), *
FileSavePath,
LidarSaves);
void AddRaycastLidar(ALidar *lidarPtr)
void RemoveRaycastLidar(ALidar *lidarPtr)
UNiagaraComponent * NiagaraComponent
TMap< FName, FColor > SemanticColors
FWeatherParameters CurrentWeatherParameters
std::random_device RandomDevice
FORCEINLINE uint32 GetSemanticData(const FHitResult &HitResult) const
void VisualizeLidarParticles(std::vector< FPointData > HitPoints)
void Init(FLidarParameters parameters, bool SimulateSensor=true)
void UpdateLidarParticles(int32 NumberOfHits, const TArray< FVector > &HitPoints, const TArray< FLinearColor > &Colors)
void SendData(const float DeltaTime)
void AddLateralNoise(FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise)
void ChangeLidarParameters(FLidarParameters newLidarParameters)
bool CanSendData(const float DeltaTime)
std::vector< std::vector< FPointData > > PreProcessedHitImpactPoints
void ResetRecordedHits(int32 MaxPointsPerChannel)
ALidar(const FObjectInitializer &ObjectInitializer)
uint32 CachedSnowflakeColor
std::vector< float > LaserAngles
void SetParticleLifeTime(float ParticleLifeTime)
bool LidarParametersChanged
void OnWeatherChanged(FWeatherParameters WeatherParams)
virtual void BeginPlay() override
FLidarParameters TempLidarParameters
void AddDistanceNoise(FHitResult &HitResult, const FVector &LidarBodyLocation)
void SetNiagaraRendering(bool Enabled)
std::vector< std::vector< FPointData > > Points
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
bool NeedToSavePointCloudWithoutNoise
std::vector< FPointData > PointsFlattened
void SetVisualizeLidarParticles(bool Visualize)
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
FORCEINLINE bool ShootLaser(FHitResult &HitResult, const FVector &EndTrace, const FCollisionQueryParams &TraceParams, const FVector &LidarBodyLocation, const int32 Channel, const bool Semantic, const uint32 RGBDefault, const bool UseLidarNoiseModel)
void SendDataToTopic(const std::vector< FPointData > &points)
void AddSnowTerrainAdjustment(FHitResult &HitResult, const FVector &LidarBodyLocation)
FLidarParameters LidarParameters
void AddProcessingToHitResult(FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise, const bool UseSnowTerrainAdjustment)
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
float CurrentHorizontalAngle
static const FName NiagaraHitPoints
bool CanSimulateSensor() const
static void HideComponentForAllCameras(UPrimitiveComponent *PrimitiveComponent)
static const FName NiagaraPointsFloat
virtual void CreateDataSavePath()
void SetSimulateSensor(bool SimulateSensor)
UTopic * GetROSTopic() const
static const FName NiagaraHitColors
FORCEINLINE bool IsROSConnected() const
virtual void CreateROSTopic()
static const FName NiagaraPointsInt
static TMap< FString, FColor > GetSemanticColors()
const FWeatherParameters & GetCurrentWeather() const
FLevelEventDelegate_WeatherChanged OnWeatherChanged
static bool CheckSnowflakeHit(FHitResult &HitInfo, const FVector EndTrace, const FVector LidarLocation, const FWeatherParameters &WeatherParameters)
static void Log(const FString &Message, bool LogToTextFile=true, bool LogToROS=true)
static AWeather * GetWeatherActor(const UObject *WorldContextObject)
static ALidarManager * GetLidarManager(const UObject *WorldContextObject)
static void SaveVectorArrayAsPlyAsync(FString FullFileName, const std::vector< FPointData > points)
float DistanceNoiseStdDev
bool SendDataAtRotationFrequency
bool SendDataToCombinedROSTopic
bool SavePointcloudWithoutNoiseModel
bool UseComplexCollisionTrace
bool UseTerrainSnowHitAdjustment
bool IsWinterSnowCondition()
bool IsLidarNoiseModelCondition()