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

#include <LidarManager.h>

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

Public Member Functions

 ALidarManager (const FObjectInitializer &ObjectInitializer)
 
void SetSimulateLidars (bool bSimulateLidars)
 
void SetMeasurePerformance (bool bMeasurePerformance)
 
void SetSaveCombinedCloudToDisk (bool bSaveCombinedCloud)
 
void SetSendCombinedCloud (bool bSaveCombinedCloud)
 
void AddRaycastLidar (ALidar *lidarPtr)
 
void RemoveRaycastLidar (ALidar *lidarPtr)
 
int GetLidarCount () const
 
TArray< ALidar * > GetAllLidars () const
 
std::vector< ALidar * > GetAllLidarsVector () const
 
 UPROPERTY (BlueprintReadOnly)
 

Public Attributes

FLidarDelegate_LidarSpawned OnLidarSpawned
 
FLidarDelegate_LidarDestroyed OnLidarDestroyed
 
bool SendCombinedCloudToROS = true
 
bool SaveCombinedCloudToDisk = false
 
bool MeasurePerformance = false
 
float TimeInMilliseconds
 

Private Member Functions

virtual void BeginPlay () override
 
virtual void EndPlay (const EEndPlayReason::Type EndPlayReason) override
 
void TickParallel (float DeltaTime)
 
void SimulateRaycastLidars (const float DeltaTime)
 
void SendCombinedPointcloud (const std::vector< FPointData > &points)
 
void SaveCombinedPointcloud (const std::vector< FPointData > &points)
 
void ROSBridgeStateChanged (EROSState RosState)
 
void InitTopic ()
 
void DestroyTopic ()
 

Private Attributes

FTickEntry TickEntry
 
bool TickAdded = false
 
std::vector< ALidar * > RaycastLidars
 
UROSIntegrationGameInstance * RosInstance = nullptr
 
TWeakObjectPtr< UTopic > CombinedLidarTopic
 
SimpleTimerTotalAverageTimer = nullptr
 
bool SimulateLidars = true
 
FString FileSavePath
 
int LidarSaves = 0
 
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
 

Detailed Description

This class handles simulating all Lidar sensors in parallel.

Definition at line 40 of file LidarManager.h.

Constructor & Destructor Documentation

◆ ALidarManager()

ALidarManager::ALidarManager ( const FObjectInitializer &  ObjectInitializer)

Definition at line 31 of file LidarManager.cpp.

31 : Super(ObjectInitializer)
32{
33 // TickManager handles this Actor ticking
34 PrimaryActorTick.bCanEverTick = false;
35
36 if (FParse::Param(FCommandLine::Get(), TEXT("-save-combined-pointcloud")))
37 {
39 }
40}
bool SaveCombinedCloudToDisk
Definition: LidarManager.h:144

References SaveCombinedCloudToDisk.

Member Function Documentation

◆ AddRaycastLidar()

void ALidarManager::AddRaycastLidar ( ALidar lidarPtr)

Add Lidar sensor to this manager. This should only be called from Lidar.cpp

Parameters
lidarPtrLidar class pointer

Definition at line 255 of file LidarManager.cpp.

256{
257 if (!lidarPtr)
258 {
259 return;
260 }
261
262 RaycastLidars.push_back(lidarPtr);
263
264#if WITH_EDITOR
265 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Added Lidar sensor."));
266#endif
267
268 if (!TickAdded)
269 {
270 InitTopic();
271
272 TickEntry = ATickManager::AddTick(this, BindTick(this, &ALidarManager::TickParallel), ETickType::FullFrameTaskParallel);
273 TickAdded = true;
274 }
275
276 // Broadcast new lidar has been spawned, broadcast Lidar actor
277 OnLidarSpawned.Broadcast(lidarPtr);
278}
static auto BindTick(ObjectType *Object, FunctionType Function)
Definition: TickManager.h:182
FLidarDelegate_LidarSpawned OnLidarSpawned
Definition: LidarManager.h:131
FTickEntry TickEntry
Definition: LidarManager.h:160
std::vector< ALidar * > RaycastLidars
Definition: LidarManager.h:201
void TickParallel(float DeltaTime)
static FTickEntry AddTick(UObject *Object, std::function< void(float)> Function, ETickType Type)
Definition: TickManager.cpp:55

