Agrarsense
Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
ARadar Class Reference

#include <Radar.h>

Inheritance diagram for ARadar:
Inheritance graph
[legend]
Collaboration diagram for ARadar:
Collaboration graph
[legend]

Classes

struct  FRadarDetection
 
struct  RadarData
 
struct  RayData
 

Public Member Functions

 ARadar (const FObjectInitializer &ObjectInitializer)
 
void Init (FRadarParameters parameters, bool SimulateSensor=true)
 
virtual ESensorTypes GetSensorType () const override
 
void ChangeRadarParameters (FRadarParameters Parameters)
 
void SetVisualizeParticles (bool Visualize)
 
FRadarParameters GetRadarParameters ()
 
virtual FString GetParametersAsString () const override
 
- Public Member Functions inherited from ASensor
 ASensor (const FObjectInitializer &ObjectInitializer)
 
FString ExportToJsonFile (const FString &FileName)
 
virtual ESensorTypes GetSensorType () const
 
FString GetSensorIdentifier () const
 
void SetSensorIdentifier (const FString newIdentifier)
 
FString GetSensorName () const
 
virtual FString GetParametersAsString () const
 
void SetSensorName (const FString newName)
 
virtual FString GetTopicName ()
 
UTopic * GetROSTopic () const
 
void SetSimulateSensor (bool SimulateSensor)
 
bool CanSimulateSensor () const
 
ASensorModelGetSensorModel () const
 
void SetSensorModel (ASensorModel *NewSensorModel)
 
bool IsROSConnected () const
 
UROSIntegrationGameInstance * GetROSGameInstance () const
 
virtual FString GetActorID_Implementation () const override
 
virtual FString GetActorName_Implementation () const override
 
virtual FString GetActorInformation_Implementation () const override
 
virtual void SetActorName_Implementation (const FString &NewActorName) override
 
virtual void SetActorIDAndName_Implementation (const FString &NewActorName, const FString &NewID) override
 
- Public Member Functions inherited from IActorInformation
FString GetActorID () const
 
FString GetActorName () const
 
FString GetActorInformation () const
 
void SetActorName (const FString &NewActorName)
 
void SetActorIDAndName (const FString &NewActorName, const FString &NewID)
 

Private Member Functions

void BeginPlay () override
 
virtual void Tick (float DeltaTime) override
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
void SendRadarData ()
 
void SetRadarParameters (FRadarParameters Parameters)
 
void CalculateCurrentVelocity (const float DeltaTime)
 
void SimulateRadar (float DeltaTime)
 
float CalculateRelativeVelocity (const FHitResult &OutHit, const FVector &RadarLocation, const FVector ActorVelocity)
 

Private Attributes

UNiagaraComponent * NiagaraComponent
 
bool VisualizeParticles = false
 
TArray< FVector > HitLocations
 
FRadarParameters RadarParameters
 
FRadarParameters TempRadarParameters
 
FVector CurrentVelocity
 
FVector PrevLocation
 
std::vector< RayDataRays
 
std::vector< FRadarDetectiondetections
 
UWorld * World = nullptr
 
bool RadarParametersChanged = false
 
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > RadarMessage
 

Additional Inherited Members

- Static Public Member Functions inherited from ASensor
static void HideComponentForAllCameras (UPrimitiveComponent *PrimitiveComponent)
 
static TMap< FString, FColor > GetSemanticColors ()
 
static TArray< TWeakObjectPtr< UPrimitiveComponent > > GetComponentsToHide ()
 
- Static Public Member Functions inherited from IActorInformation
static void SetAndValidateActorIDAndName (FString &ActorName, FString &ActorID, TWeakObjectPtr< AActor > Actor)
 
static bool DestroyActorByID (const FString &ID)
 
static AActor * GetActorByID (const FString &ID)
 
template<typename T >
static TArray< T * > GetActorsWithInterface ()
 
static void PrintAllIds ()
 
- Public Attributes inherited from ASensor
FSensorDestroy OnSensorDestroy
 
FString AttachedToComponent
 
FName AttachedToBone
 
- Protected Member Functions inherited from ASensor
virtual void BeginPlay () override
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
virtual void CreateROSTopic ()
 
virtual void DestroyROSTopic ()
 
virtual void CreateDataSavePath ()
 
bool IsLogFileCreated ()
 
virtual void CreateLogFile ()
 
void WriteToLogFile (const FString &Message)
 
