8#include "GameFramework/Actor.h"
9#include "CoreMinimal.h"
15#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
17#include "LidarManager.generated.h"
22class UNiagaraComponent;
24class UROSIntegrationGameInstance;
52 UFUNCTION(BlueprintCallable)
53 void SetSimulateLidars(
bool bSimulateLidars);
59 UFUNCTION(BlueprintCallable)
60 void SetMeasurePerformance(
bool bMeasurePerformance);
66 UFUNCTION(BlueprintCallable)
67 void SetSaveCombinedCloudToDisk(
bool bSaveCombinedCloud);
73 UFUNCTION(BlueprintCallable)
74 void SetSendCombinedCloud(
bool bSaveCombinedCloud);
80 void AddRaycastLidar(
ALidar* lidarPtr);
86 void RemoveRaycastLidar(
ALidar* lidarPtr);
92 UFUNCTION(BlueprintCallable)
93 int GetLidarCount()
const
95 return RaycastLidars.size();
102 UFUNCTION(BlueprintCallable)
107 TArray<ALidar*> Lidars;
109 for (int32 i = 0; i < RaycastLidars.size(); i++)
111 ALidar* LidarPtr = RaycastLidars[i];
114 Lidars.Add(LidarPtr);
123 return RaycastLidars;
130 UPROPERTY(BlueprintAssignable)
131 FLidarDelegate_LidarSpawned OnLidarSpawned;
137 UPROPERTY(BlueprintAssignable)
138 FLidarDelegate_LidarDestroyed OnLidarDestroyed;
140 UPROPERTY(BlueprintReadOnly)
141 bool SendCombinedCloudToROS = true;
143 UPROPERTY(BlueprintReadOnly)
144 bool SaveCombinedCloudToDisk = false;
146 UPROPERTY(BlueprintReadOnly);
147 bool MeasurePerformance = false;
149 UPROPERTY(BlueprintReadOnly)
150 float TimeInMilliseconds;
154 virtual
void BeginPlay() override;
156 virtual
void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
158 void TickParallel(
float DeltaTime);
162 bool TickAdded = false;
168 void SimulateRaycastLidars(const
float DeltaTime);
173 void SendCombinedPointcloud(const std::vector<
FPointData>& points);
179 void SaveCombinedPointcloud(const std::vector<
FPointData>& points);
186 void ROSBridgeStateChanged(
EROSState RosState);
204 UROSIntegrationGameInstance* RosInstance =
nullptr;
207 TWeakObjectPtr<UTopic> CombinedLidarTopic;
211 bool SimulateLidars = true;
213 FString FileSavePath;
217 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> PointCloudMessage;
DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FLidarDelegate_LidarSpawned, ALidar *, lidar)
std::vector< ALidar * > GetAllLidarsVector() const