Retrieve BBs of level (#3360)

* Added new function to calculate BBs on SKM and SM

* Added BB calculation for an array of actors

* Added BB folliage calculation

* Added a call on the GM to get all the BBs of the level

* Fixed Folliage BB calculation.

* GM::GetAllBBsOfLevel now returns the array of BBs

* Added call on the server side to retrieve the BBs

* Removed debug draw calls

* Added call to the PythonAPI

* Added check for empty folliage actors

* Added missing EOF

* Added new RotateVector function

* Added rotation to the BBs

* Update changelog

* Split BB calculation on more functions

* Add tag query and simplified Folliage actor BB calculation

* Look for ISM instead of HISM

* Cleaning comments

* Fixed BB duplication on BP_Procedural_Buildings

* Fixed BB duplication on vehicles BPs

* Added pedestrians case

* Added CityObjectLabel enum on PythonAPI

* Splitted logic in small functions

* Fixed uint8_t

* Merged BB of the lights in a TL

* Splitted work into more functions

* Added missing BB and rotation to TL

* Cleaned comments

* Added missing include

* Changed None to Any in PythonAPI

* Fixed Any enum

* Added check for empty folliage actors

* Added missing EOF

* Added new RotateVector function

* Added rotation to the BBs

* Update changelog

* Split BB calculation on more functions

* Add tag query and simplified Folliage actor BB calculation

* Look for ISM instead of HISM

* Cleaning comments

* Fixed BB duplication on BP_Procedural_Buildings

* Fixed BB duplication on vehicles BPs

* Added pedestrians case

* Added CityObjectLabel enum on PythonAPI

* Splitted logic in small functions

* Fixed uint8_t

* Merged BB of the lights in a TL

* Splitted work into more functions

* Added missing BB and rotation to TL

* Cleaned comments

* Changed None to Any in PythonAPI

* Fixed Any enum

* Fixed rebase

* Fixing wrong BB on splines

* Fixed ISM transform to World

* Fixed duplication of RotateVector

* Added Rotation to BB output string

* Removed hidden components and procedural building

* Fixed string BB output

* Removed logs

* Fixed filter on pedestrians

* Fixed black debug lines in package

Co-authored-by: Marc Garcia Puig <marcgpuig@gmail.com>
This commit is contained in:
doterop 2020-09-24 23:33:11 +02:00 committed by GitHub
parent 25f1780a1e
commit e05b58c2a4
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
5 changed files with 41 additions and 40 deletions

View File

@ -88,30 +88,8 @@ namespace geom {
}
Vector3D RotateVector(const Vector3D& in_point) const {
// Rotates Rz(yaw) * Ry(pitch) * Rx(roll) = first x, then y, then z.
const float cy = std::cos(Math::ToRadians(yaw));
const float sy = std::sin(Math::ToRadians(yaw));
const float cr = std::cos(Math::ToRadians(roll));
const float sr = std::sin(Math::ToRadians(roll));
const float cp = std::cos(Math::ToRadians(pitch));
const float sp = std::sin(Math::ToRadians(pitch));
Vector3D out_point;
out_point.x =
in_point.x * (cp * cy) +
in_point.y * (cy * sp * sr - sy * cr) +
in_point.z * (-cy * sp * cr - sy * sr);
out_point.y =
in_point.x * (cp * sy) +
in_point.y * (sy * sp * sr + cy * cr) +
in_point.z * (-sy * sp * cr + cy * sr);
out_point.z =
in_point.x * (sp) +
in_point.y * (-cp * sr) +
in_point.z * (cp * cr);
Vector3D out_point = in_point;
RotateVector(out_point);
return out_point;
}

View File

@ -65,6 +65,7 @@ namespace geom {
std::ostream &operator<<(std::ostream &out, const BoundingBox &box) {
out << "BoundingBox(" << box.location << ", ";
WriteVector3D(out, "Extent", box.extent);
out << ", " << box.rotation;
out << ')';
return out;
}

View File

@ -61,7 +61,6 @@ static void WritePixelsToBuffer_Vulkan(
FTexture2DRHIRef Texture = RenderResource->GetRenderTargetTexture();
if (!Texture)
{
UE_LOG(LogCarla, Error, TEXT("FPixelReader: UTextureRenderTarget2D missing render target texture"));
return;
}

View File

@ -156,8 +156,14 @@ FBoundingBox UBoundingBoxCalculator::GetCharacterBoundingBox(
{
check(Character);
crp::CityObjectLabel TagQueried = (crp::CityObjectLabel)InTagQueried;
bool FilterByTag = TagQueried == crp::CityObjectLabel::None ||
TagQueried == crp::CityObjectLabel::Pedestrians;
UCapsuleComponent* Capsule = Character->GetCapsuleComponent();
if (Capsule)
if (Capsule && FilterByTag)
{
const float Radius = Capsule->GetScaledCapsuleRadius();
const float HalfHeight = Capsule->GetScaledCapsuleHalfHeight();
@ -318,12 +324,15 @@ void UBoundingBoxCalculator::GetISMBoundingBox(
return;
}
const TArray<FInstancedStaticMeshInstanceData>& PerInstanceSMData = ISMComp->PerInstanceSMData;
const TArray<FInstancedStaticMeshInstanceData>& PerInstanceSMData = ISMComp->PerInstanceSMData;
const FTransform ParentTransform = ISMComp->GetComponentTransform();
for(auto& InstSMIData : PerInstanceSMData)
{
const FTransform Transform = FTransform(InstSMIData.Transform);
const FTransform Transform = FTransform(InstSMIData.Transform) * ParentTransform;
FBoundingBox BoundingBox = ApplyTransformToBB(SMBoundingBox, Transform);
OutBoundingBox.Add(BoundingBox);
}
@ -339,6 +348,10 @@ void UBoundingBoxCalculator::GetBBsOfStaticMeshComponents(
for(UStaticMeshComponent* Comp : StaticMeshComps)
{
// Avoid duplication with SMComp and not visible meshes
if(!Comp->IsVisible() || Cast<UInstancedStaticMeshComponent>(Comp)) continue;
// Filter by tag
crp::CityObjectLabel Tag = ATagger::GetTagOfTaggedComponent(*Comp);
if(FilterByTagEnabled && Tag != TagQueried) continue;
@ -372,7 +385,8 @@ void UBoundingBoxCalculator::GetBBsOfSkeletalMeshComponents(
{
// Filter by tag
crp::CityObjectLabel Tag = ATagger::GetTagOfTaggedComponent(*Comp);
if(FilterByTagEnabled && Tag != TagQueried) continue;
if(!Comp->IsVisible() || (FilterByTagEnabled && Tag != TagQueried)) continue;
USkeletalMesh* SkeletalMesh = Comp->SkeletalMesh;
FBoundingBox BoundingBox = GetSkeletalMeshBoundingBox(SkeletalMesh);
@ -406,7 +420,7 @@ TArray<FBoundingBox> UBoundingBoxCalculator::GetBoundingBoxOfActors(
// When improved the BP_Procedural_Building this maybe should be removed
// Note: We don't use casting here because the base class is a BP and is easier to do it this way,
// than getting the UClass of the BP to cast the actor.
if(ClassName.Contains("BP_Procedural_Bulding")) continue;
if( ClassName.Contains("Procedural_Bulding") ) continue;
// The vehicle's BP has a low-polystatic mesh for collisions, we should avoid it
ACarlaWheeledVehicle* Vehicle = Cast<ACarlaWheeledVehicle>(Actor);
@ -441,16 +455,6 @@ TArray<FBoundingBox> UBoundingBoxCalculator::GetBoundingBoxOfActors(
continue;
}
// Calculate FBoundingBox of SM
TArray<UStaticMeshComponent*> StaticMeshComps;
Actor->GetComponents<UStaticMeshComponent>(StaticMeshComps);
GetBBsOfStaticMeshComponents(StaticMeshComps, Result, InTagQueried);
// Calculate FBoundingBox of SK_M
TArray<USkeletalMeshComponent*> SkeletalMeshComps;
Actor->GetComponents<USkeletalMeshComponent>(SkeletalMeshComps);
GetBBsOfSkeletalMeshComponents(SkeletalMeshComps, Result, InTagQueried);
// Calculate FBoundingBox of ISM
TArray<UInstancedStaticMeshComponent *> ISMComps;
Actor->GetComponents<UInstancedStaticMeshComponent>(ISMComps);
@ -463,6 +467,16 @@ TArray<FBoundingBox> UBoundingBoxCalculator::GetBoundingBoxOfActors(
GetISMBoundingBox(Comp, Result);
}
// Calculate FBoundingBox of SM
TArray<UStaticMeshComponent*> StaticMeshComps;
Actor->GetComponents<UStaticMeshComponent>(StaticMeshComps);
GetBBsOfStaticMeshComponents(StaticMeshComps, Result, InTagQueried);
// Calculate FBoundingBox of SK_M
TArray<USkeletalMeshComponent*> SkeletalMeshComps;
Actor->GetComponents<USkeletalMeshComponent>(SkeletalMeshComps);
GetBBsOfSkeletalMeshComponents(SkeletalMeshComps, Result, InTagQueried);
}
return Result;

View File

@ -182,7 +182,16 @@ private:
uint8 DepthPriority = SDPG_World;
// Debug lines are way more dark in the package, that's why this
// multiplier is needed.
#if UE_BUILD_SHIPPING
static constexpr double BrightMultiplier = 1000.0;
#else
// @TODO: Use UKismetSystemLibrary::IsStandalone to support colors
// in Editor's standalone mode.
static constexpr double BrightMultiplier = 1.0;
#endif
};
void FDebugShapeDrawer::Draw(const carla::rpc::DebugShape &Shape)