Agrarsense
LidarManager.h
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#pragma once
7
8#include "GameFramework/Actor.h"
9#include "CoreMinimal.h"
10#include <vector>
11
14
15#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
16
17#include "LidarManager.generated.h"
18
19class SimpleTimer;
20class ALidar;
21class UROSHandler;
22class UNiagaraComponent;
23class UTopic;
24class UROSIntegrationGameInstance;
25
29DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FLidarDelegate_LidarSpawned, ALidar*, lidar);
30
34DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FLidarDelegate_LidarDestroyed, int, lidarCount);
35
39UCLASS()
40class AGRARSENSE_API ALidarManager : public AActor
41{
42 GENERATED_BODY()
43
44public:
45
46 ALidarManager(const FObjectInitializer& ObjectInitializer);
47
52 UFUNCTION(BlueprintCallable)
53 void SetSimulateLidars(bool bSimulateLidars);
54
59 UFUNCTION(BlueprintCallable)
60 void SetMeasurePerformance(bool bMeasurePerformance);
61
66 UFUNCTION(BlueprintCallable)
67 void SetSaveCombinedCloudToDisk(bool bSaveCombinedCloud);
68
73 UFUNCTION(BlueprintCallable)
74 void SetSendCombinedCloud(bool bSaveCombinedCloud);
75
80 void AddRaycastLidar(ALidar* lidarPtr);
81
86 void RemoveRaycastLidar(ALidar* lidarPtr);
87
92 UFUNCTION(BlueprintCallable)
93 int GetLidarCount() const
94 {
95 return RaycastLidars.size();
96 }
97
102 UFUNCTION(BlueprintCallable)
103 TArray<ALidar*> GetAllLidars() const
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 }
120
121 std::vector<ALidar*> GetAllLidarsVector() const
122 {
123 return RaycastLidars;
124 }
125
130 UPROPERTY(BlueprintAssignable)
131 FLidarDelegate_LidarSpawned OnLidarSpawned;
132
137 UPROPERTY(BlueprintAssignable)
138 FLidarDelegate_LidarDestroyed OnLidarDestroyed;
139
140 UPROPERTY(BlueprintReadOnly)
141 bool SendCombinedCloudToROS = true;
142
143 UPROPERTY(BlueprintReadOnly)
144 bool SaveCombinedCloudToDisk = false;
145
146 UPROPERTY(BlueprintReadOnly);
147 bool MeasurePerformance = false;
148
149 UPROPERTY(BlueprintReadOnly)
150 float TimeInMilliseconds;
151
152private:
153
154 virtual void BeginPlay() override;
155
156 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
157
158 void TickParallel(float DeltaTime);
159
160 FTickEntry TickEntry;
161
162 bool TickAdded = false;
163
168 void SimulateRaycastLidars(const float DeltaTime);
169
173 void SendCombinedPointcloud(const std::vector<FPointData>& points);
174
175
179 void SaveCombinedPointcloud(const std::vector<FPointData>& points);
180
185 UFUNCTION()
186 void ROSBridgeStateChanged(EROSState RosState);
187
191 void InitTopic();
192
196 void DestroyTopic();
197
201 std::vector<ALidar*> RaycastLidars;
202
203 UPROPERTY()
204 UROSIntegrationGameInstance* RosInstance = nullptr;
205
206 UPROPERTY()
207 TWeakObjectPtr<UTopic> CombinedLidarTopic;
208
209 SimpleTimer* TotalAverageTimer = nullptr;
210
211 bool SimulateLidars = true;
212
213 FString FileSavePath;
214
215 int LidarSaves = 0;
216
217 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> PointCloudMessage;
218};
DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FLidarDelegate_LidarSpawned, ALidar *, lidar)
EROSState
Definition: ROSState.h:16
std::vector< ALidar * > GetAllLidarsVector() const
Definition: LidarManager.h:121
Definition: Lidar.h:34