Agrarsense
Lidar.h
Go to the documentation of this file.
1// Copyright (c) 2023 FrostBit Software Lab at the Lapland University of Applied Sciences
2//
3// This work is licensed under the terms of the MIT license.
4// For a copy, see <https://opensource.org/licenses/MIT>.
5
6#pragma once
7
8#include "CoreMinimal.h"
9#include "Containers/Map.h"
10#include "Engine/HitResult.h"
11
16
17
18#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
19
20#include <random>
21
22#include "Lidar.generated.h"
23
24class AGeoReferencingSystem;
25class UNiagaraComponent;
26class UWorld;
27class AWeather;
28
33UCLASS()
34class AGRARSENSE_API ALidar : public ASensor
35{
36 GENERATED_BODY()
37
38public:
39
40 ALidar(const FObjectInitializer& ObjectInitializer);
41
46 void Init(FLidarParameters parameters, bool SimulateSensor = true);
47
52 virtual ESensorTypes GetSensorType() const override
53 {
55 }
56
61 UFUNCTION(BlueprintCallable)
62 void ChangeLidarParameters(FLidarParameters newLidarParameters);
63
68 UFUNCTION(BlueprintCallable)
69 void SetVisualizeLidarParticles(bool Visualize);
70
75 UFUNCTION(BlueprintCallable)
76 void SetParticleLifeTime(float ParticleLifeTime);
77
82 UFUNCTION(BlueprintCallable, BlueprintPure)
83 FLidarParameters GetLidarParameters() const
84 {
85 return LidarParameters;
86 }
87
92 UFUNCTION(BlueprintCallable)
93 UNiagaraComponent* GetNiagaraComponent() const
94 {
95 return NiagaraComponent;
96 }
97
101 virtual FString GetParametersAsString() const override
102 {
103 return StructToString(LidarParameters);
104 }
105
106 /*
107 * Force to clear all containers and starting to
108 * capture pointcloud from the beginning.
109 */
111 {
112 ClearContainers = true;
113 }
114
115 /*
116 * Request saving this frame's pointcloud to disk.
117 */
119 {
120 SaveCurrentPointCloudToDiskRequested = true;
121 }
122
123protected:
124
125 virtual void BeginPlay() override;
126
127 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
128
129 void CreateLogFile() override;
130
131 void SaveLidarMetaDataToDisk(const FString& FileName);
132
133private:
134
135 friend class ALidarManager;
136
141 std::vector<FPointData> SimulateRaycastLidar(const float DeltaTime);
142
147 UPROPERTY(VisibleAnywhere, Category = "Sensor")
148 UNiagaraComponent* NiagaraComponent = nullptr;
149
154 void SetNiagaraRendering(bool Enabled);
155
159 void VisualizeLidarParticles(std::vector<FPointData> HitPoints);
160
164 void ChangeParameters();
165
172 FORCEINLINE bool ShootLaser(const UWorld* World, FHitResult& HitResult, const FVector& EndTrace, const FCollisionQueryParams& TraceParams,
173 const FVector& LidarBodyLocation, const int32 Channel, const bool Semantic, const uint32 RGBDefault, const bool UseLidarNoiseModel);
174
178 void ResetRecordedHits(int32 MaxPointsPerChannel);
179
185 FORCEINLINE uint32 GetSemanticData(const FHitResult& HitResult) const;
186
191 void SendData(const float DeltaTime);
192
196 bool CanSendData(const float DeltaTime);
197
198 /*
199 * Send this Lidar sensor data to its own ROS topic
200 */
201 void SendDataToTopic(const std::vector<FPointData>& points);
202
203 /*
204 * Asynchronously saves Lidar point cloud data to disk
205 */
206 void SaveDataToDisk();
207
208 /*
209 * Check if we should add extra processing to the current line trace hit result.
210 * @param HitResult - The hit result containing the impact point to which noise will be added.
211 * @param LidarBodyLocation - The location of the Lidar sensor
212 */
213 void AddProcessingToHitResult(FHitResult& HitResult, const FVector& LidarBodyLocation, const bool UseHorizontalNoise, const bool UseSnowTerrainAdjustment);
214
215 /*
216 * Applies distance noise to the hit result based on the standard deviation specified
217 * in the Lidar parameters. The noise is added to the impact point, simulating measurement
218 * inaccuracies by perturbing the hit point in the direction from the Lidar sensor towards
219 * the detected impact point. This noise mimics real-world sensor errors where measurements
220 * can vary around the true value.
221 * @param HitResult - The hit result containing the impact point to which noise will be added.
222 * @param LidarBodyLocation - The location of the Lidar sensor
223 */
224 void AddDistanceNoise(FHitResult& HitResult, const FVector& LidarBodyLocation);
225
226 /*
227 * Applies lateral noise to the hit result, introducing random deviation
228 * either vertically or horizontally, perpendicular to the Lidar linetrace origin direction.
229 * @param HitResult - The hit result containing the impact point to which noise will be added.
230 * @param LidarBodyLocation - The location of the Lidar sensor.
231 * @param UseHorizontalNoise - Direction to use.
232 */
233 void AddLateralNoise(FHitResult& HitResult, const FVector& LidarBodyLocation, const bool UseHorizontalNoise);
234
235 /*
236 * Adjusts the hit result for terrain snow.
237 * @param HitResult - The hit result containing the impact point to which noise will be added.
238 * @param LidarBodyLocation - The location of the Lidar sensor
239 */
240 void AddSnowTerrainAdjustment(FHitResult& HitResult, const FVector& LidarBodyLocation);
241
242 /*
243 * Updates Niagara particle system particles
244 */
245 void UpdateLidarParticles(int32 NumberOfHits, const TArray<FVector>& HitPoints, const TArray<FLinearColor>& Colors);
246
247 /*
248 * Callback event from AWeather when weather parameters has been changed.
249 */
250 UFUNCTION()
251 void OnWeatherChanged(FWeatherParameters WeatherParams);
252
253 UPROPERTY()
254 AGeoReferencingSystem* GeoReferencingSystem = nullptr;
255
256 UPROPERTY(VisibleAnywhere, Category = "Sensor")
257 FLidarParameters LidarParameters;
258
259 FLidarParameters TempLidarParameters;
260
261 FWeatherParameters CurrentWeatherParameters;
262
263 UPROPERTY()
264 TMap<FName, FColor> SemanticColors;
265
266 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> PointCloudMessage;
267
268 std::vector<std::vector<FPointData>> PreProcessedHitImpactPoints;
269
270 std::vector<std::vector<FPointData>> Points;
271 std::vector<FPointData> PointsFlattened;
272
273 std::vector<float> LaserAngles;
274
275 std::random_device RandomDevice;
276 std::mt19937 Generator;
277
278 bool NeedToSavePointCloudWithoutNoise = false;
279 bool LidarParametersChanged = false;
280 bool SendDataEveryFrame = false;
281
282 const FName TerrainTag = "Terrain";
283
284 float CurrentHorizontalAngle = 0.0f;
285 float SensorHzFrequency = 0.1f;
286 float SensorHzTimer = 0.0f;
287
288 float SnowHeightOffset = 0.0f;
289
290 int32 LidarSaves = 0;
291
292 uint32 CachedNoneColor;
293
294 uint32 CachedSnowflakeColor;
295
296 bool SaveCurrentPointCloudToDiskRequested = false;
297
298 bool ClearContainers = true;
299};
ESensorTypes
Definition: SensorTypes.h:15
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: LidarManager.h:209
UPROPERTY(BlueprintReadOnly)
Definition: Lidar.h:35
void ForceClearContainers()
Definition: Lidar.h:110
virtual FString GetParametersAsString() const override
Definition: Lidar.h:101
void SaveCurrentPointCloudToDisk()
Definition: Lidar.h:118
virtual ESensorTypes GetSensorType() const override
Definition: Lidar.h:52
Definition: Sensor.h:45
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: Weather.cpp:47
virtual void BeginPlay() override
Definition: Weather.cpp:22