- Static Protected Member Functions inherited from ASensor
template<typename InStructType >
static FString StructToString (const InStructType &InStruct)
 
- Protected Attributes inherited from ASensor
UTopic * ROSTopic = nullptr
 
bool SendDataToROS = true
 
ULogFileLogFile = nullptr
 
FString FileSavePath
 
UROSIntegrationGameInstance * ROSInstance = nullptr
 
- Static Protected Attributes inherited from ASensor
static FPrimitiveAdded OnPrimitiveAdded
 
static const FName NiagaraPointsInt = "User.PointCount"
 
static const FName NiagaraHitPoints = "User.HitPoints"
 
static const FName NiagaraHitColors = "User.HitColors"
 
static const FName NiagaraPointsFloat = "User.Test"
 

Detailed Description

Linetrace based Radar sensor.

Definition at line 25 of file Radar.h.

Constructor & Destructor Documentation

◆ ARadar()

ARadar::ARadar ( const FObjectInitializer &  ObjectInitializer)

Definition at line 17 of file Radar.cpp.

17 : Super(ObjectInitializer)
18{
19 PrimaryActorTick.bCanEverTick = true;
20}

Member Function Documentation

◆ BeginPlay()

void ARadar::BeginPlay ( )
overrideprivatevirtual

Reimplemented from ASensor.

Definition at line 55 of file Radar.cpp.

56{
57 Super::BeginPlay();
58
59 if (!World)
60 {
61 World = GetWorld();
62 }
63
64 PrevLocation = GetActorLocation();
65
66 // Create RadarMessage
67 RadarMessage = MakeShared<ROSMessages::sensor_msgs::PointCloud2>();
68 RadarMessage->header.frame_id = "world";
69 RadarMessage->height = 1;
70 RadarMessage->is_dense = true;
71 RadarMessage->fields.SetNum(7);
72
73 RadarMessage->fields[0].name = "x";
74 RadarMessage->fields[0].offset = 0;
75 RadarMessage->fields[0].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
76 RadarMessage->fields[0].count = 1;
77
78 RadarMessage->fields[1].name = "y";
79 RadarMessage->fields[1].offset = 4;
80 RadarMessage->fields[1].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
81 RadarMessage->fields[1].count = 1;
82
83 RadarMessage->fields[2].name = "z";
84 RadarMessage->fields[2].offset = 8;
85 RadarMessage->fields[2].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
86 RadarMessage->fields[2].count = 1;
87
88 RadarMessage->fields[3].name = "Range";
89 RadarMessage->fields[3].offset = 12;
90 RadarMessage->fields[3].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
91 RadarMessage->fields[3].count = 1;
92
93 RadarMessage->fields[4].name = "Velocity";
94 RadarMessage->fields[4].offset = 16;
95 RadarMessage->fields[4].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
96 RadarMessage->fields[4].count = 1;
97
98 RadarMessage->fields[5].name = "AzimuthAngle";
99 RadarMessage->fields[5].offset = 20;
100 RadarMessage->fields[5].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
101 RadarMessage->fields[5].count = 1;
102
103 RadarMessage->fields[6].name = "ElevationAngle";
104 RadarMessage->fields[6].offset = 28;
105 RadarMessage->fields[6].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
106 RadarMessage->fields[6].count = 1;
107
108 RadarMessage->point_step = 56;
109}
UWorld * World
Definition: Radar.h:134
FVector PrevLocation
Definition: Radar.h:110
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > RadarMessage
Definition: Radar.h:149

References PrevLocation, RadarMessage, and World.

◆ CalculateCurrentVelocity()

void ARadar::CalculateCurrentVelocity ( const float  DeltaTime)
private

Definition at line 188 of file Radar.cpp.

189{
190 const FVector RadarLocation = GetActorLocation();
191 CurrentVelocity = (RadarLocation - PrevLocation) / DeltaTime;
192 PrevLocation = RadarLocation;
193}
FVector CurrentVelocity
Definition: Radar.h:107

References CurrentVelocity, and PrevLocation.

Referenced by SimulateRadar().

◆ CalculateRelativeVelocity()

float ARadar::CalculateRelativeVelocity ( const FHitResult &  OutHit,
const FVector &  RadarLocation,
const FVector  ActorVelocity 
)
private

Definition at line 340 of file Radar.cpp.