References ATickManager::AddTick(), BindTick(), InitTopic(), OnLidarSpawned, RaycastLidars, TickAdded, TickEntry, and TickParallel().

Referenced by ALidar::BeginPlay().

◆ BeginPlay()

void ALidarManager::BeginPlay ( )
overrideprivatevirtual

Definition at line 42 of file LidarManager.cpp.

43{
44 Super::BeginPlay();
45
46 // There should only be one instance of this actor which is spawned in AgrarsenseGameModebase.cpp
47 UWorld* World = GetWorld();
48 TArray<AActor*> FoundActors;
49 UGameplayStatics::GetAllActorsOfClass(World, ALidarManager::StaticClass(), FoundActors);
50 if (FoundActors.Num() != 1)
51 {
52#ifdef WITH_EDITOR
53 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: LidarManager already exists in the level. Destroying this one."));
54#endif
55 this->Destroy();
56 return;
57 }
58
59 RosInstance = Cast<UROSIntegrationGameInstance>(GetGameInstance());
60
62
63 FString DataLocation = UAgrarsensePaths::GetDataFolder();
64 FString UnixTimeStamp = FString::FromInt(FDateTime::Now().ToUnixTimestamp());
65 FileSavePath = DataLocation + "LidarCombined_" + UnixTimeStamp + "/";
66
67 // Initialize the PointCloudMessage
68 PointCloudMessage = MakeShared<ROSMessages::sensor_msgs::PointCloud2>();
69 PointCloudMessage->header.frame_id = "world";
70 PointCloudMessage->is_dense = true;
71 PointCloudMessage->fields.SetNum(4);
72 PointCloudMessage->height = 1;
73
74 PointCloudMessage->fields[0].name = "x";
75 PointCloudMessage->fields[0].offset = 0;
76 PointCloudMessage->fields[0].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
77 PointCloudMessage->fields[0].count = 1;
78
79 PointCloudMessage->fields[1].name = "y";
80 PointCloudMessage->fields[1].offset = 4;
81 PointCloudMessage->fields[1].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
82 PointCloudMessage->fields[1].count = 1;
83
84 PointCloudMessage->fields[2].name = "z";
85 PointCloudMessage->fields[2].offset = 8;
86 PointCloudMessage->fields[2].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::FLOAT32;
87 PointCloudMessage->fields[2].count = 1;
88
89 PointCloudMessage->fields[3].name = "rgb";
90 PointCloudMessage->fields[3].offset = 12;
91 PointCloudMessage->fields[3].datatype = ROSMessages::sensor_msgs::PointCloud2::PointField::UINT32;
92 PointCloudMessage->fields[3].count = 1;
93
94 PointCloudMessage->point_step = 16;
95}
FString FileSavePath
Definition: LidarManager.h:213
UROSIntegrationGameInstance * RosInstance
Definition: LidarManager.h:204
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: LidarManager.h:217
SimpleTimer * TotalAverageTimer
Definition: LidarManager.h:209
static FString GetDataFolder()

References Destroy, FileSavePath, UAgrarsensePaths::GetDataFolder(), PointCloudMessage, RosInstance, and TotalAverageTimer.

◆ DestroyTopic()

void ALidarManager::DestroyTopic ( )
private

Destroy ROS topic

Definition at line 344 of file LidarManager.cpp.

345{
346 if (CombinedLidarTopic.IsValid())
347 {
348 CombinedLidarTopic->Unadvertise();
349 CombinedLidarTopic->Unsubscribe();
350 CombinedLidarTopic->MarkAsDisconnected();
351 CombinedLidarTopic->ConditionalBeginDestroy();
352 CombinedLidarTopic.Reset();
353 }
354}
TWeakObjectPtr< UTopic > CombinedLidarTopic
Definition: LidarManager.h:207

References CombinedLidarTopic.

Referenced by EndPlay(), RemoveRaycastLidar(), and ROSBridgeStateChanged().

◆ EndPlay()

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

Definition at line 97 of file LidarManager.cpp.

98{
99 Super::EndPlay(EndPlayReason);
100
101 DestroyTopic();
102
103 PointCloudMessage.Reset();
104
105 RaycastLidars.clear();
106
107 RosInstance = nullptr;
108
109 delete(TotalAverageTimer);
110
111 if (TickAdded)
112 {
114 }
115}
static void RemoveTick(FTickEntry TickEntry)
Definition: TickManager.cpp:90

