CARLA
Radar.h
Go to the documentation of this file.
1 // Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma
2 // de Barcelona (UAB).
3 //
4 // This work is licensed under the terms of the MIT license.
5 // For a copy, see <https://opensource.org/licenses/MIT>.
6 
7 #pragma once
8 
9 #include "Carla/Sensor/Sensor.h"
10 
12 
16 
17 #include "Radar.generated.h"
18 
19 /// A ray-cast based Radar sensor.
20 UCLASS()
21 class CARLA_API ARadar : public ASensor
22 {
23  GENERATED_BODY()
24 
25  using FRadarData = carla::sensor::data::RadarData;
26 
27 public:
28 
29  static FActorDefinition GetSensorDefinition();
30 
31  ARadar(const FObjectInitializer &ObjectInitializer);
32 
33  void Set(const FActorDescription &Description) override;
34 
35  UFUNCTION(BlueprintCallable, Category = "Radar")
36  void SetHorizontalFOV(float NewHorizontalFOV);
37 
38  UFUNCTION(BlueprintCallable, Category = "Radar")
39  void SetVerticalFOV(float NewVerticalFOV);
40 
41  UFUNCTION(BlueprintCallable, Category = "Radar")
42  void SetRange(float NewRange);
43 
44  UFUNCTION(BlueprintCallable, Category = "Radar")
45  void SetPointsPerSecond(int NewPointsPerSecond);
46 
47 protected:
48 
49  void BeginPlay() override;
50 
51  // virtual void PrePhysTick(float DeltaTime) override;
52  virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override;
53 
54  UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="Detection")
55  float Range;
56 
57  UPROPERTY(VisibleAnywhere, BlueprintReadOnly, Category="Detection")
58  float HorizontalFOV;
59 
60  UPROPERTY(VisibleAnywhere, BlueprintReadOnly, Category="Detection")
61  float VerticalFOV;
62 
63  UPROPERTY(VisibleAnywhere, BlueprintReadOnly, Category="Detection")
64  int PointsPerSecond;
65 
66 private:
67 
68  void CalculateCurrentVelocity(const float DeltaTime);
69 
70  void SendLineTraces(float DeltaTime);
71 
72  float CalculateRelativeVelocity(const FHitResult& OutHit, const FVector& RadarLocation);
73 
74  FRadarData RadarData;
75 
76  FCollisionQueryParams TraceParams;
77 
78  FVector CurrentVelocity;
79 
80  /// Used to compute the velocity of the radar
81  FVector PrevLocation;
82 
83  struct RayData {
84  float Radius;
85  float Angle;
86  bool Hitted;
89  float Distance;
90  };
91 
92  std::vector<RayData> Rays;
93 };
std::vector< RayData > Rays
Definition: Radar.h:92
float RelativeVelocity
Definition: Radar.h:87
This file contains definitions of common data structures used in traffic manager. ...
Definition: Carla.cpp:133
A definition of a Carla Actor with all the variation and attributes.
A ray-cast based Radar sensor.
Definition: Radar.h:21
bool Hitted
Definition: Radar.h:86
float Radius
Definition: Radar.h:84
A description of a Carla Actor with all its variation.
float Angle
Definition: Radar.h:85
float Distance
Definition: Radar.h:89
FVector2D AzimuthAndElevation
Definition: Radar.h:88