341{
342 constexpr float TO_METERS = 1e-2;
343
344 const FVector TargetVelocity = ActorVelocity;
345 const FVector TargetLocation = (OutHit.ImpactPoint * TO_METERS);
346 const FVector Direction = (TargetLocation - RadarLocation).GetSafeNormal();
347 const FVector DeltaVelocity = (TargetVelocity - CurrentVelocity);
348 const float V = TO_METERS * FVector::DotProduct(DeltaVelocity, Direction);
349
350 return V;
351}

References CurrentVelocity.

Referenced by SimulateRadar().

◆ ChangeRadarParameters()

void ARadar::ChangeRadarParameters ( FRadarParameters  Parameters)

Change Radar parameters at the end of this frame

Parameters
FRadarParametersstruct

Definition at line 152 of file Radar.cpp.

153{
154 if (!CanSimulateSensor())
155 {
156 // We are not currently simulating sensor, we can safely change parameters here
157 SetRadarParameters(Parameters);
158 }
159 else
160 {
161 // Change parameters at the end of the frame
162 TempRadarParameters = Parameters;
164 }
165}
FRadarParameters TempRadarParameters
Definition: Radar.h:97
void SetRadarParameters(FRadarParameters Parameters)
Definition: Radar.cpp:176
bool RadarParametersChanged
Definition: Radar.h:136
bool CanSimulateSensor() const
Definition: Sensor.h:161

References ASensor::CanSimulateSensor(), RadarParametersChanged, SetRadarParameters(), and TempRadarParameters.

◆ EndPlay()

void ARadar::EndPlay ( const EEndPlayReason::Type  EndPlayReason)
overrideprivatevirtual

Reimplemented from ASensor.

Definition at line 111 of file Radar.cpp.

112{
113 Super::EndPlay(EndPlayReason);
114
115 HitLocations.Empty();
116
117 detections.clear();
118 Rays.clear();
119
120 if (RadarMessage.IsValid())
121 {
122 RadarMessage.Reset();
123 }
124
126 {
127 NiagaraComponent->UnregisterComponent();
128 NiagaraComponent->DestroyComponent();
129 }
130
131 World = nullptr;
132}
std::vector< RayData > Rays
Definition: Radar.h:131
UNiagaraComponent * NiagaraComponent
Definition: Radar.h:88
std::vector< FRadarDetection > detections
Definition: Radar.h:132
TArray< FVector > HitLocations
Definition: Radar.h:93

References detections, HitLocations, NiagaraComponent, RadarMessage, Rays, and World.

◆ GetParametersAsString()

virtual FString ARadar::GetParametersAsString ( ) const
inlineoverridevirtual

Get current LidarParameters struct fields as one string.

Reimplemented from ASensor.

Definition at line 72 of file Radar.h.

73 {
75 }
FRadarParameters RadarParameters
Definition: Radar.h:95
static FString StructToString(const InStructType &InStruct)
Definition: Sensor.h:305

◆ GetRadarParameters()

FRadarParameters ARadar::GetRadarParameters ( )
inline

Get current Radar parameters

Returns
FRadarParameters struct

Definition at line 64 of file Radar.h.

65 {
66 return RadarParameters;
67 }

Referenced by USimulatorJsonExporter::ExportSensorToJSON().

◆ GetSensorType()

virtual ESensorTypes ARadar::GetSensorType ( ) const
inlineoverridevirtual

Get type of the sensor

Returns
Sensor's type

Reimplemented from ASensor.

Definition at line 43 of file Radar.h.

References Radar.

◆ Init()

void ARadar::Init ( FRadarParameters  parameters,
bool  SimulateSensor = true 
)

Initialize new Radar sensor

Parameters
parametersFRadarParameters struct

Definition at line 22 of file Radar.cpp.