References DestroyTopic(), PointCloudMessage, RaycastLidars, ATickManager::RemoveTick(), RosInstance, TickAdded, TickEntry, and TotalAverageTimer.

◆ GetAllLidars()

TArray< ALidar * > ALidarManager::GetAllLidars ( ) const
inline

Get all Lidar sensors added to this Lidar Mananger

Returns
Tarray of ALidar pointers.

Definition at line 103 of file LidarManager.h.

104 {
105 // Create TArray<ALidar*> since LidarManager uses std::vector
106 // to keep track of Lidar sensors and Blueprints only support TArrays
107 TArray<ALidar*> Lidars;
108
109 for (int32 i = 0; i < RaycastLidars.size(); i++)
110 {
111 ALidar* LidarPtr = RaycastLidars[i];
112 if (LidarPtr)
113 {
114 Lidars.Add(LidarPtr);
115 }
116 }
117
118 return Lidars;
119 }
Definition: Lidar.h:34

◆ GetAllLidarsVector()

std::vector< ALidar * > ALidarManager::GetAllLidarsVector ( ) const
inline

Definition at line 121 of file LidarManager.h.

122 {
123 return RaycastLidars;
124 }

◆ GetLidarCount()

int ALidarManager::GetLidarCount ( ) const
inline

Get current Lidar count. Callable from blueprints.

Returns
int lidar count

Definition at line 93 of file LidarManager.h.

94 {
95 return RaycastLidars.size();
96 }

◆ InitTopic()

void ALidarManager::InitTopic ( )
private

Initialize ROS topic

Definition at line 328 of file LidarManager.cpp.

329{
330 if (CombinedLidarTopic.IsValid() || !SendCombinedCloudToROS || !RosInstance->IsROSConnected())
331 {
332 return;
333 }
334
335 CombinedLidarTopic = NewObject<UTopic>(UTopic::StaticClass());
336 CombinedLidarTopic->Init(RosInstance->ROSIntegrationCore, FString::Printf(TEXT("/agrarsense/out/sensors/lidars_combined")), TEXT("sensor_msgs/PointCloud2"));
337 CombinedLidarTopic->Advertise();
338
339#if WITH_EDITOR
340 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Created combined Lidar ROS topic. Topic name: /agrarsense/sensors/lidars_combined"));
341#endif
342}
bool SendCombinedCloudToROS
Definition: LidarManager.h:141

References CombinedLidarTopic, RosInstance, and SendCombinedCloudToROS.

Referenced by AddRaycastLidar(), ROSBridgeStateChanged(), and SetSendCombinedCloud().

◆ RemoveRaycastLidar()

void ALidarManager::RemoveRaycastLidar ( ALidar lidarPtr)

Remove Lidar sensor from this manager. This should only be called from Lidar.cpp

Parameters
lidarPtrLidar class pointer

Definition at line 280 of file LidarManager.cpp.

281{
282 if (!lidarPtr)
283 {
284 return;
285 }
286
287 auto it = std::find(RaycastLidars.begin(), RaycastLidars.end(), lidarPtr);
288 if (it != RaycastLidars.end())
289 {
290 RaycastLidars.erase(it);
291
292#if WITH_EDITOR
293 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Removed Lidar sensor"));
294#endif
295 }
296
297 // Disable tick if there's no Lidar sensors.
298 if (RaycastLidars.size() == 0)
299 {
301 if (TickAdded)
302 {
304 TickAdded = false;
305 DestroyTopic();
306 }
307 }
308
309 // Broadcast lidar sensor has been destroyed event and broadcast current lidar count
310 int currentLidarCount = RaycastLidars.size();
311 OnLidarDestroyed.Broadcast(currentLidarCount);
312}
FLidarDelegate_LidarDestroyed OnLidarDestroyed
Definition: LidarManager.h:138
void ResetAverageTime()
Definition: SimpleTimer.h:141

References DestroyTopic(), OnLidarDestroyed, RaycastLidars, ATickManager::RemoveTick(), SimpleTimer::ResetAverageTime(), TickAdded, TickEntry, and TotalAverageTimer.

Referenced by ALidar::EndPlay().

◆ ROSBridgeStateChanged()

void ALidarManager::ROSBridgeStateChanged ( EROSState  RosState)
private

Callback when ROS Bridge state changed. must be marked as UFUNCTION, otherwise binding to event will not work.

