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 UNiagaraComponent;
25class UWorld;
26class AWeather;
27
32UCLASS()
33class AGRARSENSE_API ALidar : public ASensor
34{
35 GENERATED_BODY()
36
37public:
38
39 ALidar(const FObjectInitializer& ObjectInitializer);
40
45 void Init(FLidarParameters parameters, bool SimulateSensor = true);
46
51 virtual ESensorTypes GetSensorType() const override
52 {
54 }
55
60 UFUNCTION(BlueprintCallable)
61 void ChangeLidarParameters(FLidarParameters newLidarParameters);
62
67 UFUNCTION(BlueprintCallable)
68 void SetVisualizeLidarParticles(bool Visualize);
69
74 UFUNCTION(BlueprintCallable)
75 void SetParticleLifeTime(float ParticleLifeTime);
76
81 UFUNCTION(BlueprintCallable, BlueprintPure)
82 FLidarParameters GetLidarParameters() const
83 {
84 return LidarParameters;
85 }
86
91 UFUNCTION(BlueprintCallable)
92 UNiagaraComponent* GetNiagaraComponent() const
93 {
94 return NiagaraComponent;
95 }
96
100 virtual FString GetParametersAsString() const override
101 {
102 return StructToString(LidarParameters);
103 }
104
105protected:
106
107 virtual void BeginPlay() override;
108
109 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
110
111private:
112
113 friend class ALidarManager;
114
119 std::vector<FPointData> SimulateRaycastLidar(const float DeltaTime);
120
125 UPROPERTY(VisibleAnywhere, Category = "Sensor")
126 UNiagaraComponent* NiagaraComponent = nullptr;
127
132 void SetNiagaraRendering(bool Enabled);
133
137 void VisualizeLidarParticles();
138
142 void ChangeParameters();
143
150 bool ShootLaser(FHitResult& HitResult, const FVector& EndTrace, const FCollisionQueryParams& TraceParams,
151 const FVector& LidarBodyLocation, const int32 Channel, const bool Semantic, const uint32 RGBDefault);
152
156 void ResetRecordedHits(int32 MaxPointsPerChannel);
157
163 uint32 GetSemanticData(const FHitResult& HitResult) const;
164
169 void SendData(const float DeltaTime);
170
174 bool CanSendData(const float DeltaTime);
175
176 /*
177 * Send this Lidar sensor data to its own ROS topic
178 */
179 void SendDataToTopic(const std::vector<FPointData>& points);
180
181 /*
182 * Asynchronously saves Lidar point cloud data to disk
183 */
184 void SaveDataToDisk();
185
186 /*
187 * Add extra processing to the current line trace hit result.
188 * @param HitResult - The hit result containing the impact point to which noise will be added.
189 * @param LidarBodyLocation - The location of the Lidar sensor
190 */
191 void AddProcessingToHitResult(FHitResult& HitResult, const FVector& LidarBodyLocation, const bool UseHorizontalNoise);
192
193 /*
194 * Applies distance noise to the hit result based on the standard deviation specified
195 * in the Lidar parameters. The noise is added to the impact point, simulating measurement
196 * inaccuracies by perturbing the hit point in the direction from the Lidar sensor towards
197 * the detected impact point. This noise mimics real-world sensor errors where measurements
198 * can vary around the true value.
199 * @param HitResult - The hit result containing the impact point to which noise will be added.
200 * @param LidarBodyLocation - The location of the Lidar sensor
201 */
202 void AddDistanceNoise(FHitResult& HitResult, const FVector& LidarBodyLocation);
203
204 /*
205 * Applies lateral noise to the hit result, introducing random deviation
206 * either vertically or horizontally, perpendicular to the Lidar linetrace origin direction.
207 * @param HitResult - The hit result containing the impact point to which noise will be added.
208 * @param LidarBodyLocation - The location of the Lidar sensor.
209 * @param UseHorizontalNoise - Direction to use.
210 */
211 void AddLateralNoise(FHitResult& HitResult, const FVector& LidarBodyLocation, const bool UseHorizontalNoise);
212
213 /*
214 * Adjusts the hit result for terrain snow.
215 * @param HitResult - The hit result containing the impact point to which noise will be added.
216 * @param LidarBodyLocation - The location of the Lidar sensor
217 */
218 void AddSnowTerrainAdjustment(FHitResult& HitResult, const FVector& LidarBodyLocation);
219
220 /*
221 * Updates Niagara particle system particles
222 */
223 void UpdateLidarParticles(int NumberOfHits, const TArray<FVector>& HitPoints, const TArray<FLinearColor>& Colors);
224
225 /*
226 * Callback event from AWeather when weather parameters has been changed.
227 */
228 UFUNCTION()
229 void OnWeatherChanged(FWeatherParameters WeatherParams);
230
231 UPROPERTY(VisibleAnywhere, Category = "Sensor")
232 FLidarParameters LidarParameters;
233
234 FLidarParameters TempLidarParameters;
235
236 FWeatherParameters CurrentWeatherParameters;
237
238 UPROPERTY()
239 UWorld* World = nullptr;
240
241 UPROPERTY()
242 TMap<FName, FColor> SemanticColors;
243
244 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> PointCloudMessage;
245
246 std::vector<std::vector<FPointData>> PreProcessedHitImpactPoints;
247 std::vector<std::vector<FPointData>> Points;
248 std::vector<FPointData> PointsFlattened;
249
250 std::vector<uint32_t> PointsPerChannel;
251 std::vector<float> LaserAngles;
252
253 std::random_device RandomDevice;
254 std::mt19937 Generator;
255
256 bool NeedToSavePointCloudWithoutNoise = false;
257 bool LidarParametersChanged = false;
258 bool SendDataEveryFrame = false;
259 bool ClearContainers = true;
260
261 float CurrentHorizontalAngle = 0.0f;
262 float SensorHzFrequency = 0.1f;
263 float SensorHzTimer = 0.0f;
264
265 float SnowHeightOffset = 0.0f;
266
267 int LidarSaves = 0;
268
269 uint32 CachedNoneColor;
270
271 uint32 CachedSnowflakeColor;
272};
ESensorTypes
Definition: SensorTypes.h:15
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: LidarManager.h:217
UPROPERTY(BlueprintReadOnly)
Definition: Lidar.h:34
virtual FString GetParametersAsString() const override
Definition: Lidar.h:100
virtual ESensorTypes GetSensorType() const override
Definition: Lidar.h:51
Definition: Sensor.h:44
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: Weather.cpp:47
virtual void BeginPlay() override
Definition: Weather.cpp:22