CARLA
 
载入中...
搜索中...
未找到
Radar.cpp
浏览该文件的文档.
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#include <PxScene.h>
8
9#include "Carla.h"
10#include "Carla/Sensor/Radar.h"
12#include "Kismet/KismetMathLibrary.h"
13#include "Runtime/Core/Public/Async/ParallelFor.h"
14
16#include "carla/geom/Math.h"
17#include "carla/ros2/ROS2.h"
19
24
25ARadar::ARadar(const FObjectInitializer& ObjectInitializer)
26 : Super(ObjectInitializer)
27{
28 PrimaryActorTick.bCanEverTick = true;
29
30 RandomEngine = CreateDefaultSubobject<URandomEngine>(TEXT("RandomEngine"));
31
32 TraceParams = FCollisionQueryParams(FName(TEXT("Laser_Trace")), true, this);
33 TraceParams.bTraceComplex = true;
34 TraceParams.bReturnPhysicalMaterial = false;
35
36}
37
38void ARadar::Set(const FActorDescription &ActorDescription)
39{
40 Super::Set(ActorDescription);
41 UActorBlueprintFunctionLibrary::SetRadar(ActorDescription, this);
42}
43
44void ARadar::SetHorizontalFOV(float NewHorizontalFOV)
45{
46 HorizontalFOV = NewHorizontalFOV;
47}
48
49void ARadar::SetVerticalFOV(float NewVerticalFOV)
50{
51 VerticalFOV = NewVerticalFOV;
52}
53
54void ARadar::SetRange(float NewRange)
55{
56 Range = NewRange;
57}
58
59void ARadar::SetPointsPerSecond(int NewPointsPerSecond)
60{
61 PointsPerSecond = NewPointsPerSecond;
63}
64
66{
67 Super::BeginPlay();
68
69 PrevLocation = GetActorLocation();
70}
71
72void ARadar::PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime)
73{
74 TRACE_CPUPROFILER_EVENT_SCOPE(ARadar::PostPhysTick);
75 CalculateCurrentVelocity(DeltaTime);
76
78 SendLineTraces(DeltaTime);
79
80 auto DataStream = GetDataStream(*this);
81
82 // ROS2
83 #if defined(WITH_ROS2)
85 if (ROS2->IsEnabled())
86 {
87 TRACE_CPUPROFILER_EVENT_SCOPE_STR("ROS2 Send");
89 AActor* ParentActor = GetAttachParentActor();
90 if (ParentActor)
91 {
92 FTransform LocalTransformRelativeToParent = GetActorTransform().GetRelativeTransform(ParentActor->GetActorTransform());
93 ROS2->ProcessDataFromRadar(DataStream.GetSensorType(), StreamId, LocalTransformRelativeToParent, RadarData, this);
94 }
95 else
96 {
97 ROS2->ProcessDataFromRadar(DataStream.GetSensorType(), StreamId, DataStream.GetSensorTransform(), RadarData, this);
98 }
99 }
100 #endif
101
102 {
103 TRACE_CPUPROFILER_EVENT_SCOPE_STR("Send Stream");
104 DataStream.SerializeAndSend(*this, RadarData, DataStream.PopBufferFromPool());
105 }
106}
107
108void ARadar::CalculateCurrentVelocity(const float DeltaTime)
109{
110 const FVector RadarLocation = GetActorLocation();
111 CurrentVelocity = (RadarLocation - PrevLocation) / DeltaTime;
112 PrevLocation = RadarLocation;
113}
114
115void ARadar::SendLineTraces(float DeltaTime)
116{
117 TRACE_CPUPROFILER_EVENT_SCOPE(ARadar::SendLineTraces);
118 constexpr float TO_METERS = 1e-2;
119 const FTransform& ActorTransform = GetActorTransform();
120 const FRotator& TransformRotator = ActorTransform.Rotator();
121 const FVector& RadarLocation = GetActorLocation();
122 const FVector& ForwardVector = GetActorForwardVector();
123 const FVector TransformXAxis = ActorTransform.GetUnitAxis(EAxis::X);
124 const FVector TransformYAxis = ActorTransform.GetUnitAxis(EAxis::Y);
125 const FVector TransformZAxis = ActorTransform.GetUnitAxis(EAxis::Z);
126
127 // Maximum radar radius in horizontal and vertical direction
128 const float MaxRx = FMath::Tan(FMath::DegreesToRadians(HorizontalFOV * 0.5f)) * Range;
129 const float MaxRy = FMath::Tan(FMath::DegreesToRadians(VerticalFOV * 0.5f)) * Range;
130 const int NumPoints = (int)(PointsPerSecond * DeltaTime);
131
132 // Generate the parameters of the rays in a deterministic way
133 Rays.clear();
134 Rays.resize(NumPoints);
135 for (int i = 0; i < Rays.size(); i++) {
136 Rays[i].Radius = RandomEngine->GetUniformFloat();
137 Rays[i].Angle = RandomEngine->GetUniformFloatInRange(0.0f, carla::geom::Math::Pi2<float>());
138 Rays[i].Hitted = false;
139 }
140
141 FCriticalSection Mutex;
142 GetWorld()->GetPhysicsScene()->GetPxScene()->lockRead();
143 {
144 TRACE_CPUPROFILER_EVENT_SCOPE(ParallelFor);
145 ParallelFor(NumPoints, [&](int32 idx) {
146 TRACE_CPUPROFILER_EVENT_SCOPE(ParallelForTask);
147 FHitResult OutHit(ForceInit);
148 const float Radius = Rays[idx].Radius;
149 const float Angle = Rays[idx].Angle;
150
151 float Sin, Cos;
152 FMath::SinCos(&Sin, &Cos, Angle);
153
154 const FVector EndLocation = RadarLocation + TransformRotator.RotateVector({
155 Range,
156 MaxRx * Radius * Cos,
157 MaxRy * Radius * Sin
158 });
159
160 const bool Hitted = GetWorld()->ParallelLineTraceSingleByChannel(
161 OutHit,
162 RadarLocation,
163 EndLocation,
164 ECC_GameTraceChannel2,
166 FCollisionResponseParams::DefaultResponseParam
167 );
168
169 const TWeakObjectPtr<AActor> HittedActor = OutHit.Actor;
170 if (Hitted && HittedActor.Get()) {
171 Rays[idx].Hitted = true;
172
173 Rays[idx].RelativeVelocity = CalculateRelativeVelocity(OutHit, RadarLocation);
174
175 Rays[idx].AzimuthAndElevation = FMath::GetAzimuthAndElevation (
176 (EndLocation - RadarLocation).GetSafeNormal() * Range,
177 TransformXAxis,
178 TransformYAxis,
179 TransformZAxis
180 );
181
182 Rays[idx].Distance = OutHit.Distance * TO_METERS;
183 }
184 });
185 }
186 GetWorld()->GetPhysicsScene()->GetPxScene()->unlockRead();
187
188 // Write the detections in the output structure
189 for (auto& ray : Rays) {
190 if (ray.Hitted) {
192 ray.RelativeVelocity,
193 ray.AzimuthAndElevation.X,
194 ray.AzimuthAndElevation.Y,
195 ray.Distance
196 });
197 }
198 }
199
200}
201
202float ARadar::CalculateRelativeVelocity(const FHitResult& OutHit, const FVector& RadarLocation)
203{
204 constexpr float TO_METERS = 1e-2;
205
206 const TWeakObjectPtr<AActor> HittedActor = OutHit.Actor;
207 const FVector TargetVelocity = HittedActor->GetVelocity();
208 const FVector TargetLocation = OutHit.ImpactPoint;
209 const FVector Direction = (TargetLocation - RadarLocation).GetSafeNormal();
210 const FVector DeltaVelocity = (TargetVelocity - CurrentVelocity);
211 const float V = TO_METERS * FVector::DotProduct(DeltaVelocity, Direction);
212
213 return V;
214}
static FActorDefinition GetSensorDefinition()
Definition Radar.cpp:20
float Range
Definition Radar.h:55
float VerticalFOV
Definition Radar.h:61
void BeginPlay() override
Definition Radar.cpp:65
FVector CurrentVelocity
Definition Radar.h:78
float CalculateRelativeVelocity(const FHitResult &OutHit, const FVector &RadarLocation)
Definition Radar.cpp:202
int PointsPerSecond
Definition Radar.h:64
std::vector< RayData > Rays
Definition Radar.h:92
void SetPointsPerSecond(int NewPointsPerSecond)
Definition Radar.cpp:59
void SetHorizontalFOV(float NewHorizontalFOV)
Definition Radar.cpp:44
FVector PrevLocation
Used to compute the velocity of the radar
Definition Radar.h:81
void SendLineTraces(float DeltaTime)
Definition Radar.cpp:115
FCollisionQueryParams TraceParams
Definition Radar.h:76
virtual void PostPhysTick(UWorld *World, ELevelTick TickType, float DeltaTime) override
Definition Radar.cpp:72
ARadar(const FObjectInitializer &ObjectInitializer)
Definition Radar.cpp:25
void SetVerticalFOV(float NewVerticalFOV)
Definition Radar.cpp:49
void CalculateCurrentVelocity(const float DeltaTime)
Definition Radar.cpp:108
void SetRange(float NewRange)
Definition Radar.cpp:54
void Set(const FActorDescription &Description) override
Definition Radar.cpp:38
float HorizontalFOV
Definition Radar.h:58
FRadarData RadarData
Definition Radar.h:74
auto GetToken() const
Return the token that allows subscribing to this sensor's stream.
FAsyncDataStream GetDataStream(const SensorT &Self)
Return the FDataStream associated with this sensor.
URandomEngine * RandomEngine
Random Engine used to provide noise for sensor output.
static void SetRadar(const FActorDescription &Description, ARadar *Radar)
float GetUniformFloat()
float GetUniformFloatInRange(float Minimum, float Maximum)
static std::shared_ptr< ROS2 > GetInstance()
Definition ROS2.h:51
void Reset()
Deletes the current detections.
Definition RadarData.h:64
void SetResolution(uint32_t resolution)
Set a new resolution for the RadarData.
Definition RadarData.h:49
void WriteDetection(RadarDetection detection)
Adds a new detection.
Definition RadarData.h:69
Serializes a stream endpoint.
A definition of a Carla Actor with all the variation and attributes.
A description of a Carla Actor with all its variation.