Definition at line 314 of file LidarManager.cpp.

315{
316 switch (RosState)
317 {
319 InitTopic();
320 break;
321
323 DestroyTopic();
324 break;
325 }
326}

References Connected, DestroyTopic(), Disconnected, and InitTopic().

◆ SaveCombinedPointcloud()

void ALidarManager::SaveCombinedPointcloud ( const std::vector< FPointData > &  points)
private

Save combined cloud as ply to disk

Definition at line 356 of file LidarManager.cpp.

357{
359 {
360 return;
361 }
362
363 FString Filename = FString::Printf(TEXT("%sCombinedPointcloud_%d.ply"), *FileSavePath, LidarSaves);
364 ++LidarSaves;
365
367}
static void SaveVectorArrayAsPlyAsync(FString FullFileName, const std::vector< FPointData > points)

References FileSavePath, LidarSaves, SaveCombinedCloudToDisk, and UPointcloudUtilities::SaveVectorArrayAsPlyAsync().

Referenced by SimulateRaycastLidars().

◆ SendCombinedPointcloud()

void ALidarManager::SendCombinedPointcloud ( const std::vector< FPointData > &  points)
private

Send combined pointcloud to ROS topic

Definition at line 369 of file LidarManager.cpp.

370{
371 TRACE_CPUPROFILER_EVENT_SCOPE(ALidarManager::SendCombinedPointcloud);
372
373 UTopic* Topic = CombinedLidarTopic.Get();
374
376 || !RosInstance
377 || !RosInstance->IsROSConnected()
378 || !Topic
379 || !PointCloudMessage.IsValid())
380 {
381 return;
382 }
383
384 const int pointSize = points.size();
385 size_t dataSize = pointSize * sizeof(FPointData);
386
387 PointCloudMessage->width = pointSize;
388 PointCloudMessage->row_step = dataSize;
389 PointCloudMessage->data_ptr = reinterpret_cast<uint8*>(const_cast<FPointData*>(points.data()));
390
391 Topic->Publish(PointCloudMessage);
392}
void SendCombinedPointcloud(const std::vector< FPointData > &points)

References CombinedLidarTopic, PointCloudMessage, RosInstance, SendCombinedCloudToROS, and SendCombinedPointcloud().

Referenced by SendCombinedPointcloud(), and SimulateRaycastLidars().

◆ SetMeasurePerformance()

void ALidarManager::SetMeasurePerformance ( bool  bMeasurePerformance)

Set boolean whether to measure Lidar performance (logs milliseconds to console)

Parameters
bMeasurePerformanceboolean to toggle performance measurement

Definition at line 232 of file LidarManager.cpp.

233{
234 MeasurePerformance = bMeasurePerformance;
235}
bool MeasurePerformance
Definition: LidarManager.h:147

References MeasurePerformance.

◆ SetSaveCombinedCloudToDisk()

void ALidarManager::SetSaveCombinedCloudToDisk ( bool  bSaveCombinedCloud)

Set boolean whether to save combined cloud to disk

Parameters
bSaveCombinedCloudboolean to set saving to disk

Definition at line 237 of file LidarManager.cpp.

238{
239 SaveCombinedCloudToDisk = bSaveCombinedCloud;
240}

References SaveCombinedCloudToDisk.

Referenced by UROSCommands::HandleSetSaveCombinedPointcloudToDisk().

◆ SetSendCombinedCloud()

void ALidarManager::SetSendCombinedCloud ( bool  bSaveCombinedCloud)

Set boolean whether to send combined cloud to ROS

Parameters
bSaveCombinedCloudboolean to set sending data to ROS

Definition at line 242 of file LidarManager.cpp.

243{
244 SendCombinedCloudToROS = bSaveCombinedCloud;
246 {
247 InitTopic();
248 }
249
250#if WITH_EDITOR
251 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Saving combined Lidar pointcloud to disk: %s"), (SendCombinedCloudToROS ? TEXT("true") : TEXT("false")));
252#endif
253}

References InitTopic(), and SendCombinedCloudToROS.

◆ SetSimulateLidars()

void ALidarManager::SetSimulateLidars ( bool  bSimulateLidars)

Set boolean whether Lidar sensors be simulated

Parameters
bSimulateLidarsboolean to set simulating Lidars on/off

