14#include "ROSIntegration/Classes/ROSIntegrationGameInstance.h"
15#include "ROSIntegration/Classes/RI/Topic.h"
17#include "PhysicsEngine/PhysicsObjectExternalInterface.h"
18#include "Physics/Experimental/PhysScene_Chaos.h"
19#include "Physics/PhysicsInterfaceUtils.h"
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"
34 PrimaryActorTick.bCanEverTick =
false;
36 if (FParse::Param(FCommandLine::Get(), TEXT(
"-save-combined-pointcloud")))
47 UWorld* World = GetWorld();
48 TArray<AActor*> FoundActors;
49 UGameplayStatics::GetAllActorsOfClass(World, ALidarManager::StaticClass(), FoundActors);
50 if (FoundActors.Num() != 1)
53 UE_LOG(LogTemp, Warning, TEXT(
"LidarManager.cpp: LidarManager already exists in the level. Destroying this one."));
59 RosInstance = Cast<UROSIntegrationGameInstance>(GetGameInstance());
64 FString UnixTimeStamp = FString::FromInt(FDateTime::Now().ToUnixTimestamp());
65 FileSavePath = DataLocation +
"LidarCombined_" + UnixTimeStamp +
"/";
74 Super::EndPlay(EndPlayReason);
123 std::vector<FPointData> FlattenedPoints;
132#ifdef ParallelLineTraceSingleByChannel_EXISTS
135 auto PhysicsLock = FPhysicsObjectExternalInterface::LockRead(GetWorld()->GetPhysicsScene());
140#ifdef ParallelLineTraceSingleByChannel_EXISTS
142 PhysicsLock.Release();
150 std::vector<std::vector<FPointData>> points(LidarCount);
152#ifdef ParallelLineTraceSingleByChannel_EXISTS
155 auto PhysicsLock = FPhysicsObjectExternalInterface::LockRead(GetWorld()->GetPhysicsScene());
158 ParallelFor(LidarCount, [&](int32 lidarIndex)
165 }, EParallelForFlags::Unbalanced);
167#ifdef ParallelLineTraceSingleByChannel_EXISTS
169 PhysicsLock.Release();
174 for (
const std::vector<FPointData>& vec : points)
176 TotalSize += vec.size();
181 FlattenedPoints.reserve(TotalSize);
182 for (std::vector<FPointData>& vec : points)
184 FlattenedPoints.insert(FlattenedPoints.end(), std::make_move_iterator(vec.begin()), std::make_move_iterator(vec.end()));
190 if (!FlattenedPoints.empty())
225 UE_LOG(LogTemp, Warning, TEXT(
"LidarManager.cpp: Saving combined Lidar pointcloud to disk: %s"), (
SendCombinedCloudToROS ? TEXT(
"true") : TEXT(
"false")));
239 UE_LOG(LogTemp, Warning, TEXT(
"LidarManager.cpp: Added Lidar sensor."));
267 UE_LOG(LogTemp, Warning, TEXT(
"LidarManager.cpp: Removed Lidar sensor"));
310 CombinedLidarTopic->Init(
RosInstance->ROSIntegrationCore, FString::Printf(TEXT(
"/agrarsense/out/sensors/lidars_combined")), TEXT(
"sensor_msgs/PointCloud2"));
314 UE_LOG(LogTemp, Warning, TEXT(
"LidarManager.cpp: Created combined Lidar ROS topic. Topic name: /agrarsense/sensors/lidars_combined"));
358 const size_t PointsSize = points.size();
359 const size_t DataSize = PointsSize *
sizeof(
FPointData);
static auto BindTick(ObjectType *Object, FunctionType Function)
void SendCombinedPointcloud(const std::vector< FPointData > &points)
FLidarDelegate_LidarSpawned OnLidarSpawned
UROSIntegrationGameInstance * RosInstance
void SaveCombinedPointcloud(const std::vector< FPointData > &points)
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > PointCloudMessage
virtual void BeginPlay() override
TWeakObjectPtr< UTopic > CombinedLidarTopic
void SetSaveCombinedCloudToDisk(bool bSaveCombinedCloud)
void AddRaycastLidar(ALidar *lidarPtr)
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override
bool SaveCombinedCloudToDisk
void ROSBridgeStateChanged(EROSState RosState)
void SetSendCombinedCloud(bool bSaveCombinedCloud)
void SetMeasurePerformance(bool bMeasurePerformance)
void SetSimulateLidars(bool bSimulateLidars)
void RemoveRaycastLidar(ALidar *lidarPtr)
SimpleTimer * TotalAverageTimer
void SimulateLidars(const float DeltaTime)
ALidarManager(const FObjectInitializer &ObjectInitializer)
bool SendCombinedCloudToROS
std::vector< ALidar * > RaycastLidars
FLidarDelegate_LidarDestroyed OnLidarDestroyed
void TickParallel(float DeltaTime)
std::vector< FPointData > SimulateRaycastLidar(const float DeltaTime)
static void RemoveTick(FTickEntry TickEntry)
static FTickEntry AddTick(UObject *Object, std::function< void(float)> Function, ETickType Type)
double PrintAverageTime(FString prefix="Average execution time ", FString suffix=" milliseconds", bool printToScreen=false)
static FString GetDataFolder()
static void SaveVectorArrayAsPlyAsync(FString FullFileName, const std::vector< FPointData > points)