Agrarsense
Radar.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 "CoreMinimal.h"
9#include "Templates/SharedPointer.h"
10#include "Engine/HitResult.h"
11
13#include "RadarParameters.h"
14
15#include "ROSIntegration/Public/sensor_msgs/PointCloud2.h"
16
17#include "Radar.generated.h"
18
19class UNiagaraComponent;
20
24UCLASS()
25class AGRARSENSE_API ARadar : public ASensor
26{
27 GENERATED_BODY()
28
29public:
30
31 ARadar(const FObjectInitializer& ObjectInitializer);
32
37 void Init(FRadarParameters parameters, bool SimulateSensor = true);
38
43 virtual ESensorTypes GetSensorType() const override { return ESensorTypes::Radar; }
44
49 UFUNCTION(BlueprintCallable)
50 void ChangeRadarParameters(FRadarParameters Parameters);
51
56 UFUNCTION(BlueprintCallable)
57 void SetVisualizeParticles(bool Visualize);
58
63 UFUNCTION(BlueprintCallable, BlueprintPure)
64 FRadarParameters GetRadarParameters()
65 {
66 return RadarParameters;
67 }
68
72 virtual FString GetParametersAsString() const override
73 {
74 return StructToString(RadarParameters);
75 }
76
77private:
78
79 void BeginPlay() override;
80
81 virtual void Tick(float DeltaTime) override;
82
83 virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
84
85 void SendRadarData();
86
87 UPROPERTY()
88 UNiagaraComponent* NiagaraComponent;
89
90 bool VisualizeParticles = false;
91
92 UPROPERTY()
93 TArray<FVector> HitLocations;
94
95 FRadarParameters RadarParameters;
96
97 FRadarParameters TempRadarParameters;
98
99 void SetRadarParameters(FRadarParameters Parameters);
100
101 void CalculateCurrentVelocity(const float DeltaTime);
102
103 void SimulateRadar(float DeltaTime);
104
105 float CalculateRelativeVelocity(const FHitResult& OutHit, const FVector& RadarLocation, const FVector ActorVelocity);
106
107 FVector CurrentVelocity;
108
109 // Used to compute the velocity of the radar
110 FVector PrevLocation;
111
112 struct RayData
113 {
114 float Radius;
115 float Angle;
116 bool Hit;
119 float Distance;
120 FVector HitPoint;
121 };
122
124 {
125 float velocity; // m/s
126 float azimuth; // rad
127 float altitude; // rad
128 float depth; // m
129 };
130
131 std::vector<RayData> Rays;
132 std::vector<FRadarDetection> detections;
133
134 UWorld* World = nullptr;
135
136 bool RadarParametersChanged = false;
137
139 {
140 float x;
141 float y;
142 float z;
143 float range;
144 float velocity;
145 float azimuth;
147 };
148
149 TSharedPtr<ROSMessages::sensor_msgs::PointCloud2> RadarMessage;
150};
ESensorTypes
Definition: SensorTypes.h:15
Definition: Radar.h:26
virtual ESensorTypes GetSensorType() const override
Definition: Radar.h:43
std::vector< RayData > Rays
Definition: Radar.h:131
TSharedPtr< ROSMessages::sensor_msgs::PointCloud2 > RadarMessage
Definition: Radar.h:149
std::vector< FRadarDetection > detections
Definition: Radar.h:132
virtual FString GetParametersAsString() const override
Definition: Radar.h:72
Definition: Sensor.h:44
float azimuth
Definition: Radar.h:145
float velocity
Definition: Radar.h:144
float elevationAng
Definition: Radar.h:146
FVector HitPoint
Definition: Radar.h:120
float RelativeVelocity
Definition: Radar.h:117
float Angle
Definition: Radar.h:115
float Radius
Definition: Radar.h:114
FVector2D AzimuthAndElevation
Definition: Radar.h:118
float Distance
Definition: Radar.h:119