Agrarsense
Lidar.cpp
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#include "Lidar.h"
7
8#include "LidarNoiseModel.h"
16
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"
24#include "Landscape.h"
25#include "Async/ParallelFor.h"
26#include "Engine/GameViewportClient.h"
27#include "Engine/Engine.h"
28#include "Async/Async.h"
29
30#include <iterator>
31
32ALidar::ALidar(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
33{
34 // Lidar sensors are ticked by LidarManager.cpp
35 PrimaryActorTick.bCanEverTick = false;
36}
37
38void ALidar::Init(FLidarParameters parameters, bool SimulateSensor)
39{
40 LidarParameters = parameters;
41 SetSimulateSensor(SimulateSensor);
44
45 // Initialize PointCloudMessage
46 PointCloudMessage.Reset();
47 PointCloudMessage = MakeShared<ROSMessages::sensor_msgs::PointCloud2>();
48 PointCloudMessage->CreateDefaultPointCloud2Message();
49
50 Generator.seed(RandomDevice());
51}
52
54{
55 Super::BeginPlay();
56
57 UWorld* World = GetWorld();
58
59 // Create the SemanticColors TMap
60 TMap<FString, FColor> Colors = GetSemanticColors();
61 for (const auto& ColorEntry : Colors)
62 {
63 FName SemanticName = FName(*ColorEntry.Key);
64 SemanticColors.Add(SemanticName, ColorEntry.Value);
65 }
66
67 // Cache "None" and "Snowflake" colors for Semantic
68 FColor NoneColor = SemanticColors.FindRef("None");
69 FColor SnowflakeColor = SemanticColors.FindRef("Snowflake");
70 CachedNoneColor = (NoneColor.R << 16) | (NoneColor.G << 8) | (NoneColor.B << 0);
71 CachedSnowflakeColor = (SnowflakeColor.R << 16) | (SnowflakeColor.G << 8) | (SnowflakeColor.B << 0);
72
73 // Add this lidar to LidarManager that handles ticking of this sensor in parallel.
75 if (LidarManager)
76 {
77 LidarManager->AddRaycastLidar(this);
78 }
79
81 if (Weather)
82 {
84 Weather->OnWeatherChanged.AddUniqueDynamic(this, &ALidar::OnWeatherChanged);
85 }
86
87 // Load pointcloud Niagara particle system
88 UNiagaraSystem* NS = LoadObject<UNiagaraSystem>(nullptr, TEXT("/Game/Agrarsense/Particles/PointCloud/NS_PointCloudSemanticFast"), nullptr, LOAD_None, nullptr);
89 if (NS)
90 {
91 NiagaraComponent = UNiagaraFunctionLibrary::SpawnSystemAtLocation(World, NS, GetActorLocation());
93 {
94 // Hide this NiagaraComponent for all Camera sensors.
95 HideComponentForAllCameras(Cast<UPrimitiveComponent>(NiagaraComponent));
96
97 NiagaraComponent->SetAffectDynamicIndirectLighting(false);
98 NiagaraComponent->SetAffectDistanceFieldLighting(false);
99 NiagaraComponent->SetCastContactShadow(false);
100 NiagaraComponent->SetCastShadow(false);
101
103 }
104 }
105#if WITH_EDITOR
106 else
107 {
108 UE_LOG(LogTemp, Warning, TEXT("Lidar.cpp: Couldn't find Niagara particle system."));
109 }
110#endif
111}
112
113void ALidar::EndPlay(const EEndPlayReason::Type EndPlayReason)
114{
115 Super::EndPlay(EndPlayReason);
116
117 UWorld* World = GetWorld();
118
119 // Remove this lidar from LidarManager
121 if (LidarManager)
122 {
123 LidarManager->RemoveRaycastLidar(this);
124 }
125
126 // Unbind from Weather changed event
128 if (Weather)
129 {
130 Weather->OnWeatherChanged.RemoveDynamic(this, &ALidar::OnWeatherChanged);
131 }
132
134 {
135 SetNiagaraRendering(false);
136
137 // Destroy component
138 NiagaraComponent->UnregisterComponent();
139 NiagaraComponent->DestroyComponent();
140 NiagaraComponent = nullptr;
141 }
142
143 PointCloudMessage.Reset();
145 PointsFlattened.clear();
146 LaserAngles.clear();
147 Points.clear();
148}
149
151{
152 CurrentWeatherParameters = WeatherParams;
153
154 // Here we recalculate SnowHeightOffset when Weather changes.
155 // This is fine-tuned by hand. If the Snow implementation would change meaningfully,
156 // we would need to change this implementation as well.
157 // See AddSnowTerrainAdjustment() function how SnowHeightOffset is used.
159 SnowHeightOffset *= 1e-2;
160}
161
163{
164 // Ensure certain parameters are valid ranges
165 LidarParameters.HorizontalFov = FMath::Clamp(LidarParameters.HorizontalFov, 0.1f, 360.0f);
169
170 const int32 NumberOfLasers = LidarParameters.Channels;
171
172 // Resize arrays
173 PreProcessedHitImpactPoints.resize(NumberOfLasers);
174 Points.resize(NumberOfLasers);
175
176 // Create Lidar linetrace angles
177 LaserAngles.clear();
178 const float DeltaAngle = NumberOfLasers == 1u ? 0.f : (LidarParameters.UpperFovLimit - LidarParameters.LowerFovLimit) / static_cast<float>(NumberOfLasers - 1);
179
180 for (int32 i = 0; i < NumberOfLasers; ++i)
181 {
182 const float VerticalAngle = LidarParameters.UpperFovLimit - static_cast<float>(i) * DeltaAngle;
183 LaserAngles.emplace_back(VerticalAngle);
184 }
185
189
190 if (LidarParameters.PointsPerSecond > 1000000)
191 {
192 SimulatorLog::Log("Lidar sensor: It's highly advisable to turn off VisualizePointcloud when PointsPerSecond exceed 1 million.");
193
194 if (LidarParameters.PointsPerSecond > 2000000)
195 {
197 SimulatorLog::Log("Lidar sensor: VisualizePointcloud has been set to false due PointsPerSecond exceeding 2 million.");
198 }
199 }
200
203}
204
206{
207 SetNiagaraRendering(Visualize);
208}
209
211{
213 {
214 if (!Enabled)
215 {
216 TArray<FVector> EmptyHitpoints;
217 TArray<FLinearColor> EmptyColors;
218 UpdateLidarParticles(0, EmptyHitpoints, EmptyColors);
219 }
220
221 NiagaraComponent->SetRenderingEnabled(Enabled);
222 }
223}
224
225void ALidar::UpdateLidarParticles(int32 NumberOfHits, const TArray<FVector>& HitPoints, const TArray<FLinearColor>& Colors)
226{
228 {
229 NiagaraComponent->SetVariableFloat(NiagaraPointsFloat, float(NumberOfHits));
230 NiagaraComponent->SetVariableInt(NiagaraPointsInt, NumberOfHits);
231 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayVector(NiagaraComponent, NiagaraHitPoints, HitPoints);
232 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayColor(NiagaraComponent, NiagaraHitColors, Colors);
233 }
234}
235
236void ALidar::SetParticleLifeTime(float ParticleLifeTime)
237{
239 {
240 NiagaraComponent->SetVariableFloat(FName("User.LifeTime"), ParticleLifeTime);
241 }
242}
243
244std::vector<FPointData> ALidar::SimulateRaycastLidar(const float DeltaTime)
245{
246 TRACE_CPUPROFILER_EVENT_SCOPE(ALidar::SimulateRaycastLidar);
247
248 std::vector<FPointData> HitPoints;
249
250 if (!CanSimulateSensor())
251 {
252 return HitPoints;
253 }
254
255 // Get sensor position and rotation
256 const FTransform& ActorTransform = GetTransform();
257 const FVector LidarBodyLocation = ActorTransform.GetLocation();
258 const FRotator LidarBodyRotation = ActorTransform.Rotator();
259 const FMatrix LidarRotationMatrix = FRotationMatrix(FQuat(LidarBodyRotation).Rotator());
260
261 // Prepare needed variables for processing
262 const int32 ChannelCount = LidarParameters.Channels;
263 const int32 PointsToScanWithOneChannel = FMath::RoundHalfFromZero(LidarParameters.PointsPerSecond * DeltaTime / float(ChannelCount));
264 const float HorizontalAngle = CurrentHorizontalAngle;
265 const float AngleDistanceOfTick = LidarParameters.RotationFrequency * LidarParameters.HorizontalFov * DeltaTime;
266 const float AngleDistanceOfLaserMeasure = AngleDistanceOfTick / PointsToScanWithOneChannel;
267 const float Range = LidarParameters.Range * 100; // to meters
268
269 const FColor Color = FColor(255, 255, 255);
270 const int32 RgbDefault = (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
271
272 FCollisionQueryParams TraceParams = FCollisionQueryParams(FName(TEXT("Laser_Trace")), true, this);
273 TraceParams.bReturnPhysicalMaterial = false;
274
275 // Note. can become very expensive with high vertice meshes.
276 // Any very high vertice mesh should have simpler collision mesh (Tree for example)
277 TraceParams.bTraceComplex = LidarParameters.UseComplexCollisionTrace;
278
279 // Check if we are going to add any noise
283
284 // Check if separate point cloud should be saved without the noise
285 NeedToSavePointCloudWithoutNoise = ShouldAddNoise
288
289 const bool Semantic = LidarParameters.Semantic;
291 const bool NeedsExtraProcessing = UseSnowTerrainAdjustment || LidarParameters.DistanceNoiseStdDev > 0.0f || LidarParameters.LateralNoiseStdDev > 0.0f;
292 const bool UseLidarNoiseModel = LidarParameters.UseLidarNoiseModel;
293
294 const float HorizontalFOV = LidarParameters.HorizontalFov;
295 const float HorizontalFOVHalf = HorizontalFOV / 2;
296
297 const UWorld* World = GetWorld();
298
299 ResetRecordedHits(PointsToScanWithOneChannel);
300
301 // Loop Lidar channels in Parallel
302 ParallelFor(ChannelCount, [&](int32 Channel)
303 {
304 const float VerticalAngle = LaserAngles[Channel];
305 int32 RGB = RgbDefault;
306 FHitResult HitResult;
307
308 // Generate random bool which we use later in AddLateralNoise
309 const bool UseHorizontalNoise = FMath::RandBool();
310
311 // Cache the reference to Points[idxChannel]
312 std::vector<FPointData>& ChannelPoints = Points[Channel];
313
314 // Loop through this channel linetraces
315 for (int32 i = 0; i < PointsToScanWithOneChannel; i++)
316 {
317 //HitResult.Reset();
318
319 // Calculate the EndTrace point for this linetrace
320 const float LaserHorizontalAngle = std::fmod(HorizontalAngle + AngleDistanceOfLaserMeasure * i, HorizontalFOV) - HorizontalFOVHalf;
321 const float VerticalRad = FMath::DegreesToRadians(VerticalAngle);
322 const float HorizontalRad = FMath::DegreesToRadians(LaserHorizontalAngle);
323
324 const FVector LocalDirection(FMath::Cos(VerticalRad) * FMath::Cos(HorizontalRad),
325 FMath::Cos(VerticalRad) * FMath::Sin(HorizontalRad),
326 FMath::Sin(VerticalRad));
327
328 const FVector EndTrace = LidarBodyLocation + Range * LidarRotationMatrix.TransformVector(LocalDirection);
329
330 if (ShootLaser(World, HitResult, EndTrace, TraceParams, LidarBodyLocation, Channel, Semantic, RgbDefault, UseLidarNoiseModel))
331 {
332 if (Semantic)
333 {
334 RGB = GetSemanticData(HitResult);
335 }
336
337 if (NeedsExtraProcessing)
338 {
339 AddProcessingToHitResult(HitResult, LidarBodyLocation, UseHorizontalNoise, UseSnowTerrainAdjustment);
340 }
341
342 // Add HitResult impact point to the current channel's point list
343 const FVector& HitPoint = HitResult.ImpactPoint;
344 ChannelPoints.emplace_back(HitPoint.X, HitPoint.Y, HitPoint.Z, RGB);
345 }
346 }
347 }, EParallelForFlags::Unbalanced);
348
349 CurrentHorizontalAngle = FMath::Fmod(HorizontalAngle + AngleDistanceOfTick, LidarParameters.HorizontalFov);
350
351 SendData(DeltaTime);
352
354 {
358 }
359
361 {
362 return PointsFlattened;
363 }
364
365 return HitPoints;
366}
367
368void ALidar::AddProcessingToHitResult(FHitResult& HitResult, const FVector& LidarBodyLocation, const bool UseHorizontalNoise, const bool UseSnowTerrainAdjustment)
369{
370 if (UseSnowTerrainAdjustment)
371 {
372 AddSnowTerrainAdjustment(HitResult, LidarBodyLocation);
373 }
374
376 {
377 AddDistanceNoise(HitResult, LidarBodyLocation);
378 }
379
381 {
382 AddLateralNoise(HitResult, LidarBodyLocation, UseHorizontalNoise);
383 }
384}
385
386void ALidar::AddDistanceNoise(FHitResult& HitResult, const FVector& LidarBodyLocation)
387{
388 std::normal_distribution<float> Distribution(0.0f, LidarParameters.DistanceNoiseStdDev);
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;
393}
394
395void ALidar::AddLateralNoise(FHitResult& HitResult, const FVector& LidarBodyLocation, const bool UseHorizontalNoise)
396{
397 const FVector ForwardVector = (HitResult.ImpactPoint - LidarBodyLocation).GetSafeNormal();
398 const FVector RightVector = FVector::CrossProduct(ForwardVector, FVector::UpVector).GetSafeNormal();
399
400 FVector ChosenDirection;
401 if (UseHorizontalNoise)
402 {
403 ChosenDirection = RightVector;
404 }
405 else
406 {
407 FVector UpVector = FVector::CrossProduct(ForwardVector, RightVector).GetSafeNormal();
408 ChosenDirection = UpVector;
409 }
410
411 std::normal_distribution<float> Distribution(0.0f, LidarParameters.LateralNoiseStdDev);
412 const float NoiseValue = Distribution(Generator);
413
414 HitResult.ImpactPoint += ChosenDirection * NoiseValue;
415}
416
417void ALidar::AddSnowTerrainAdjustment(FHitResult& HitResult, const FVector& LidarBodyLocation)
418{
419 AActor* HitActor = HitResult.GetActor();
420
421 // Terrain should have tag "Terrain" in order to make this work.
422 if (HitActor && HitActor->Tags.Contains(TerrainTag))
423 {
424 // Scale the Z value of ImpactPoint based on SnowHeightOffset.
425 HitResult.ImpactPoint.Z += SnowHeightOffset;
426 }
427}
428
429void ALidar::VisualizeLidarParticles(std::vector<FPointData> HitPoints)
430{
431 TRACE_CPUPROFILER_EVENT_SCOPE(ALidar::VisualizeLidarParticles);
432
433 if (!LidarParameters.VisualizePointcloud || !NiagaraComponent || HitPoints.empty())
434 {
435 return;
436 }
437
438 if (GEngine && GEngine->GameViewport && GEngine->GameViewport->bDisableWorldRendering)
439 {
440 // If world rendering (Spectator camera) is disabled, no need to update the particle system.
441 return;
442 }
443
444 // Convert std::vector<FPointData> to
445 // TArray<FVector> and TArray<FLinearColor> for Niagara visualization.
446 int32 NumberOfHits = HitPoints.size();
447
448 // Create and allocate HitLocations TArray
449 TArray<FVector> HitLocations;
450 HitLocations.SetNumUninitialized(NumberOfHits);
451
452 // Create and set initial colors to green
453 TArray<FLinearColor> Colors;
454 Colors.Init(FLinearColor::Green, NumberOfHits);
455
456 // Pointer access for reduced overhead
457 FVector* HitLocationPtr = HitLocations.GetData();
458 FLinearColor* ColorsPtr = Colors.GetData();
459
460 const bool Semantic = LidarParameters.Semantic;
461
462 for (int32 i = 0; i < NumberOfHits; ++i)
463 {
464 const FPointData& point = HitPoints[i];
465
466 HitLocationPtr[i].X = point.X;
467 HitLocationPtr[i].Y = (point.Y * -1);
468 HitLocationPtr[i].Z = point.Z;
469
470 if (Semantic)
471 {
472 // Convert point.RGB (uint32) to FLinearColor
473 uint8 R = (point.RGB >> 16) & 0xFF;
474 uint8 G = (point.RGB >> 8) & 0xFF;
475 uint8 B = point.RGB & 0xFF;
476
477 ColorsPtr[i].R = R / 255.0f;
478 ColorsPtr[i].G = G / 255.0f;
479 ColorsPtr[i].B = B / 255.0f;
480 //ColorsPtr[i].A = 1.0f;
481 }
482 }
483 UpdateLidarParticles(NumberOfHits, HitLocations, Colors);
484}
485
486void ALidar::SendData(const float DeltaTime)
487{
488 if (!CanSendData(DeltaTime))
489 {
490 return;
491 }
492
493 // Preallocate PointsFlattened size
494 // and fill PointsFlattened
495 size_t TotalSize = 0;
496 for (const std::vector<FPointData>& Vec : Points)
497 {
498 TotalSize += Vec.size();
499 }
500 PointsFlattened.reserve(TotalSize);
501
502 for (std::vector<FPointData>& HitPoints : Points)
503 {
504 PointsFlattened.insert(PointsFlattened.end(), std::make_move_iterator(HitPoints.begin()), std::make_move_iterator(HitPoints.end()));
505 }
506
508 {
510 }
511
512 if (SendDataToROS)
513 {
515 }
516}
517
518bool ALidar::CanSendData(const float DeltaTime)
519{
521 {
522 ClearContainers = true;
523 return true;
524 }
525
526 SensorHzTimer += DeltaTime;
528 {
529 SensorHzTimer = 0.0f;
530 ClearContainers = true;
531 return true;
532 }
533 else
534 {
535 ClearContainers = false;
536 return false;
537 }
538}
539
541{
542 if (!CanSimulateSensor())
543 {
544 // We are not currently simulating sensor, we can safely change parameters here
545 LidarParameters = newLidarParameters;
547 }
548 else
549 {
550 // Change parameters at the end of the frame
551 TempLidarParameters = newLidarParameters;
553 }
554}
555
556uint32 ALidar::GetSemanticData(const FHitResult& HitResult) const
557{
558 auto* HitComponent = HitResult.Component.Get();
559
560 if (HitComponent)
561 {
562 TArray<FName>& CompTags = HitComponent->ComponentTags;
563 if (!CompTags.IsEmpty())
564 {
565 FName Tag = CompTags[0]; // First component tag should be the tag we want.
566 FColor Color = SemanticColors.FindRef(Tag);
567 return (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
568 }
569 else
570 {
571 return CachedNoneColor;
572 }
573 }
574 else
575 {
577 }
578}
579
580bool ALidar::ShootLaser(const UWorld* World, FHitResult& HitResult, const FVector& EndTrace, const FCollisionQueryParams& TraceParams,
581 const FVector& LidarBodyLocation, const int32 Channel, const bool Semantic, const uint32 RGBDefault, const bool UseLidarNoiseModel)
582{
583#ifdef ParallelLineTraceSingleByChannel_EXISTS
584 // Defined and implemented in our AGRARSENSE Unreal Engine fork
585 // This LineTrace method doesn't block the physics scene which improves linetrace performance.
586 World->ParallelLineTraceSingleByChannel(
587 HitResult,
588 LidarBodyLocation,
589 EndTrace,
590 ECC_GameTraceChannel3,
591 TraceParams,
592 FCollisionResponseParams::DefaultResponseParam);
593#else
594 // If not using our fork of the engine, use default LineTrace method.
595 World->LineTraceSingleByChannel(
596 HitResult,
597 LidarBodyLocation,
598 EndTrace,
599 ECC_GameTraceChannel3,
600 TraceParams,
601 FCollisionResponseParams::DefaultResponseParam);
602#endif
603
604 bool BlockingHit = HitResult.IsValidBlockingHit();
605 if (!BlockingHit && !UseLidarNoiseModel)
606 {
607 return false;
608 }
609
610 // Scale the pointcloud
611 HitResult.ImpactPoint *= 1e-2;
612
613 // Flip Y axis
614 HitResult.ImpactPoint.Y *= -1;
615
617 {
618 // Save Original FHitResult to separate array
619 FHitResult OriginalHitResultCopy = HitResult;
620 uint32 RGB = RGBDefault;
621 if (Semantic)
622 {
623 // If Lidar is set to Semantic, set point color
624 RGB = GetSemanticData(OriginalHitResultCopy);
625 }
626 const FVector& HitPoint = OriginalHitResultCopy.ImpactPoint;
627 FPointData point = { HitPoint.X, HitPoint.Y, HitPoint.Z, RGB };
628 PreProcessedHitImpactPoints[Channel].emplace_back(point);
629 }
630
631 if (UseLidarNoiseModel)
632 {
633 // Check whether we "hit" snowflake by using LUAS formula
634 bool HitSnowFlake = LidarNoiseModel::CheckSnowflakeHit(HitResult, EndTrace, LidarBodyLocation, CurrentWeatherParameters);
635 BlockingHit = HitResult.bBlockingHit || HitSnowFlake;
636 }
637
638 return BlockingHit;
639}
640
641void ALidar::ResetRecordedHits(int32 MaxPointsPerChannel)
642{
643 if (!ClearContainers)
644 {
645 return;
646 }
647
648 // Visualize Lidar particles on main thread because,
649 // in some instances NiagaraComponent crashes when updating points from background thread.
650 std::vector<FPointData> CopiedPoints = PointsFlattened;
651 AsyncTask(ENamedThreads::GameThread, [this, CopiedPoints]()
652 {
653 VisualizeLidarParticles(CopiedPoints);
654 });
655
657 {
658 // If we only send data at Lidar sensor rotation frequency
659 // reserve enough points to fill all points
661 }
662
663 // Clear all containers
665 {
666 for (std::vector<FPointData>& ImpactPoints : PreProcessedHitImpactPoints)
667 {
668 ImpactPoints.clear();
669 ImpactPoints.reserve(MaxPointsPerChannel);
670 }
671 }
672
673 for (std::vector<FPointData>& ImpactPoints : Points)
674 {
675 ImpactPoints.clear();
676 ImpactPoints.reserve(MaxPointsPerChannel);
677 }
678
679 PointsFlattened.clear();
680}
681
682void ALidar::SendDataToTopic(const std::vector<FPointData>& points)
683{
684 UTopic* Topic = GetROSTopic();
685
686 if (!IsROSConnected()
687 || !Topic
688 || !SendDataToROS
689 || !PointCloudMessage.IsValid()
690 || points.empty())
691 {
692 return;
693 }
694
695 const size_t PointsSize = points.size();
696 const size_t DataSize = PointsSize * sizeof(FPointData);
697
698 PointCloudMessage->width = static_cast<uint32>(PointsSize);
699 PointCloudMessage->row_step = static_cast<uint32>(DataSize);
700 PointCloudMessage->data_ptr = reinterpret_cast<uint8*>(const_cast<FPointData*>(points.data()));
701 Topic->Publish(PointCloudMessage);
702}
703
705{
707 {
708 return;
709 }
710
711 // Save point cloud to disk
712 FString Filename = FString::Printf(TEXT("%sLidar_%d.ply"), *FileSavePath, LidarSaves);
714
716 {
717 // Flatten 2D std::vector to 1D std::vector
718 std::vector<FPointData> PointsWithOutNoiseModel;
719
720 size_t totalSize = 0;
721 for (const std::vector<FPointData>& Vec : PreProcessedHitImpactPoints)
722 {
723 totalSize += Vec.size();
724 }
725 PointsWithOutNoiseModel.reserve(totalSize);
726
727 for (const std::vector<FPointData>& Vec : PreProcessedHitImpactPoints)
728 {
729 PointsWithOutNoiseModel.insert(PointsWithOutNoiseModel.end(), Vec.begin(), Vec.end());
730 }
731
732 // Save pointcloud to disk without any noise
733 FString PreprocessedFilename = FString::Printf(TEXT("%sLidar_%d_without_noise_model.ply"), *FileSavePath, LidarSaves);
734 UPointcloudUtilities::SaveVectorArrayAsPlyAsync(PreprocessedFilename, PointsWithOutNoiseModel);
735 }
736
737 ++LidarSaves;
738}
void AddRaycastLidar(ALidar *lidarPtr)
void RemoveRaycastLidar(ALidar *lidarPtr)
UNiagaraComponent * NiagaraComponent
Definition: Lidar.h:126
TMap< FName, FColor > SemanticColors
Definition: Lidar.h:239
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)
Definition: Lidar.cpp:580
FWeatherParameters CurrentWeatherParameters
Definition: Lidar.h:236
std::random_device RandomDevice
Definition: Lidar.h:250
FORCEINLINE uint32 GetSemanticData(const FHitResult &HitResult) const
Definition: Lidar.cpp:556
void VisualizeLidarParticles(std::vector< FPointData > HitPoints)
Definition: Lidar.cpp:429
void Init(FLidarParameters parameters, bool SimulateSensor=true)
Definition: Lidar.cpp:38
const FName TerrainTag
Definition: Lidar.h:258
void UpdateLidarParticles(int32 NumberOfHits, const TArray< FVector > &HitPoints, const TArray< FLinearColor > &Colors)
Definition: Lidar.cpp:225
float SensorHzFrequency
Definition: Lidar.h:261
void SendData(const float DeltaTime)
Definition: Lidar.cpp:486
void AddLateralNoise(FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise)
Definition: Lidar.cpp:395
void ChangeLidarParameters(FLidarParameters newLidarParameters)
Definition: Lidar.cpp:540
bool CanSendData(const float DeltaTime)
Definition: Lidar.cpp:518
std::vector< std::vector< FPointData > > PreProcessedHitImpactPoints
Definition: Lidar.h:243
void SaveDataToDisk()
Definition: Lidar.cpp:704
void ResetRecordedHits(int32 MaxPointsPerChannel)
Definition: Lidar.cpp:641
ALidar(const FObjectInitializer &ObjectInitializer)
Definition: Lidar.cpp:32
uint32 CachedSnowflakeColor
Definition: Lidar.h:270
std::vector< float > LaserAngles
Definition: Lidar.h:248
void SetParticleLifeTime(float ParticleLifeTime)
Definition: Lidar.cpp:236
std::mt19937 Generator
Definition: Lidar.h:251
bool LidarParametersChanged
Definition: Lidar.h:254
void ChangeParameters()
Definition: Lidar.cpp:162
int32 LidarSaves
Definition: Lidar.h:266
void OnWeatherChanged(FWeatherParameters WeatherParams)
Definition: Lidar.cpp:150
float SnowHeightOffset
Definition: Lidar.h:264
virtual void BeginPlay() override
Definition: Lidar.cpp:53
FLidarParameters TempLidarParameters
Definition: Lidar.h:234
void AddDistanceNoise(FHitResult &HitResult, const FVector &LidarBodyLocation)
Definition: Lidar.cpp:386
void SetNiagaraRendering(bool Enabled)
Definition: Lidar.cpp:210
std::vector< std::vector< FPointData > > Points
Definition: Lidar.h:245
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
Definition: Lidar.cpp:244
uint32 CachedNoneColor
Definition: Lidar.h:268
bool ClearContainers
Definition: Lidar.h:256
bool NeedToSavePointCloudWithoutNoise
Definition: Lidar.h:253
std::vector< FPointData > PointsFlattened
Definition: Lidar.h:246
void SetVisualizeLidarParticles(bool Visualize)
Definition: Lidar.cpp:205
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: Lidar.h:241
void SendDataToTopic(const std::vector< FPointData > &points)
Definition: Lidar.cpp:682
void AddSnowTerrainAdjustment(FHitResult &HitResult, const FVector &LidarBodyLocation)
Definition: Lidar.cpp:417
bool SendDataEveryFrame
Definition: Lidar.h:255
float SensorHzTimer
Definition: Lidar.h:262
FLidarParameters LidarParameters
Definition: Lidar.h:232
void AddProcessingToHitResult(FHitResult &HitResult, const FVector &LidarBodyLocation, const bool UseHorizontalNoise, const bool UseSnowTerrainAdjustment)
Definition: Lidar.cpp:368
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
Definition: Lidar.cpp:113
float CurrentHorizontalAngle
Definition: Lidar.h:260
static const FName NiagaraHitPoints
Definition: Sensor.h:358
bool CanSimulateSensor() const
Definition: Sensor.h:161
static void HideComponentForAllCameras(UPrimitiveComponent *PrimitiveComponent)
Definition: Sensor.cpp:282
static const FName NiagaraPointsFloat
Definition: Sensor.h:360
virtual void CreateDataSavePath()
Definition: Sensor.cpp:229
void SetSimulateSensor(bool SimulateSensor)
Definition: Sensor.h:151
UTopic * GetROSTopic() const
Definition: Sensor.h:141
bool SendDataToROS
Definition: Sensor.h:344
static const FName NiagaraHitColors
Definition: Sensor.h:359
FString FileSavePath
Definition: Sensor.h:349
FORCEINLINE bool IsROSConnected() const
Definition: Sensor.h:192
virtual void CreateROSTopic()
Definition: Sensor.cpp:173
static const FName NiagaraPointsInt
Definition: Sensor.h:357
static TMap< FString, FColor > GetSemanticColors()
Definition: Sensor.cpp:292
const FWeatherParameters & GetCurrentWeather() const
Definition: Weather.h:76
FLevelEventDelegate_WeatherChanged OnWeatherChanged
Definition: Weather.h:85
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)
bool SendDataAtRotationFrequency
bool SavePointcloudWithoutNoiseModel
bool UseTerrainSnowHitAdjustment
float Z
Definition: PointData.h:19
float Y
Definition: PointData.h:17
float X
Definition: PointData.h:15
uint32 RGB
Definition: PointData.h:21