8#include "CoreMinimal.h"
9#include "Containers/Map.h"
10#include "Engine/HitResult.h"
18#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
22#include "Lidar.generated.h"
24class UNiagaraComponent;
39 ALidar(
const FObjectInitializer& ObjectInitializer);
60 UFUNCTION(BlueprintCallable)
67 UFUNCTION(BlueprintCallable)
68 void SetVisualizeLidarParticles(
bool Visualize);
74 UFUNCTION(BlueprintCallable)
75 void SetParticleLifeTime(
float ParticleLifeTime);
81 UFUNCTION(BlueprintCallable, BlueprintPure)
84 return LidarParameters;
91 UFUNCTION(BlueprintCallable)
92 UNiagaraComponent* GetNiagaraComponent()
const
94 return NiagaraComponent;
102 return StructToString(LidarParameters);
109 virtual void EndPlay(
const EEndPlayReason::Type EndPlayReason)
override;
119 std::vector<FPointData> SimulateRaycastLidar(
const float DeltaTime);
125 UPROPERTY(VisibleAnywhere, Category =
"Sensor")
126 UNiagaraComponent* NiagaraComponent =
nullptr;
132 void SetNiagaraRendering(
bool Enabled);
137 void VisualizeLidarParticles();
142 void ChangeParameters();
150 bool ShootLaser(FHitResult& HitResult, const FVector& EndTrace, const FCollisionQueryParams& TraceParams,
151 const FVector& LidarBodyLocation, const int32 Channel, const
bool Semantic, const uint32 RGBDefault);
156 void ResetRecordedHits(int32 MaxPointsPerChannel);
163 uint32 GetSemanticData(const FHitResult& HitResult) const;
169 void SendData(const
float DeltaTime);
174 bool CanSendData(const
float DeltaTime);
179 void SendDataToTopic(const std::vector<
FPointData>& points);
184 void SaveDataToDisk();
191 void AddProcessingToHitResult(FHitResult& HitResult, const FVector& LidarBodyLocation, const
bool UseHorizontalNoise);
202 void AddDistanceNoise(FHitResult& HitResult, const FVector& LidarBodyLocation);
211 void AddLateralNoise(FHitResult& HitResult, const FVector& LidarBodyLocation, const
bool UseHorizontalNoise);
218 void AddSnowTerrainAdjustment(FHitResult& HitResult, const FVector& LidarBodyLocation);
223 void UpdateLidarParticles(
int NumberOfHits, const TArray<FVector>& HitPoints, const TArray<FLinearColor>& Colors);
231 UPROPERTY(VisibleAnywhere, Category = "Sensor")
239 UWorld* World =
nullptr;
242 TMap<FName, FColor> SemanticColors;
246 std::vector<std::vector<
FPointData>> PreProcessedHitImpactPoints;
250 std::vector<uint32_t> PointsPerChannel;
251 std::vector<
float> LaserAngles;
253 std::random_device RandomDevice;
254 std::mt19937 Generator;
256 bool NeedToSavePointCloudWithoutNoise = false;
257 bool LidarParametersChanged = false;
258 bool SendDataEveryFrame = false;
259 bool ClearContainers = true;
261 float CurrentHorizontalAngle = 0.0f;
262 float SensorHzFrequency = 0.1f;
263 float SensorHzTimer = 0.0f;
265 float SnowHeightOffset = 0.0f;
269 uint32 CachedNoneColor;
271 uint32 CachedSnowflakeColor;
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
UPROPERTY(BlueprintReadOnly)
virtual FString GetParametersAsString() const override
virtual ESensorTypes GetSensorType() const override
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
virtual void BeginPlay() override