Agrarsense
LidarManager.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 "LidarManager.h"
7
13
14#include "ROSIntegration/Classes/ROSIntegrationGameInstance.h"
15#include "ROSIntegration/Classes/RI/Topic.h"
16
17#include "PhysicsEngine/PhysicsObjectExternalInterface.h"
18#include "Physics/Experimental/PhysScene_Chaos.h"
19#include "Physics/PhysicsInterfaceUtils.h"
20
21#include "Math/Vector.h"
22#include "Engine/CollisionProfile.h"
23#include "Runtime/Engine/Classes/Kismet/KismetMathLibrary.h"
24#include "Runtime/Core/Public/Async/ParallelFor.h"
25#include "Kismet/GameplayStatics.h"
26#include "Kismet/KismetMathLibrary.h"
27#include "Misc/CommandLine.h"
28
29#include <iterator>
30
31ALidarManager::ALidarManager(const FObjectInitializer& ObjectInitializer) : 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}
41
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->CreateDefaultPointCloud2Message();
70}
71
72void ALidarManager::EndPlay(const EEndPlayReason::Type EndPlayReason)
73{
74 Super::EndPlay(EndPlayReason);
75
77
78 PointCloudMessage.Reset();
79
80 RaycastLidars.clear();
81
82 RosInstance = nullptr;
83
84 delete(TotalAverageTimer);
85
86 if (TickAdded)
87 {
89 }
90}
91
92void ALidarManager::TickParallel(float DeltaTime)
93{
94#ifdef WITH_EDITOR
96 {
98 }
99#endif
100
101 SimulateLidars(DeltaTime);
102
103#ifdef WITH_EDITOR
105 {
106 double ms = TotalAverageTimer->PrintAverageTime();
107 TimeInMilliseconds = FMath::RoundToFloat(ms * 100.0f) / 100.0f;
108 }
109#endif
110}
111
112void ALidarManager::SimulateLidars(const float DeltaTime)
113{
114 TRACE_CPUPROFILER_EVENT_SCOPE(ALidarManager::SimulateLidars);
115
116 const int32 LidarCount = RaycastLidars.size();
117
118 if (LidarCount == 0 || !CanSimulateLidars)
119 {
120 return;
121 }
122
123 std::vector<FPointData> FlattenedPoints;
124
125 if (LidarCount == 1)
126 {
127 // If we only have one lidar sensor,
128 // we can skip ParallelFor and 2D to 1D std::vector conversion overhead completely
129 ALidar* lidar = RaycastLidars[0];
130 if (lidar)
131 {
132#ifdef ParallelLineTraceSingleByChannel_EXISTS
133 // ParallelLineTraceSingleByChannel_EXISTS Defined and implemented in AGRARSENSE Unreal Engine fork
134 // Lock physics scene while linetracing.
135 auto PhysicsLock = FPhysicsObjectExternalInterface::LockRead(GetWorld()->GetPhysicsScene());
136 {
137#endif
138 FlattenedPoints = lidar->SimulateRaycastLidar(DeltaTime);
139
140#ifdef ParallelLineTraceSingleByChannel_EXISTS
141 }
142 PhysicsLock.Release();
143#endif
144 }
145 }
146 else
147 {
148 // Else we have multiple Lidar sensors,
149 // Simulate all of them in parallel
150 std::vector<std::vector<FPointData>> points(LidarCount);
151
152#ifdef ParallelLineTraceSingleByChannel_EXISTS
153 // ParallelLineTraceSingleByChannel_EXISTS Defined and implemented in AGRARSENSE Unreal Engine fork
154 // Lock physics scene while linetracing.
155 auto PhysicsLock = FPhysicsObjectExternalInterface::LockRead(GetWorld()->GetPhysicsScene());
156 {
157#endif
158 ParallelFor(LidarCount, [&](int32 lidarIndex)
159 {
160 ALidar* lidar = RaycastLidars[lidarIndex];
161 if (lidar)
162 {
163 points[lidarIndex] = lidar->SimulateRaycastLidar(DeltaTime);
164 }
165 }, EParallelForFlags::Unbalanced);
166
167#ifdef ParallelLineTraceSingleByChannel_EXISTS
168 }
169 PhysicsLock.Release();
170#endif
172 {
173 int32 TotalSize = 0;
174 for (const std::vector<FPointData>& vec : points)
175 {
176 TotalSize += vec.size();
177 }
178
179 if (TotalSize != 0)
180 {
181 FlattenedPoints.reserve(TotalSize);
182 for (std::vector<FPointData>& vec : points)
183 {
184 FlattenedPoints.insert(FlattenedPoints.end(), std::make_move_iterator(vec.begin()), std::make_move_iterator(vec.end()));
185 }
186 }
187 }
188 }
189
190 if (!FlattenedPoints.empty())
191 {
193 {
194 SaveCombinedPointcloud(FlattenedPoints);
195 }
196
197 SendCombinedPointcloud(FlattenedPoints);
198 }
199}
200
201void ALidarManager::SetSimulateLidars(bool bSimulateLidars)
202{
203 CanSimulateLidars = bSimulateLidars;
204}
205
206void ALidarManager::SetMeasurePerformance(bool bMeasurePerformance)
207{
208 MeasurePerformance = bMeasurePerformance;
209}
210
211void ALidarManager::SetSaveCombinedCloudToDisk(bool bSaveCombinedCloud)
212{
213 SaveCombinedCloudToDisk = bSaveCombinedCloud;
214}
215
216void ALidarManager::SetSendCombinedCloud(bool bSaveCombinedCloud)
217{
218 SendCombinedCloudToROS = bSaveCombinedCloud;
220 {
221 InitTopic();
222 }
223
224#if WITH_EDITOR
225 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Saving combined Lidar pointcloud to disk: %s"), (SendCombinedCloudToROS ? TEXT("true") : TEXT("false")));
226#endif
227}
228
230{
231 if (!lidarPtr)
232 {
233 return;
234 }
235
236 RaycastLidars.push_back(lidarPtr);
237
238#if WITH_EDITOR
239 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Added Lidar sensor."));
240#endif
241
242 if (!TickAdded)
243 {
244 InitTopic();
245
246 TickEntry = ATickManager::AddTick(this, BindTick(this, &ALidarManager::TickParallel), ETickType::FullFrameTaskParallel);
247 TickAdded = true;
248 }
249
250 // Broadcast new lidar has been spawned, broadcast Lidar actor
251 OnLidarSpawned.Broadcast(lidarPtr);
252}
253
255{
256 if (!lidarPtr)
257 {
258 return;
259 }
260
261 auto it = std::find(RaycastLidars.begin(), RaycastLidars.end(), lidarPtr);
262 if (it != RaycastLidars.end())
263 {
264 RaycastLidars.erase(it);
265
266#if WITH_EDITOR
267 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Removed Lidar sensor"));
268#endif
269 }
270
271 // Disable tick if there's no Lidar sensors.
272 if (RaycastLidars.size() == 0)
273 {
275 if (TickAdded)
276 {
278 TickAdded = false;
279 DestroyTopic();
280 }
281 }
282
283 // Broadcast lidar sensor has been destroyed event and broadcast current lidar count
284 int currentLidarCount = RaycastLidars.size();
285 OnLidarDestroyed.Broadcast(currentLidarCount);
286}
287
289{
290 switch (RosState)
291 {
293 InitTopic();
294 break;
295
297 DestroyTopic();
298 break;
299 }
300}
301
303{
304 if (CombinedLidarTopic.IsValid() || !SendCombinedCloudToROS || !RosInstance->IsROSConnected())
305 {
306 return;
307 }
308
309 CombinedLidarTopic = NewObject<UTopic>(UTopic::StaticClass());
310 CombinedLidarTopic->Init(RosInstance->ROSIntegrationCore, FString::Printf(TEXT("/agrarsense/out/sensors/lidars_combined")), TEXT("sensor_msgs/PointCloud2"));
311 CombinedLidarTopic->Advertise();
312
313#if WITH_EDITOR
314 UE_LOG(LogTemp, Warning, TEXT("LidarManager.cpp: Created combined Lidar ROS topic. Topic name: /agrarsense/sensors/lidars_combined"));
315#endif
316}
317
319{
320 if (CombinedLidarTopic.IsValid())
321 {
322 CombinedLidarTopic->Unadvertise();
323 CombinedLidarTopic->Unsubscribe();
324 CombinedLidarTopic->MarkAsDisconnected();
325 CombinedLidarTopic->ConditionalBeginDestroy();
326 CombinedLidarTopic.Reset();
327 }
328}
329
330void ALidarManager::SaveCombinedPointcloud(const std::vector<FPointData>& points)
331{
333 {
334 return;
335 }
336
337 FString Filename = FString::Printf(TEXT("%sCombinedPointcloud_%d.ply"), *FileSavePath, LidarSaves);
338 ++LidarSaves;
339
341}
342
343void ALidarManager::SendCombinedPointcloud(const std::vector<FPointData>& points)
344{
345 TRACE_CPUPROFILER_EVENT_SCOPE(ALidarManager::SendCombinedPointcloud);
346
347 UTopic* Topic = CombinedLidarTopic.Get();
348
350 || !RosInstance
351 || !RosInstance->IsROSConnected()
352 || !Topic
353 || !PointCloudMessage.IsValid())
354 {
355 return;
356 }
357
358 const size_t PointsSize = points.size();
359 const size_t DataSize = PointsSize * sizeof(FPointData);
360
361 PointCloudMessage->width = static_cast<uint32>(PointsSize);
362 PointCloudMessage->row_step = static_cast<uint32>(DataSize);
363 PointCloudMessage->data_ptr = reinterpret_cast<uint8*>(const_cast<FPointData*>(points.data()));
364 Topic->Publish(PointCloudMessage);
365}
EROSState
Definition: ROSState.h:16
static auto BindTick(ObjectType *Object, FunctionType Function)
Definition: TickManager.h:182
bool CanSimulateLidars
Definition: LidarManager.h:213
void SendCombinedPointcloud(const std::vector< FPointData > &points)
FString FileSavePath
Definition: LidarManager.h:215
FLidarDelegate_LidarSpawned OnLidarSpawned
Definition: LidarManager.h:131
UROSIntegrationGameInstance * RosInstance
Definition: LidarManager.h:204
void SaveCombinedPointcloud(const std::vector< FPointData > &points)
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
Definition: LidarManager.h:209
virtual void BeginPlay() override
TWeakObjectPtr< UTopic > CombinedLidarTopic
Definition: LidarManager.h:207
void SetSaveCombinedCloudToDisk(bool bSaveCombinedCloud)
void AddRaycastLidar(ALidar *lidarPtr)
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
bool SaveCombinedCloudToDisk
Definition: LidarManager.h:144
FTickEntry TickEntry
Definition: LidarManager.h:160
void ROSBridgeStateChanged(EROSState RosState)
void SetSendCombinedCloud(bool bSaveCombinedCloud)
void SetMeasurePerformance(bool bMeasurePerformance)
void SetSimulateLidars(bool bSimulateLidars)
float TimeInMilliseconds
Definition: LidarManager.h:150
void RemoveRaycastLidar(ALidar *lidarPtr)
SimpleTimer * TotalAverageTimer
Definition: LidarManager.h:211
void SimulateLidars(const float DeltaTime)
ALidarManager(const FObjectInitializer &ObjectInitializer)
bool SendCombinedCloudToROS
Definition: LidarManager.h:141
std::vector< ALidar * > RaycastLidars
Definition: LidarManager.h:201
FLidarDelegate_LidarDestroyed OnLidarDestroyed
Definition: LidarManager.h:138
void TickParallel(float DeltaTime)
bool MeasurePerformance
Definition: LidarManager.h:147
Definition: Lidar.h:34
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
Definition: Lidar.cpp:247
static void RemoveTick(FTickEntry TickEntry)
Definition: TickManager.cpp:90
static FTickEntry AddTick(UObject *Object, std::function< void(float)> Function, ETickType Type)
Definition: TickManager.cpp:55
double PrintAverageTime(FString prefix="Average execution time ", FString suffix=" milliseconds", bool printToScreen=false)
Definition: SimpleTimer.h:123
void TakeTimeStamp()
Definition: SimpleTimer.h:76
void ResetAverageTime()
Definition: SimpleTimer.h:141
static FString GetDataFolder()
static void SaveVectorArrayAsPlyAsync(FString FullFileName, const std::vector< FPointData > points)