A ray-cast based Radar sensor. More...
#include <Radar.h>
Classes | |
struct | RayData |
Public Member Functions | |
ARadar (const FObjectInitializer &ObjectInitializer) | |
void | Set (const FActorDescription &Description) override |
void | SetHorizontalFOV (float NewHorizontalFOV) |
void | SetPointsPerSecond (int NewPointsPerSecond) |
void | SetRange (float NewRange) |
void | SetVerticalFOV (float NewVerticalFOV) |
Public Member Functions inherited from ASensor | |
ASensor (const FObjectInitializer &ObjectInitializer) | |
boost::optional< FActorAttribute > | GetAttribute (const FString Name) |
const UCarlaEpisode & | GetEpisode () const |
URandomEngine * | GetRandomEngine () |
int32 | GetSeed () const |
auto | GetToken () const |
Return the token that allows subscribing to this sensor's stream. More... | |
bool | IsStreamReady () |
FDataStream | MoveDataStream () |
virtual void | OnFirstClientConnected () |
virtual void | OnLastClientDisconnected () |
void | PostPhysTickInternal (UWorld *World, ELevelTick TickType, float DeltaSeconds) |
virtual void | PrePhysTick (float DeltaSeconds) |
void | SetDataStream (FDataStream InStream) |
Replace the FDataStream associated with this sensor. More... | |
void | SetEpisode (const UCarlaEpisode &InEpisode) |
void | SetSeed (int32 InSeed) |
void | Tick (const float DeltaTime) final |
Static Public Member Functions | |
static FActorDefinition | GetSensorDefinition () |
Protected Member Functions | |
void | BeginPlay () override |
virtual void | PostPhysTick (UWorld *World, ELevelTick TickType, float DeltaTime) override |
Protected Member Functions inherited from ASensor | |
void | EndPlay (EEndPlayReason::Type EndPlayReason) override |
template<typename SensorT > | |
FAsyncDataStream | GetDataStream (const SensorT &Self) |
Return the FDataStream associated with this sensor. More... | |
void | PostActorCreated () override |
Protected Attributes | |
float | HorizontalFOV |
int | PointsPerSecond |
float | Range |
float | VerticalFOV |
Protected Attributes inherited from ASensor | |
bool | bIsActive = false |
URandomEngine * | RandomEngine = nullptr |
Random Engine used to provide noise for sensor output. More... | |
int32 | Seed = 123456789 |
Seed of the pseudo-random engine. More... | |
Private Types | |
using | FRadarData = carla::sensor::data::RadarData |
Private Member Functions | |
void | CalculateCurrentVelocity (const float DeltaTime) |
float | CalculateRelativeVelocity (const FHitResult &OutHit, const FVector &RadarLocation) |
void | SendLineTraces (float DeltaTime) |
Private Attributes | |
FVector | CurrentVelocity |
FVector | PrevLocation |
Used to compute the velocity of the radar. More... | |
FRadarData | RadarData |
std::vector< RayData > | Rays |
FCollisionQueryParams | TraceParams |
|
private |
ARadar::ARadar | ( | const FObjectInitializer & | ObjectInitializer | ) |
Definition at line 25 of file Radar.cpp.
References ASensor::RandomEngine, and TraceParams.
|
overrideprotectedvirtual |
|
private |
Definition at line 108 of file Radar.cpp.
References CurrentVelocity, and PrevLocation.
Referenced by PostPhysTick().
|
private |
Definition at line 202 of file Radar.cpp.
References CurrentVelocity.
Referenced by SendLineTraces().
|
static |
Definition at line 20 of file Radar.cpp.
References UActorBlueprintFunctionLibrary::MakeRadarDefinition().
|
overrideprotectedvirtual |
Reimplemented from ASensor.
Definition at line 72 of file Radar.cpp.
References CalculateCurrentVelocity(), carla::streaming::detail::token_type::get_stream_id(), ASensor::GetDataStream(), carla::ros2::ROS2::GetInstance(), ASensor::GetToken(), RadarData, carla::sensor::data::RadarData::Reset(), and SendLineTraces().
|
private |
Definition at line 115 of file Radar.cpp.
References CalculateRelativeVelocity(), URandomEngine::GetUniformFloat(), URandomEngine::GetUniformFloatInRange(), HorizontalFOV, PointsPerSecond, RadarData, ASensor::RandomEngine, Range, Rays, TraceParams, VerticalFOV, and carla::sensor::data::RadarData::WriteDetection().
Referenced by PostPhysTick().
|
overridevirtual |
Reimplemented from ASensor.
Definition at line 38 of file Radar.cpp.
References UActorBlueprintFunctionLibrary::SetRadar().
void ARadar::SetHorizontalFOV | ( | float | NewHorizontalFOV | ) |
Definition at line 44 of file Radar.cpp.
References HorizontalFOV.
Referenced by UActorBlueprintFunctionLibrary::SetRadar().
void ARadar::SetPointsPerSecond | ( | int | NewPointsPerSecond | ) |
Definition at line 59 of file Radar.cpp.
References PointsPerSecond, RadarData, and carla::sensor::data::RadarData::SetResolution().
Referenced by UActorBlueprintFunctionLibrary::SetRadar().
void ARadar::SetRange | ( | float | NewRange | ) |
Definition at line 54 of file Radar.cpp.
References Range.
Referenced by UActorBlueprintFunctionLibrary::SetRadar().
void ARadar::SetVerticalFOV | ( | float | NewVerticalFOV | ) |
Definition at line 49 of file Radar.cpp.
References VerticalFOV.
Referenced by UActorBlueprintFunctionLibrary::SetRadar().
|
private |
Definition at line 78 of file Radar.h.
Referenced by CalculateCurrentVelocity(), and CalculateRelativeVelocity().
|
protected |
Definition at line 58 of file Radar.h.
Referenced by SendLineTraces(), and SetHorizontalFOV().
|
protected |
Definition at line 64 of file Radar.h.
Referenced by SendLineTraces(), and SetPointsPerSecond().
|
private |
Used to compute the velocity of the radar.
Definition at line 81 of file Radar.h.
Referenced by BeginPlay(), and CalculateCurrentVelocity().
|
private |
Definition at line 74 of file Radar.h.
Referenced by PostPhysTick(), SendLineTraces(), and SetPointsPerSecond().
|
protected |
Definition at line 55 of file Radar.h.
Referenced by SendLineTraces(), and SetRange().
|
private |
Definition at line 92 of file Radar.h.
Referenced by SendLineTraces().
|
private |
Definition at line 76 of file Radar.h.
Referenced by ARadar(), and SendLineTraces().
|
protected |
Definition at line 61 of file Radar.h.
Referenced by SendLineTraces(), and SetVerticalFOV().