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
29#include <iterator>
30
31ALidar::ALidar(const FObjectInitializer& ObjectInitializer) : Super(ObjectInitializer)
32{
33 // Lidar sensors are ticked by LidarManager.cpp
34 PrimaryActorTick.bCanEverTick = false;
35}
36
37void ALidar::Init(FLidarParameters parameters, bool SimulateSensor)
38{
39 LidarParameters = parameters;
40 SetSimulateSensor(SimulateSensor);
43
44 // Initialize PointCloudMessage
45 PointCloudMessage.Reset();
46 PointCloudMessage = MakeShared<ROSMessages::sensor_msgs::PointCloud2>();
47 PointCloudMessage->CreateDefaultPointCloud2Message();
48
49 Generator.seed(RandomDevice());
50}
51
53{
54 Super::BeginPlay();
55
56 World = GetWorld();
57
58 // Create the SemanticColors TMap
59 TMap<FString, FColor> Colors = GetSemanticColors();
60 for (const auto& ColorEntry : Colors)
61 {
62 FName SemanticName = FName(*ColorEntry.Key);
63 SemanticColors.Add(SemanticName, ColorEntry.Value);
64 }
65
66 // Cache "None" and "Snowflake" colors for Semantic
67 FColor NoneColor = SemanticColors.FindRef("None");
68 FColor SnowflakeColor = SemanticColors.FindRef("Snowflake");
69 CachedNoneColor = (NoneColor.R << 16) | (NoneColor.G << 8) | (NoneColor.B << 0);
70 CachedSnowflakeColor = (SnowflakeColor.R << 16) | (SnowflakeColor.G << 8) | (SnowflakeColor.B << 0);
71
72 // Add this lidar to LidarManager that handles ticking of this sensor in parallel.
74 if (LidarManager)
75 {
76 LidarManager->AddRaycastLidar(this);
77 }
78
80 if (Weather)
81 {
83 Weather->OnWeatherChanged.AddUniqueDynamic(this, &ALidar::OnWeatherChanged);
84 }
85
86 // Load pointcloud Niagara particle system
87 UNiagaraSystem* NS = LoadObject<UNiagaraSystem>(nullptr, TEXT("/Game/Agrarsense/Particles/PointCloud/NS_PointCloudSemanticFast"), nullptr, LOAD_None, nullptr);
88 if (NS)
89 {
90 NiagaraComponent = UNiagaraFunctionLibrary::SpawnSystemAtLocation(World, NS, GetActorLocation());
92 {
93 // Hide this NiagaraComponent for all Camera sensors.
94 HideComponentForAllCameras(Cast<UPrimitiveComponent>(NiagaraComponent));
95
96 NiagaraComponent->SetAffectDynamicIndirectLighting(false);
97 NiagaraComponent->SetAffectDistanceFieldLighting(false);
98 NiagaraComponent->SetCastContactShadow(false);
99 NiagaraComponent->SetCastShadow(false);
100
102 }
103 }
104#if WITH_EDITOR
105 else
106 {
107 UE_LOG(LogTemp, Warning, TEXT("Lidar.cpp: Couldn't find Niagara particle system."));
108 }
109#endif
110}
111
112void ALidar::EndPlay(const EEndPlayReason::Type EndPlayReason)
113{
114 Super::EndPlay(EndPlayReason);
115
116 World = GetWorld();
117
118 // Remove this lidar from LidarManager
120 if (LidarManager)
121 {
122 LidarManager->RemoveRaycastLidar(this);
123 }
124
125 // Unbind from Weather changed event
127 if (Weather)
128 {
129 Weather->OnWeatherChanged.RemoveDynamic(this, &ALidar::OnWeatherChanged);
130 }
131
133 {
134 SetNiagaraRendering(false);
135
136 // Destroy component
137 NiagaraComponent->UnregisterComponent();
138 NiagaraComponent->DestroyComponent();
139 NiagaraComponent = nullptr;
140 }
141
142 PointCloudMessage.Reset();
143
144 World = nullptr;
145
146 // Clear all containers on EndPlay
148 PointsFlattened.clear();
149 LaserAngles.clear();
150 Points.clear();
151}
152
154{
155 CurrentWeatherParameters = WeatherParams;
156
157 // Here we recalculate SnowHeightOffset when Weather changes.
158 // This is fine-tuned by hand. If the Snow implementation would change meaningfully,
159 // we would need to change this implemenation as well.
160 // See AddSnowTerrainAdjustment() function how SnowHeightOffset is used.
162 SnowHeightOffset *= 1e-2;
163}
164
166{
167 // Ensure certain parameters are valid ranges
168 LidarParameters.HorizontalFov = FMath::Clamp(LidarParameters.HorizontalFov, 0.1f, 360.0f);
172
173 const int32 NumberOfLasers = LidarParameters.Channels;
174
175 // Resize arrays
176 PreProcessedHitImpactPoints.resize(NumberOfLasers);
177 Points.resize(NumberOfLasers);
178
179 // Create Lidar linetrace angles
180 LaserAngles.clear();
181 const float DeltaAngle = NumberOfLasers == 1u ? 0.f : (LidarParameters.UpperFovLimit - LidarParameters.LowerFovLimit) / static_cast<float>(NumberOfLasers - 1);
182
183 for (int32 i = 0; i < NumberOfLasers; ++i)
184 {
185 const float VerticalAngle = LidarParameters.UpperFovLimit - static_cast<float>(i) * DeltaAngle;
186 LaserAngles.emplace_back(VerticalAngle);
187 }
188
192
193 if (LidarParameters.PointsPerSecond > 1000000)
194 {
195 SimulatorLog::Log("Lidar sensor: It's highly advisable to turn off VisualizePointcloud when PointsPerSecond exceed 1 million.");
196
197 if (LidarParameters.PointsPerSecond > 2000000)
198 {
200 SimulatorLog::Log("Lidar sensor: VisualizePointcloud has been set to false due PointsPerSecond exceeding 2 million.");
201 }
202 }
203
206}
207
209{
210 SetNiagaraRendering(Visualize);
211}
212
214{
216 {
217 if (!Enabled)
218 {
219 TArray<FVector> EmptyHitpoints;
220 TArray<FLinearColor> EmptyColors;
221 UpdateLidarParticles(0, EmptyHitpoints, EmptyColors);
222 }
223
224 NiagaraComponent->SetRenderingEnabled(Enabled);
225 }
226}
227
228void ALidar::UpdateLidarParticles(int32 NumberOfHits, const TArray<FVector>& HitPoints, const TArray<FLinearColor>& Colors)
229{
231 {
232 NiagaraComponent->SetVariableFloat(NiagaraPointsFloat, float(NumberOfHits));
233 NiagaraComponent->SetVariableInt(NiagaraPointsInt, NumberOfHits);
234 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayVector(NiagaraComponent, NiagaraHitPoints, HitPoints);
235 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayColor(NiagaraComponent, NiagaraHitColors, Colors);
236 }
237}
238
239void ALidar::SetParticleLifeTime(float ParticleLifeTime)
240{
242 {
243 NiagaraComponent->SetVariableFloat(FName("User.LifeTime"), ParticleLifeTime);
244 }
245}
246
247std::vector<FPointData> ALidar::SimulateRaycastLidar(const float DeltaTime)
248{
249 TRACE_CPUPROFILER_EVENT_SCOPE(ALidar::SimulateRaycastLidar);
250
251 std::vector<FPointData> HitPoints;
252
253 if (!CanSimulateSensor())
254 {
255 return HitPoints;
256 }
257
258 // Get sensor position and rotation
259 const FTransform ActorTransform = GetTransform();
260 const FVector LidarBodyLocation = ActorTransform.GetLocation();
261 const FRotator LidarBodyRotation = ActorTransform.Rotator();
262 const FQuat LidarBodyQuat = FQuat(LidarBodyRotation);
263
264 // Prepare needed variables for processing
265 const int32 ChannelCount = LidarParameters.Channels;
266 const int32 PointsToScanWithOneChannel = FMath::RoundHalfFromZero(LidarParameters.PointsPerSecond * DeltaTime / float(ChannelCount));
267 const float HorizontalAngle = CurrentHorizontalAngle;
268 const float AngleDistanceOfTick = LidarParameters.RotationFrequency * LidarParameters.HorizontalFov * DeltaTime;
269 const float AngleDistanceOfLaserMeasure = AngleDistanceOfTick / PointsToScanWithOneChannel;
270 const float Range = LidarParameters.Range * 100; // to meters
271
272 const FColor Color = FColor(255, 255, 255);
273 const int32 RgbDefault = (Color.R << 16) | (Color.G << 8) | (Color.B << 0);
274
275 FCollisionQueryParams TraceParams = FCollisionQueryParams(FName(TEXT("Laser_Trace")), true, this);
276 TraceParams.bReturnPhysicalMaterial = false;
277
278 // Note. can become very expensive with high vertice meshes.
279 // Any very high vertice mesh should have simpler collision mesh (Tree for example)
280 TraceParams.bTraceComplex = LidarParameters.UseComplexCollisionTrace;
281
282 // Check if we are going to add any noise
286
287 // Check if separate point cloud should be saved without the noise
288 NeedToSavePointCloudWithoutNoise = ShouldAddNoise
291
292 const bool Semantic = LidarParameters.Semantic;
294 const bool NeedsExtraProcessing = UseSnowTerrainAdjustment || LidarParameters.DistanceNoiseStdDev > 0.0f || LidarParameters.LateralNoiseStdDev > 0.0f;
295 const bool UseLidarNoiseModel = LidarParameters.UseLidarNoiseModel;
296
297 const float HorizontalFOV = LidarParameters.HorizontalFov;
298 const float HorizontalFOVHalf = HorizontalFOV / 2;
299
300 ResetRecordedHits(PointsToScanWithOneChannel);
301
302 // Loop Lidar channels in Parallel
303 ParallelFor(ChannelCount, [&](int32 Channel)
304 {
305 const float VerticalAngle = LaserAngles[Channel];
306 int32 RGB = RgbDefault;
307
308 FRotator LaserRotation;
309 FHitResult HitResult;
310 FVector EndTrace;
311
312 // Generate random bool which we use later in AddLateralNoise
313 const bool UseHorizontalNoise = FMath::RandBool();
314
315 // Cache the reference to Points[idxChannel]
316 std::vector<FPointData>& ChannelPoints = Points[Channel];
317
318 // Loop through this channel linetraces
319 for (int32 i = 0; i < PointsToScanWithOneChannel; i++)
320 {
321 HitResult.Reset();
322
323 // Calculate the end trace point for this linetrace
324 const float LaserHorizontalAngle = std::fmod(HorizontalAngle + AngleDistanceOfLaserMeasure * i, HorizontalFOV) - HorizontalFOVHalf;
325 LaserRotation = FRotator(VerticalAngle, LaserHorizontalAngle, 0);
326 const FQuat LaserQuat = FQuat(LaserRotation);
327 const FQuat ResultQuat = LaserQuat * LidarBodyQuat;
328 EndTrace = Range * ResultQuat.Vector() + LidarBodyLocation;
329
330 if (ShootLaser(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(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 // Scale the pointcloud
605 HitResult.ImpactPoint *= 1e-2;
606
607 // Flip Y axis
608 HitResult.ImpactPoint.Y *= -1;
609
611 {
612 // Save Original FHitResult to separate array
613 FHitResult OriginalHitResultCopy = HitResult;
614 uint32 RGB = RGBDefault;
615 if (Semantic)
616 {
617 // If Lidar is set to Semantic, set point color
618 RGB = GetSemanticData(OriginalHitResultCopy);
619 }
620 const FVector& HitPoint = OriginalHitResultCopy.ImpactPoint;
621 FPointData point = { HitPoint.X, HitPoint.Y, HitPoint.Z, RGB };
622 PreProcessedHitImpactPoints[Channel].emplace_back(point);
623 }
624
625 bool BlockingHit = false;
626 if (UseLidarNoiseModel)
627 {
628 // Check whether we "hit" snowflake by using LUAS formula
629 bool HitSnowFlake = LidarNoiseModel::CheckSnowflakeHit(HitResult, EndTrace, LidarBodyLocation, CurrentWeatherParameters);
630 BlockingHit = HitResult.bBlockingHit || HitSnowFlake;
631 }
632 else
633 {
634 BlockingHit = HitResult.IsValidBlockingHit();
635 }
636
637 return BlockingHit;
638}
639
640void ALidar::ResetRecordedHits(int32 MaxPointsPerChannel)
641{
642 if (!ClearContainers)
643 {
644 return;
645 }
646
647 // Visualize Lidar particles on main thread because,
648 // in some instances NiagaraComponent crashes when updating points from background thread.
649 std::vector<FPointData> CopiedPoints = PointsFlattened;
650 AsyncTask(ENamedThreads::GameThread, [this, CopiedPoints]()
651 {
652 VisualizeLidarParticles(CopiedPoints);
653 });
654
656 {
657 // If we only send data at Lidar sensor rotation frequency
658 // reserve enough points to fill all points
660 }
661
662 // Clear all containers
664 {
665 for (std::vector<FPointData>& ImpactPoints : PreProcessedHitImpactPoints)
666 {
667 ImpactPoints.clear();
668 ImpactPoints.reserve(MaxPointsPerChannel);
669 }
670 }
671
672 for (std::vector<FPointData>& ImpactPoints : Points)
673 {
674 ImpactPoints.clear();
675 ImpactPoints.reserve(MaxPointsPerChannel);
676 }
677
678 PointsFlattened.clear();
679}
680
681void ALidar::SendDataToTopic(const std::vector<FPointData>& points)
682{
683 UTopic* Topic = GetROSTopic();
684
685 if (!IsROSConnected()
686 || !Topic
687 || !SendDataToROS
688 || !PointCloudMessage.IsValid()
689 || points.empty())
690 {
691 return;
692 }
693
694 const size_t PointsSize = points.size();
695 const size_t DataSize = PointsSize * sizeof(FPointData);
696
697 PointCloudMessage->width = static_cast<uint32>(PointsSize);
698 PointCloudMessage->row_step = static_cast<uint32>(DataSize);
699 PointCloudMessage->data_ptr = reinterpret_cast<uint8*>(const_cast<FPointData*>(points.data()));
700 Topic->Publish(PointCloudMessage);
701}
702
704{
706 {
707 return;
708 }
709
710 // Save point cloud to disk
711 FString Filename = FString::Printf(TEXT("%sLidar_%d.ply"), *FileSavePath, LidarSaves);
713
715 {
716 // Flatten 2D std::vector to 1D std::vector
717 std::vector<FPointData> PointsWithOutNoiseModel;
718
719 size_t totalSize = 0;
720 for (const std::vector<FPointData>& Vec : PreProcessedHitImpactPoints)
721 {
722 totalSize += Vec.size();
723 }
724 PointsWithOutNoiseModel.reserve(totalSize);
725
726 for (const std::vector<FPointData>& Vec : PreProcessedHitImpactPoints)
727 {
728 PointsWithOutNoiseModel.insert(PointsWithOutNoiseModel.end(), Vec.begin(), Vec.end());
729 }
730
731 // Save pointcloud to disk without any noise
732 FString PreprocessedFilename = FString::Printf(TEXT("%sLidar_%d_without_noise_model.ply"), *FileSavePath, LidarSaves);
733 UPointcloudUtilities::SaveVectorArrayAsPlyAsync(PreprocessedFilename, PointsWithOutNoiseModel);
734 }
735
736 ++LidarSaves;
737}
void AddRaycastLidar(ALidar *lidarPtr)
void RemoveRaycastLidar(ALidar *lidarPtr)
UNiagaraComponent * NiagaraComponent
Definition: Lidar.h:126
TMap< FName, FColor > SemanticColors
Definition: Lidar.h:242
FWeatherParameters CurrentWeatherParameters
Definition: Lidar.h:236
std::random_device RandomDevice
Definition: Lidar.h:253
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:37
const FName TerrainTag
Definition: Lidar.h:261
void UpdateLidarParticles(int32 NumberOfHits, const TArray< FVector > &HitPoints, const TArray< FLinearColor > &Colors)
Definition: Lidar.cpp:228
float SensorHzFrequency
Definition: Lidar.h:264
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:246
void SaveDataToDisk()
Definition: Lidar.cpp:703
void ResetRecordedHits(int32 MaxPointsPerChannel)
Definition: Lidar.cpp:640
ALidar(const FObjectInitializer &ObjectInitializer)
Definition: Lidar.cpp:31
uint32 CachedSnowflakeColor
Definition: Lidar.h:273
std::vector< float > LaserAngles
Definition: Lidar.h:251
void SetParticleLifeTime(float ParticleLifeTime)
Definition: Lidar.cpp:239
std::mt19937 Generator
Definition: Lidar.h:254
bool LidarParametersChanged
Definition: Lidar.h:257
void ChangeParameters()
Definition: Lidar.cpp:165
int32 LidarSaves
Definition: Lidar.h:269
UWorld * World
Definition: Lidar.h:239
void OnWeatherChanged(FWeatherParameters WeatherParams)
Definition: Lidar.cpp:153
float SnowHeightOffset
Definition: Lidar.h:267
virtual void BeginPlay() override
Definition: Lidar.cpp:52
FLidarParameters TempLidarParameters
Definition: Lidar.h:234
void AddDistanceNoise(FHitResult &HitResult, const FVector &LidarBodyLocation)
Definition: Lidar.cpp:386
void SetNiagaraRendering(bool Enabled)
Definition: Lidar.cpp:213
std::vector< std::vector< FPointData > > Points
Definition: Lidar.h:248
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
Definition: Lidar.cpp:247
uint32 CachedNoneColor
Definition: Lidar.h:271
bool ClearContainers
Definition: Lidar.h:259
bool NeedToSavePointCloudWithoutNoise
Definition: Lidar.h:256
std::vector< FPointData > PointsFlattened
Definition: Lidar.h:249
void SetVisualizeLidarParticles(bool Visualize)
Definition: Lidar.cpp:208
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: Lidar.h:244
FORCEINLINE bool ShootLaser(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
void SendDataToTopic(const std::vector< FPointData > &points)
Definition: Lidar.cpp:681
void AddSnowTerrainAdjustment(FHitResult &HitResult, const FVector &LidarBodyLocation)
Definition: Lidar.cpp:417
bool SendDataEveryFrame
Definition: Lidar.h:258
float SensorHzTimer
Definition: Lidar.h:265
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:112
float CurrentHorizontalAngle
Definition: Lidar.h:263
static const FName NiagaraHitPoints
Definition: Sensor.h:358
bool CanSimulateSensor() const
Definition: Sensor.h:161
static void HideComponentForAllCameras(UPrimitiveComponent *PrimitiveComponent)
Definition: Sensor.cpp:278
static const FName NiagaraPointsFloat
Definition: Sensor.h:360
virtual void CreateDataSavePath()
Definition: Sensor.cpp:225
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:169
static const FName NiagaraPointsInt
Definition: Sensor.h:357
static TMap< FString, FColor > GetSemanticColors()
Definition: Sensor.cpp:288
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