23{
24 SetSimulateSensor(SimulateSensor);
25 SetRadarParameters(parameters);
26
27 World = GetWorld();
28
30
31 // Load pointcloud Niagara particle system
32 UNiagaraSystem* NS = LoadObject<UNiagaraSystem>(nullptr, TEXT("/Game/Agrarsense/Particles/PointCloud/NS_PointCloudFast"), nullptr, LOAD_None, nullptr);
33 if (NS)
34 {
35 NiagaraComponent = UNiagaraFunctionLibrary::SpawnSystemAtLocation(World, NS, GetActorLocation());
37 {
38 // Hide this NiagaraComponent for all Camera sensors.
39 HideComponentForAllCameras(Cast<UPrimitiveComponent>(NiagaraComponent));
40
41 NiagaraComponent->SetAffectDynamicIndirectLighting(false);
42 NiagaraComponent->SetAffectDistanceFieldLighting(false);
43 NiagaraComponent->SetCastContactShadow(false);
44 NiagaraComponent->SetCastShadow(false);
45 }
46 }
47#if WITH_EDITOR
48 else
49 {
50 UE_LOG(LogTemp, Warning, TEXT("Radar.cpp: Couldn't find Niagara particle system."));
51 }
52#endif
53}
static void HideComponentForAllCameras(UPrimitiveComponent *PrimitiveComponent)
Definition: Sensor.cpp:255
void SetSimulateSensor(bool SimulateSensor)
Definition: Sensor.h:151
virtual void CreateROSTopic()
Definition: Sensor.cpp:146

References ASensor::CreateROSTopic(), ASensor::HideComponentForAllCameras(), NiagaraComponent, SetRadarParameters(), ASensor::SetSimulateSensor(), and World.

Referenced by USensorFactory::SpawnRadar().

◆ SendRadarData()

void ARadar::SendRadarData ( )
private

Definition at line 353 of file Radar.cpp.

354{
355 UTopic* Topic = GetROSTopic();
356
357 if (!SendDataToROS
358 || !Topic
359 || !RadarMessage.IsValid()
360 || detections.empty())
361 {
362 return;
363 }
364
365 int detectionsSize = detections.size();
366 RadarMessage->width = detectionsSize;
367 RadarMessage->row_step = detectionsSize * RadarMessage->point_step;
368
369 TUniquePtr<uint8> data(new uint8[RadarMessage->row_step]);
370 int pointStep = RadarMessage->point_step;
371
372 int i = 0;
373 for (const FRadarDetection& detection : detections)
374 {
375 RadarData params =
376 {
377 detection.depth * cos(detection.azimuth) * cos(-detection.altitude),
378 detection.depth * sin(-detection.azimuth) * cos(detection.altitude),
379 detection.depth * sin(detection.altitude),
380 detection.depth,
381 detection.velocity,
382 detection.azimuth,
383 detection.altitude
384 };
385
386 memcpy(data.Get() + i * pointStep, &params, sizeof(params));
387 i++;
388 }
389
390 RadarMessage->data_ptr = data.Get();
391
392 Topic->Publish(RadarMessage);
393}
UTopic * GetROSTopic() const
Definition: Sensor.h:141
bool SendDataToROS
Definition: Sensor.h:344

References detections, ASensor::GetROSTopic(), RadarMessage, ASensor::SendDataToROS, and ARadar::RadarData::velocity.

Referenced by SimulateRadar().

◆ SetRadarParameters()

void ARadar::SetRadarParameters ( FRadarParameters  Parameters)
private

◆ SetVisualizeParticles()

void ARadar::SetVisualizeParticles ( bool  Visualize)

Set visualize this radar particles with Niagara particle system

Parameters
visualizeboolean

Definition at line 167 of file Radar.cpp.

168{
169 VisualizeParticles = Visualize;
171 {
172 NiagaraComponent->SetRenderingEnabled(VisualizeParticles);
173 }
174}

References NiagaraComponent, and VisualizeParticles.

◆ SimulateRadar()

void ARadar::SimulateRadar ( float  DeltaTime)
private

Definition at line 195 of file Radar.cpp.

