18#include "GeoReferencingSystem.h"
19#include "Runtime/Engine/Classes/Kismet/KismetMathLibrary.h"
20#include "NiagaraDataInterfaceArrayFunctionLibrary.h"
21#include "Math/UnrealMathUtility.h"
22#include "NiagaraFunctionLibrary.h"
23#include "Misc/FileHelper.h"
24#include "NiagaraComponent.h"
25#include "Components/PrimitiveComponent.h"
27#include "Async/ParallelFor.h"
28#include "Engine/GameViewportClient.h"
29#include "Engine/Engine.h"
30#include "Async/Async.h"
34ALidar::ALidar(
const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
37 PrimaryActorTick.bCanEverTick =
false;
60 UWorld* World = GetWorld();
64 for (
const auto& ColorEntry : Colors)
66 FName SemanticName = FName(*ColorEntry.Key);
73 CachedNoneColor = (NoneColor.R << 16) | (NoneColor.G << 8) | (NoneColor.B << 0);
74 CachedSnowflakeColor = (SnowflakeColor.R << 16) | (SnowflakeColor.G << 8) | (SnowflakeColor.B << 0);
91 UNiagaraSystem* NS = LoadObject<UNiagaraSystem>(
nullptr, TEXT(
"/Game/Agrarsense/Particles/PointCloud/NS_PointCloudSemanticFast"),
nullptr, LOAD_None,
nullptr);
94 NiagaraComponent = UNiagaraFunctionLibrary::SpawnSystemAtLocation(World, NS, GetActorLocation());
111 UE_LOG(LogTemp, Warning, TEXT(
"Lidar.cpp: Couldn't find Niagara particle system."));
118 Super::EndPlay(EndPlayReason);
120 UWorld* World = GetWorld();
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 FMatrix LidarRotationMatrix = FRotationMatrix(FQuat(LidarBodyRotation).Rotator());
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;
277 TraceParams.bReturnFaceIndex =
false;
299 const float HorizontalFOVHalf = HorizontalFOV / 2;
301 const UWorld* World = GetWorld();
306 ParallelFor(ChannelCount, [&](int32 Channel)
309 int32 RGB = RgbDefault;
310 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 const float VerticalRad = FMath::DegreesToRadians(VerticalAngle);
326 const float HorizontalRad = FMath::DegreesToRadians(LaserHorizontalAngle);
328 const FVector LocalDirection(FMath::Cos(VerticalRad) * FMath::Cos(HorizontalRad),
329 FMath::Cos(VerticalRad) * FMath::Sin(HorizontalRad),
330 FMath::Sin(VerticalRad));
332 const FVector EndTrace = LidarBodyLocation + Range * LidarRotationMatrix.TransformVector(LocalDirection);
334 if (
ShootLaser(World, HitResult, EndTrace, TraceParams, LidarBodyLocation, Channel, Semantic, RgbDefault, UseLidarNoiseModel))
341 if (NeedsExtraProcessing)
347 const FVector& HitPoint = HitResult.ImpactPoint;
348 ChannelPoints.emplace_back(HitPoint.X, HitPoint.Y, HitPoint.Z, RGB);
351 }, EParallelForFlags::Unbalanced);
374 if (UseSnowTerrainAdjustment)
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;
401 const FVector ForwardVector = (HitResult.ImpactPoint - LidarBodyLocation).GetSafeNormal();
402 const FVector RightVector = FVector::CrossProduct(ForwardVector, FVector::UpVector).GetSafeNormal();
404 FVector ChosenDirection;
405 if (UseHorizontalNoise)
407 ChosenDirection = RightVector;
411 FVector UpVector = FVector::CrossProduct(ForwardVector, RightVector).GetSafeNormal();
412 ChosenDirection = UpVector;
416 const float NoiseValue = Distribution(
Generator);
418 HitResult.ImpactPoint += ChosenDirection * NoiseValue;
423 AActor* HitActor = HitResult.GetActor();
426 if (HitActor && HitActor->Tags.Contains(
TerrainTag))
442 if (GEngine && GEngine->GameViewport && GEngine->GameViewport->bDisableWorldRendering)
450 int32 NumberOfHits = HitPoints.size();
453 TArray<FVector> HitLocations;
454 HitLocations.SetNumUninitialized(NumberOfHits);
457 TArray<FLinearColor> Colors;
458 Colors.Init(FLinearColor::Green, NumberOfHits);
461 FVector* HitLocationPtr = HitLocations.GetData();
462 FLinearColor* ColorsPtr = Colors.GetData();
466 for (int32 i = 0; i < NumberOfHits; ++i)
470 HitLocationPtr[i].
X = point.
X;
471 HitLocationPtr[i].Y = (point.
Y * -1);
472 HitLocationPtr[i].Z = point.
Z;
477 uint8 R = (point.
RGB >> 16) & 0xFF;
478 uint8 G = (point.
RGB >> 8) & 0xFF;
479 uint8 B = point.
RGB & 0xFF;
481 ColorsPtr[i].R = R / 255.0f;
482 ColorsPtr[i].G = G / 255.0f;
483 ColorsPtr[i].B = B / 255.0f;
499 size_t TotalSize = 0;
500 for (
const std::vector<FPointData>& Vec :
Points)
502 TotalSize += Vec.size();
506 for (std::vector<FPointData>& HitPoints :
Points)
566 auto* HitComponent = HitResult.Component.Get();
570 TArray<FName>& CompTags = HitComponent->ComponentTags;
571 if (!CompTags.IsEmpty())
573 FName Tag = CompTags[0];
575 return (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
588bool ALidar::ShootLaser(
const UWorld* World, FHitResult& HitResult,
const FVector& EndTrace,
const FCollisionQueryParams& TraceParams,
589 const FVector& LidarBodyLocation,
const int32 Channel,
const bool Semantic,
const uint32 RGBDefault,
const bool UseLidarNoiseModel)
591#ifdef ParallelLineTraceSingleByChannel_EXISTS
594 World->ParallelLineTraceSingleByChannel(
598 ECC_GameTraceChannel3,
600 FCollisionResponseParams::DefaultResponseParam);
603 World->LineTraceSingleByChannel(
607 ECC_GameTraceChannel3,
609 FCollisionResponseParams::DefaultResponseParam);
612 bool BlockingHit = HitResult.IsValidBlockingHit();
613 if (!BlockingHit && !UseLidarNoiseModel)
619 HitResult.ImpactPoint *= 1e-2;
622 HitResult.ImpactPoint.Y *= -1;
627 FHitResult OriginalHitResultCopy = HitResult;
628 uint32 RGB = RGBDefault;
634 const FVector& HitPoint = OriginalHitResultCopy.ImpactPoint;
635 FPointData point = { HitPoint.
X, HitPoint.Y, HitPoint.Z, RGB };
639 if (UseLidarNoiseModel)
643 BlockingHit = HitResult.bBlockingHit || HitSnowFlake;
659 AsyncTask(ENamedThreads::GameThread, [
this, CopiedPoints]()
676 ImpactPoints.clear();
677 ImpactPoints.reserve(MaxPointsPerChannel);
681 for (std::vector<FPointData>& ImpactPoints :
Points)
683 ImpactPoints.clear();
684 ImpactPoints.reserve(MaxPointsPerChannel);
703 const size_t PointsSize = points.size();
704 const size_t DataSize = PointsSize *
sizeof(
FPointData);
728 std::vector<FPointData> PointsWithOutNoiseModel;
730 size_t totalSize = 0;
733 totalSize += Vec.size();
735 PointsWithOutNoiseModel.reserve(totalSize);
739 PointsWithOutNoiseModel.insert(PointsWithOutNoiseModel.end(), Vec.begin(), Vec.end());
743 FString PreprocessedFilename = FString::Printf(TEXT(
"%sLidar_%d_without_noise_model.ply"), *
FileSavePath,
LidarSaves);
768 LogFile = NewObject<ULogFile>(ULogFile::StaticClass());
771 FString FileName =
"lidar_metadata";
778 WriteToLogFile(
"timestamp, pointcloud_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation, GPS latitude, GPS longitude, GPS altitude");
782 WriteToLogFile(
"timestamp, pointcloud_name, X location, Y location, Z location, yaw rotation, pitch rotation, roll rotation");
795 const FVector ActorPosition = GetActorLocation();
796 const FRotator ActorRotation = GetActorRotation();
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);
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);
void AddRaycastLidar(ALidar *lidarPtr)
void RemoveRaycastLidar(ALidar *lidarPtr)
UNiagaraComponent * NiagaraComponent
TMap< FName, FColor > SemanticColors
void SaveLidarMetaDataToDisk(const FString &FileName)
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)
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)
AGeoReferencingSystem * GeoReferencingSystem
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
void SendDataToTopic(const std::vector< FPointData > &points)
void AddSnowTerrainAdjustment(FHitResult &HitResult, const FVector &LidarBodyLocation)
void CreateLogFile() override
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
bool SaveCurrentPointCloudToDiskRequested
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
FString CreateTimeStampString() const
void WriteToLogFile(const FString &Message)
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 FGeographicCoordinates UnrealToGeographicCoordinates(AGeoReferencingSystem *GeoReferencingSystem, const FVector &Position)
void Create(const FString &FileNameWithoutExtension, FLogFileSettings Settings)
static void SaveVectorArrayAsPlyAsync(FString FullFileName, const std::vector< FPointData > points)
float DistanceNoiseStdDev
bool SendDataAtRotationFrequency
bool SendDataToCombinedROSTopic
bool SavePointcloudWithoutNoiseModel
bool UseComplexCollisionTrace
bool UseTerrainSnowHitAdjustment
FFileWriteOptions FileWriteOptions
FFileCreationOptions FileCreationOptions
bool IsWinterSnowCondition()
bool IsLidarNoiseModelCondition()