Definition at line 227 of file LidarManager.cpp.

228{
229 SimulateLidars = bSimulateLidars;
230}

References SimulateLidars.

◆ SimulateRaycastLidars()

void ALidarManager::SimulateRaycastLidars ( const float  DeltaTime)
private

Simulate all Lidar sensors

Parameters
DeltaTimecurrent DeltaTime

Definition at line 137 of file LidarManager.cpp.

138{
139 TRACE_CPUPROFILER_EVENT_SCOPE(ALidarManager::SimulateRaycastLidars);
140
141 const int lidarCount = RaycastLidars.size();
142
143 if (lidarCount == 0 || !SimulateLidars)
144 {
145 return;
146 }
147
148 std::vector<FPointData> flattenedPoints;
149
150 if (lidarCount == 1)
151 {
152 // If we only have one lidar sensor,
153 // we can skip ParallelFor and 2D to 1D std::vector conversion overhead completely
154 ALidar* lidar = RaycastLidars[0];
155 if (lidar)
156 {
157#ifdef ParallelLineTraceSingleByChannel_EXISTS
158 // ParallelLineTraceSingleByChannel_EXISTS Defined and implemented in AGRARSENSE Unreal Engine fork
159 // Lock physics scene while linetracing.
160 auto PhysicsLock = FPhysicsObjectExternalInterface::LockRead(GetWorld()->GetPhysicsScene());
161 {
162 flattenedPoints = lidar->SimulateRaycastLidar(DeltaTime);
163 }
164 PhysicsLock.Release();
165#else
166 // If not using AGRARSENSE fork no need to lock the physics scene.
167 flattenedPoints = lidar->SimulateRaycastLidar(DeltaTime);
168#endif
169 }
170 }
171 else
172 {
173 // Else we have multiple Lidar sensors,
174 // Simulate all of them in parallel
175 std::vector<std::vector<FPointData>> points(lidarCount);
176 ParallelFor(lidarCount, [&](int32 lidarIndex)
177 {
178 ALidar* lidar = RaycastLidars[lidarIndex];
179 if (lidar)
180 {
181#ifdef ParallelLineTraceSingleByChannel_EXISTS
182 // ParallelLineTraceSingleByChannel_EXISTS Defined and implemented in AGRARSENSE Unreal Engine fork
183 // Lock physics scene while linetracing.
184 auto PhysicsLock = FPhysicsObjectExternalInterface::LockRead(GetWorld()->GetPhysicsScene());
185 {
186 points[lidarIndex] = lidar->SimulateRaycastLidar(DeltaTime);
187 }
188 PhysicsLock.Release();
189#else
190 // If not using AGRARSENSE fork no need to lock the physics scene.
191 points[lidarIndex] = lidar->SimulateRaycastLidar(DeltaTime);
192#endif
193 }
194 }, EParallelForFlags::Unbalanced);
195
197 {
198 int32 TotalSize = 0;
199
200 for (const auto& subVector : points)
201 {
202 TotalSize += subVector.size();
203 }
204
205 if (TotalSize != 0)
206 {
207 flattenedPoints.reserve(TotalSize);
208 for (auto& subVector : points)
209 {
210 flattenedPoints.insert(flattenedPoints.end(), std::make_move_iterator(subVector.begin()), std::make_move_iterator(subVector.end()));
211 }
212 }
213 }
214 }
215
216 if (!flattenedPoints.empty())
217 {
219 {
220 SaveCombinedPointcloud(flattenedPoints);
221 }
222
223 SendCombinedPointcloud(flattenedPoints);
224 }
225}
void SaveCombinedPointcloud(const std::vector< FPointData > &points)
void SimulateRaycastLidars(const float DeltaTime)
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
Definition: Lidar.cpp:273

References RaycastLidars, SaveCombinedCloudToDisk, SaveCombinedPointcloud(), SendCombinedCloudToROS, SendCombinedPointcloud(), SimulateLidars, ALidar::SimulateRaycastLidar(), and SimulateRaycastLidars().

Referenced by SimulateRaycastLidars(), and TickParallel().

◆ TickParallel()

void ALidarManager::TickParallel ( float  DeltaTime)
private

Definition at line 117 of file LidarManager.cpp.