196{
197 TRACE_CPUPROFILER_EVENT_SCOPE(ARadar::SimulateRadar);
198
199 CalculateCurrentVelocity(DeltaTime);
200
201 auto TraceParams = FCollisionQueryParams(FName(TEXT("Laser_Trace")), true, this);
202 TraceParams.bTraceComplex = true;
203 TraceParams.bReturnPhysicalMaterial = false;
204
205 constexpr float TO_METERS = 1e-2;
206 const FTransform& ActorTransform = GetActorTransform();
207 const FRotator& TransformRotator = ActorTransform.Rotator();
208 const FVector& RadarLocation = GetActorLocation();
209 const FVector& ForwardVector = GetActorForwardVector();
210 const FVector TransformXAxis = ActorTransform.GetUnitAxis(EAxis::X);
211 const FVector TransformYAxis = ActorTransform.GetUnitAxis(EAxis::Y);
212 const FVector TransformZAxis = ActorTransform.GetUnitAxis(EAxis::Z);
213
214 const float Range = RadarParameters.Range * 100;
215 const float HorizontalFOV = RadarParameters.HorizontalFOV;
216 const float VerticalFOV = RadarParameters.VerticalFOV;
217 const float PointsPerSecond = RadarParameters.PointsPerSecond;
218
219 bool DebugLines = false;
220 EParallelForFlags Flag = EParallelForFlags::Unbalanced;
221 if (DebugLines)
222 {
223 Flag = EParallelForFlags::ForceSingleThread;
224 }
225
226 // Maximum radar radius in horizontal and vertical direction
227 const float MaxRx = FMath::Tan(FMath::DegreesToRadians(HorizontalFOV * 0.5f)) * Range;
228 const float MaxRy = FMath::Tan(FMath::DegreesToRadians(VerticalFOV * 0.5f)) * Range;
229 const int NumPoints = (int)(PointsPerSecond * DeltaTime);
230
231 Rays.clear();
232 Rays.resize(NumPoints);
233 for (int32 i = 0; i < Rays.size(); i++)
234 {
235 Rays[i].Radius = static_cast<float>(rand()) / static_cast<float>(RAND_MAX);
236 Rays[i].Angle = 0.0f + static_cast<float>(rand()) / (static_cast<float>(RAND_MAX / (2 * PI - 0.0f)));
237 Rays[i].Hit = false;
238 }
239
240 // Linetrace in parallel
241 ParallelFor(NumPoints, [&](int32 idx)
242 {
243 FHitResult OutHit(ForceInit);
244 const float Radius = Rays[idx].Radius;
245 const float Angle = Rays[idx].Angle;
246
247 float Sin, Cos;
248 FMath::SinCos(&Sin, &Cos, Angle);
249
250 const FVector EndLocation = RadarLocation + TransformRotator.RotateVector({
251 Range,
252 MaxRx * Radius * Cos,
253 MaxRy * Radius * Sin
254 });
255
256 bool hit = false;
257
258#ifdef ParallelLineTraceSingleByChannel_EXISTS
259 hit = World->ParallelLineTraceSingleByChannel(
260 OutHit,
261 RadarLocation,
262 EndLocation,
263 ECC_GameTraceChannel3,
264 TraceParams,
265 FCollisionResponseParams::DefaultResponseParam);
266#else
267 hit = World->LineTraceSingleByChannel(
268 OutHit,
269 RadarLocation,
270 EndLocation,
271 ECC_GameTraceChannel3,
272 TraceParams,
273 FCollisionResponseParams::DefaultResponseParam);
274#endif
275
276#ifdef UE_BUILD_DEBUG
277 if (DebugLines)
278 {
279 DrawDebugLine(World, RadarLocation, EndLocation, FColor::Green, false, 1.0f);
280 }
281#endif
282
283 const TWeakObjectPtr<AActor> Actor = OutHit.GetActor();
284 if (hit && Actor.IsValid())
285 {
286 auto point = OutHit.ImpactPoint;
287 point *= 1e-2;
288 Rays[idx].HitPoint = point;
289 Rays[idx].Hit = true;
290 Rays[idx].RelativeVelocity = CalculateRelativeVelocity(OutHit, RadarLocation, Actor->GetVelocity());
291 Rays[idx].AzimuthAndElevation = FMath::GetAzimuthAndElevation(
292 (EndLocation - RadarLocation).GetSafeNormal() * Range,
293 TransformXAxis,
294 TransformYAxis,
295 TransformZAxis
296 );
297 Rays[idx].Distance = OutHit.Distance * TO_METERS;
298 }
299 }, Flag);
300
301
303 {
304 HitLocations.Empty();
305 }
306
307 // Clear previous detections
308 detections.clear();
309
310 // Write the detections to the output structure
311 for (auto& ray : Rays)
312 {
313 if (ray.Hit)
314 {
315 detections.push_back({
316 ray.RelativeVelocity,
317 (float)ray.AzimuthAndElevation.X,
318 (float)ray.AzimuthAndElevation.Y,
319 ray.Distance
320 });
321
323 {
324 HitLocations.Add(ray.HitPoint);
325 }
326 }
327 }
328
330 {
331 int numberOfHits = HitLocations.Num();
332 NiagaraComponent->SetVariableFloat(NiagaraPointsFloat, float(numberOfHits));
333 NiagaraComponent->SetVariableInt(NiagaraPointsInt, numberOfHits);
334 UNiagaraDataInterfaceArrayFunctionLibrary::SetNiagaraArrayVector(NiagaraComponent, NiagaraHitPoints, HitLocations);
335 }
336
338}
float CalculateRelativeVelocity(const FHitResult &OutHit, const FVector &RadarLocation, const FVector ActorVelocity)
Definition: Radar.cpp:340
void SendRadarData()
Definition: Radar.cpp:353
void SimulateRadar(float DeltaTime)
Definition: Radar.cpp:195
void CalculateCurrentVelocity(const float DeltaTime)
Definition: Radar.cpp:188
static const FName NiagaraHitPoints
Definition: Sensor.h:358
static const FName NiagaraPointsFloat
Definition: Sensor.h:360
static const FName NiagaraPointsInt
Definition: Sensor.h:357