118{
119#ifdef WITH_EDITOR
121 {
123 }
124#endif
125
126 SimulateRaycastLidars(DeltaTime);
127
128#ifdef WITH_EDITOR
130 {
131 double ms = TotalAverageTimer->PrintAverageTime();
132 TimeInMilliseconds = FMath::RoundToFloat(ms * 100.0f) / 100.0f;
133 }
134#endif
135}
float TimeInMilliseconds
Definition: LidarManager.h:150
double PrintAverageTime(FString prefix="Average execution time ", FString suffix=" milliseconds", bool printToScreen=false)
Definition: SimpleTimer.h:123
void TakeTimeStamp()
Definition: SimpleTimer.h:76

References MeasurePerformance, SimpleTimer::PrintAverageTime(), SimulateRaycastLidars(), SimpleTimer::TakeTimeStamp(), TimeInMilliseconds, and TotalAverageTimer.

Referenced by AddRaycastLidar().

◆ UPROPERTY()

ALidarManager::UPROPERTY ( BlueprintReadOnly  )

Member Data Documentation

◆ CombinedLidarTopic

TWeakObjectPtr<UTopic> ALidarManager::CombinedLidarTopic
private

Definition at line 207 of file LidarManager.h.

Referenced by DestroyTopic(), InitTopic(), and SendCombinedPointcloud().

◆ FileSavePath

FString ALidarManager::FileSavePath
private

Definition at line 213 of file LidarManager.h.

Referenced by BeginPlay(), and SaveCombinedPointcloud().

◆ LidarSaves

int ALidarManager::LidarSaves = 0
private

Definition at line 215 of file LidarManager.h.

Referenced by SaveCombinedPointcloud().

◆ MeasurePerformance

bool ALidarManager::MeasurePerformance = false

Definition at line 147 of file LidarManager.h.

Referenced by SetMeasurePerformance(), and TickParallel().

◆ OnLidarDestroyed

FLidarDelegate_LidarDestroyed ALidarManager::OnLidarDestroyed

On Lidar sensor destroyed event. BlueprintAssignable.

Returns
int Lidar sensor count

Definition at line 138 of file LidarManager.h.

Referenced by RemoveRaycastLidar().

◆ OnLidarSpawned

FLidarDelegate_LidarSpawned ALidarManager::OnLidarSpawned

On Lidar sensor spawned event. BlueprintAssignable.

Returns
ALidar Lidar class pointer

Definition at line 131 of file LidarManager.h.

Referenced by AddRaycastLidar().

◆ PointCloudMessage

TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> ALidarManager::PointCloudMessage
private

Definition at line 217 of file LidarManager.h.

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

◆ RaycastLidars

std::vector<ALidar*> ALidarManager::RaycastLidars
private

Container that holds references to Lidar sensors

Definition at line 201 of file LidarManager.h.

Referenced by AddRaycastLidar(), EndPlay(), RemoveRaycastLidar(), and SimulateRaycastLidars().

◆ RosInstance

UROSIntegrationGameInstance* ALidarManager::RosInstance = nullptr
private

Definition at line 204 of file LidarManager.h.

Referenced by BeginPlay(), EndPlay(), InitTopic(), and SendCombinedPointcloud().

◆ SaveCombinedCloudToDisk

bool ALidarManager::SaveCombinedCloudToDisk = false

◆ SendCombinedCloudToROS

bool ALidarManager::SendCombinedCloudToROS = true

◆ SimulateLidars

bool ALidarManager::SimulateLidars = true
private

Definition at line 211 of file LidarManager.h.

Referenced by SetSimulateLidars(), and SimulateRaycastLidars().

◆ TickAdded

bool ALidarManager::TickAdded = false
private

Definition at line 162 of file LidarManager.h.

Referenced by AddRaycastLidar(), EndPlay(), and RemoveRaycastLidar().

◆ TickEntry

FTickEntry ALidarManager::TickEntry
private

Definition at line 160 of file LidarManager.h.

Referenced by AddRaycastLidar(), EndPlay(), and RemoveRaycastLidar().

◆ TimeInMilliseconds

float ALidarManager::TimeInMilliseconds

Definition at line 150 of file LidarManager.h.

Referenced by TickParallel().

◆ TotalAverageTimer

SimpleTimer* ALidarManager::TotalAverageTimer = nullptr
private

Definition at line 209 of file LidarManager.h.

Referenced by BeginPlay(), EndPlay(), RemoveRaycastLidar(), and TickParallel().


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