References CalculateCurrentVelocity(), CalculateRelativeVelocity(), detections, HitLocations, FRadarParameters::HorizontalFOV, NiagaraComponent, ASensor::NiagaraHitPoints, ASensor::NiagaraPointsFloat, ASensor::NiagaraPointsInt, FRadarParameters::PointsPerSecond, RadarParameters, FRadarParameters::Range, Rays, SendRadarData(), SimulateRadar(), FRadarParameters::VerticalFOV, VisualizeParticles, and World.

Referenced by SimulateRadar(), and Tick().

◆ Tick()

void ARadar::Tick ( float  DeltaTime)
overrideprivatevirtual

Definition at line 134 of file Radar.cpp.

135{
136 TRACE_CPUPROFILER_EVENT_SCOPE(ARadar::Tick);
137
138 if (!CanSimulateSensor())
139 {
140 return;
141 }
142
143 SimulateRadar(DeltaTime);
144
146 {
149 }
150}
virtual void Tick(float DeltaTime) override
Definition: Radar.cpp:134

References ASensor::CanSimulateSensor(), RadarParametersChanged, SetRadarParameters(), SimulateRadar(), TempRadarParameters, and Tick().

Referenced by Tick().

Member Data Documentation

◆ CurrentVelocity

FVector ARadar::CurrentVelocity
private

Definition at line 107 of file Radar.h.

Referenced by CalculateCurrentVelocity(), and CalculateRelativeVelocity().

◆ detections

std::vector<FRadarDetection> ARadar::detections
private

Definition at line 132 of file Radar.h.

Referenced by EndPlay(), SendRadarData(), SetRadarParameters(), and SimulateRadar().

◆ HitLocations

TArray<FVector> ARadar::HitLocations
private

Definition at line 93 of file Radar.h.

Referenced by EndPlay(), and SimulateRadar().

◆ NiagaraComponent

UNiagaraComponent* ARadar::NiagaraComponent
private

Definition at line 88 of file Radar.h.

Referenced by EndPlay(), Init(), SetVisualizeParticles(), and SimulateRadar().

◆ PrevLocation

FVector ARadar::PrevLocation
private

Definition at line 110 of file Radar.h.

Referenced by BeginPlay(), and CalculateCurrentVelocity().

◆ RadarMessage

TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> ARadar::RadarMessage
private

Definition at line 149 of file Radar.h.

Referenced by BeginPlay(), EndPlay(), and SendRadarData().

◆ RadarParameters

FRadarParameters ARadar::RadarParameters
private

Definition at line 95 of file Radar.h.

Referenced by SetRadarParameters(), and SimulateRadar().

◆ RadarParametersChanged

bool ARadar::RadarParametersChanged = false
private

Definition at line 136 of file Radar.h.

Referenced by ChangeRadarParameters(), and Tick().

◆ Rays

std::vector<RayData> ARadar::Rays
private

Definition at line 131 of file Radar.h.

Referenced by EndPlay(), and SimulateRadar().

◆ TempRadarParameters

FRadarParameters ARadar::TempRadarParameters
private

Definition at line 97 of file Radar.h.

Referenced by ChangeRadarParameters(), and Tick().

◆ VisualizeParticles

bool ARadar::VisualizeParticles = false
private

Definition at line 90 of file Radar.h.

Referenced by SetRadarParameters(), SetVisualizeParticles(), and SimulateRadar().

◆ World

UWorld* ARadar::World = nullptr
private

Definition at line 134 of file Radar.h.

Referenced by BeginPlay(), EndPlay(), Init(), and SimulateRadar().


The documentation for this class was generated from the following files: