Luis/fix package (#5794)
* fixed not finding skeletal blueprints in shipping builds * Physics fixed. - Removed re-aplying forces all the time. - Removed collisions with the static meshes. * Added parameter to modify torque and forces for nested bones. * Forgot to add file. * removed old unused code * fix windows compilation * collisions now are applied from the closest point. added debug bools to enable more collisions and draw collision points. * Removed old code. * Fixed bug with distance less than zero. * Try to stabilize a bit * CHanged repulsion forces so that contacts end with equilibrium * Now all foliages are spawned correctly. - SpringBasedVegetationComponent: Added the posibility to set bones as static. This static bones will use the OnCollisionEvent instead overlap events. - VegetationManager: Removed unnecessary variables. - VegetationManager: Now the FTileData supports multiple level loads for the same tile. - VegetationManager: Refactor the code. * Remove unnecessary logs * Resolve Conflict * Removed Freeing CacheData * Removing 'can rest' feature Co-authored-by: bernatx <bernatx@gmail.com> Co-authored-by: Axel <axellopez92@outlook.com>
This commit is contained in:
parent
0d9b05b73b
commit
89ba3f0397
|
@ -184,7 +184,7 @@ public:
|
|||
TileID GetTileID(FDVector TileLocation) const;
|
||||
|
||||
TileID GetTileID(FIntVector TileVectorID) const;
|
||||
|
||||
public:
|
||||
FCarlaMapTile& GetCarlaMapTile(FVector Location);
|
||||
|
||||
FCarlaMapTile& GetCarlaMapTile(ULevel* InLevel);
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "Math/Matrix.h"
|
||||
#include "Components/CapsuleComponent.h"
|
||||
#include "DrawDebugHelpers.h"
|
||||
#include "Kismet/KismetMathLibrary.h"
|
||||
#include <unordered_set>
|
||||
#include <vector>
|
||||
#include "carla/rpc/String.h"
|
||||
|
@ -48,24 +49,6 @@
|
|||
#define OTHER_LOG(...)
|
||||
#endif
|
||||
|
||||
static float ClampToPositiveDegrees(float d)
|
||||
{
|
||||
if (d < 0.0f)
|
||||
{
|
||||
while (d < 0.0f)
|
||||
{
|
||||
d += 360.0f;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
while (d >= 360.0f)
|
||||
{
|
||||
d -= 360.0f;
|
||||
}
|
||||
}
|
||||
return d;
|
||||
}
|
||||
template <class T>
|
||||
static T GetSign(T n)
|
||||
{
|
||||
|
@ -208,7 +191,7 @@ void FSkeletonHierarchy::AddForce(const FString& BoneName, const FVector& Force)
|
|||
{
|
||||
if(Joint.JointName == BoneName)
|
||||
{
|
||||
Joint.ExternalForces += Force * 0.001f;
|
||||
Joint.ExternalForces += Force;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -374,28 +357,7 @@ void USpringBasedVegetationComponent::BeginPlay()
|
|||
void USpringBasedVegetationComponent::ResetComponent()
|
||||
{
|
||||
Skeleton.ClearExternalForces();
|
||||
// Get resting pose for bones
|
||||
auto *AnimInst = SkeletalMesh->GetAnimInstance();
|
||||
if (!AnimInst)
|
||||
{
|
||||
OTHER_LOG(Error, "Could not get animation instance.");
|
||||
return;
|
||||
}
|
||||
UWalkerAnim *WalkerAnim = Cast<UWalkerAnim>(AnimInst);
|
||||
if (!WalkerAnim)
|
||||
{
|
||||
OTHER_LOG(Error, "Could not get UWalkerAnim.");
|
||||
return;
|
||||
}
|
||||
|
||||
// get current pose
|
||||
FPoseSnapshot TempSnapshot;
|
||||
SkeletalMesh->SnapshotPose(TempSnapshot);
|
||||
|
||||
// copy pose
|
||||
WalkerAnim->Snap = TempSnapshot;
|
||||
|
||||
UpdateGlobalTransform();
|
||||
SkeletalMesh->ResetAllBodiesSimulatePhysics();
|
||||
}
|
||||
|
||||
void USpringBasedVegetationComponent::GenerateCollisionCapsules()
|
||||
|
@ -415,10 +377,20 @@ void USpringBasedVegetationComponent::GenerateCollisionCapsules()
|
|||
Capsule->SetRelativeTransform(CapsuleTransform);
|
||||
Capsule->SetCapsuleHalfHeight(Bone.Length*0.5f);
|
||||
Capsule->SetCapsuleRadius(6);
|
||||
Capsule->SetGenerateOverlapEvents(true);
|
||||
Capsule->SetCollisionProfileName("OverlapAll");
|
||||
Capsule->OnComponentBeginOverlap.AddDynamic(this, &USpringBasedVegetationComponent::OnBeginOverlapEvent);
|
||||
Capsule->OnComponentEndOverlap.AddDynamic(this, &USpringBasedVegetationComponent::OnEndOverlapEvent);
|
||||
if (Joint.bIsStatic)
|
||||
{
|
||||
Capsule->SetGenerateOverlapEvents(false);
|
||||
Capsule->SetCollisionProfileName("BlockAll");
|
||||
Capsule->OnComponentHit.AddDynamic(this, &USpringBasedVegetationComponent::OnCollisionEvent);
|
||||
}
|
||||
else
|
||||
{
|
||||
Capsule->SetGenerateOverlapEvents(true);
|
||||
Capsule->SetCollisionProfileName("OverlapAll");
|
||||
Capsule->OnComponentBeginOverlap.AddDynamic(this, &USpringBasedVegetationComponent::OnBeginOverlapEvent);
|
||||
Capsule->OnComponentEndOverlap.AddDynamic(this, &USpringBasedVegetationComponent::OnEndOverlapEvent);
|
||||
}
|
||||
|
||||
BoneCapsules.Add(Capsule);
|
||||
CapsuleToJointId.Add(Capsule, Joint.JointId);
|
||||
}
|
||||
|
@ -445,7 +417,6 @@ void USpringBasedVegetationComponent::ComputeSpringStrengthForBranches()
|
|||
|
||||
OTHER_LOG(Log, "Joint: %s, location %s, Strength %f", *Joint.JointName, *JointLocation.ToString(), Joint.SpringStrength);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void USpringBasedVegetationComponent::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||
|
@ -470,9 +441,7 @@ void USpringBasedVegetationComponent::ComputePerJointProperties(
|
|||
Properties.JointToGlobalMatrix = ToEigenMatrix(Joint.GlobalTransform);
|
||||
JointPropertiesList[Joint.JointId].JointToGlobalMatrix = Properties.JointToGlobalMatrix;
|
||||
if (!Joint.Bones.Num())
|
||||
{
|
||||
continue;
|
||||
}
|
||||
// COM and mass
|
||||
for (FSkeletonBone& Bone : Joint.Bones)
|
||||
{
|
||||
|
@ -491,9 +460,7 @@ void USpringBasedVegetationComponent::ComputePerJointProperties(
|
|||
for (FSkeletonBone& Bone : Joint.Bones)
|
||||
{
|
||||
if (Bone.Length < 1)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
float CylinderRadius = 0.1f;
|
||||
float CylinderHeight = Bone.Length/100.f;
|
||||
Eigen::Matrix3d LocalCylinderInertia;
|
||||
|
@ -505,9 +472,7 @@ void USpringBasedVegetationComponent::ComputePerJointProperties(
|
|||
Eigen::Vector3d LocalV1 = BoneVector.normalized();
|
||||
Eigen::Vector3d LocalV2 = LocalV1.cross(Eigen::Vector3d(0,1,0));
|
||||
if (LocalV2.norm() == 0)
|
||||
{
|
||||
LocalV2 = LocalV1.cross(Eigen::Vector3d(0,0,1));
|
||||
}
|
||||
LocalV2.normalize();
|
||||
Eigen::Vector3d LocalV3 = LocalV1.cross(LocalV2);
|
||||
Eigen::Matrix3d LocalToJointMatrix;
|
||||
|
@ -520,6 +485,7 @@ void USpringBasedVegetationComponent::ComputePerJointProperties(
|
|||
ACC_LOG(Log, "Local Joint: %s \n Inertia \n %s \n Force \n %s \n Torque \n %s \n COM: \n %s \n Mass %f", *Joint.JointName, *EigenToFString(Properties.InertiaTensor), *EigenToFString(Properties.Force), *EigenToFString(Properties.Torque), *EigenToFString(Properties.CenterOfMass), Properties.Mass);
|
||||
}
|
||||
}
|
||||
|
||||
// Compute accumulated properties (Center of Mass, Inertia, Forces and Torque)
|
||||
void USpringBasedVegetationComponent::ComputeCompositeBodyContribution(
|
||||
std::vector<FJointProperties>& JointLocalPropertiesList,
|
||||
|
@ -637,75 +603,115 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions(
|
|||
std::vector<FJointProperties>& JointPropertiesList)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(USpringBasedVegetationComponent::ResolveContactsAndCollisions);
|
||||
float MinDistance = INFINITY;
|
||||
FVector ClosestSurfacePoint;
|
||||
for (auto& ActorCapsules : OverlappingActors)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(ActorLoop);
|
||||
AActor* CollidingActor = ActorCapsules.Key;
|
||||
UPrimitiveComponent* Primitive = Cast<UPrimitiveComponent>(CollidingActor->GetRootComponent());
|
||||
if (!Primitive)
|
||||
{
|
||||
if (!IsValid(CollidingActor))
|
||||
continue;
|
||||
UPrimitiveComponent* Primitive = Cast<UPrimitiveComponent>(CollidingActor->GetRootComponent());
|
||||
if (!IsValid(Primitive))
|
||||
continue;
|
||||
}
|
||||
// force transferring momentum (for the initial collision frame)
|
||||
FVector PrimitiveVelocity = Primitive->GetComponentVelocity();
|
||||
Eigen::Vector3d ColliderVelocity = ToEigenVector(PrimitiveVelocity)/100.f;
|
||||
FVector Impulse = (Primitive->GetMass() * PrimitiveVelocity);
|
||||
Eigen::Vector3d CollisionImpulse = ToEigenVector(Impulse)/100.f;
|
||||
const FVector PrimitiveVelocity = Primitive->GetComponentVelocity();
|
||||
const Eigen::Vector3d ColliderVelocity = ToEigenVector(PrimitiveVelocity) / 100.f;
|
||||
const FVector Impulse = (Primitive->GetMass() * PrimitiveVelocity);
|
||||
const Eigen::Vector3d CollisionImpulse = 0*ToEigenVector(Impulse) / 100.f;
|
||||
TArray<UPrimitiveComponent*>& CollidingCapsules = ActorCapsules.Value;
|
||||
for (UPrimitiveComponent* Capsule : CollidingCapsules)
|
||||
{
|
||||
FVector auxVector;
|
||||
float distance = Primitive->GetClosestPointOnCollision(Capsule->GetComponentLocation(), auxVector);
|
||||
float DistanceToRoot = 0.0f;
|
||||
if (distance < MinDistance)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(CapsuleLoop);
|
||||
if (!IsValid(Capsule))
|
||||
continue;
|
||||
const FVector CapsuleLocation = Capsule->GetComponentLocation();
|
||||
const FVector PrimitiveLocation = Primitive->GetComponentLocation();
|
||||
static constexpr float MIN_DISTANCE = 1.0f;
|
||||
FVector ClosestPointOnCapsule;
|
||||
float DistanceOnCapsule;
|
||||
FHitResult HitResult;
|
||||
bool HitFound;
|
||||
FVector ClosestPointOnCollider;
|
||||
float DistanceToCollider;
|
||||
{
|
||||
MinDistance = distance;
|
||||
ClosestSurfacePoint = auxVector;
|
||||
const FVector RootLocation = Skeleton.Joints[0].GlobalTransform.GetLocation();
|
||||
DistanceToRoot = FMath::Sqrt(std::pow(auxVector.X - RootLocation.X, 2) + std::pow(auxVector.Y - RootLocation.Y, 2) + std::pow(auxVector.Z - RootLocation.Z, 2));
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(ColliderPenetrationDistance);
|
||||
DistanceOnCapsule = Capsule->GetClosestPointOnCollision(PrimitiveLocation, ClosestPointOnCapsule);
|
||||
FVector LineDirection = (ClosestPointOnCapsule - PrimitiveLocation).GetSafeNormal();
|
||||
FVector LineTraceStart = ClosestPointOnCapsule + LineTraceMaxDistance*LineDirection;
|
||||
FVector LineTraceEnd = ClosestPointOnCapsule;
|
||||
HitFound = Primitive->LineTraceComponent(HitResult,
|
||||
LineTraceStart, LineTraceEnd, FCollisionQueryParams());
|
||||
ClosestPointOnCollider = HitResult.Location;
|
||||
DistanceToCollider = (ClosestPointOnCollider - ClosestPointOnCapsule).Size();
|
||||
}
|
||||
if(!HitFound)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
|
||||
int JointId = CapsuleToJointId[Capsule];
|
||||
FSkeletonJoint& Joint = Skeleton.Joints[JointId];
|
||||
FJointProperties& JointProperties = JointLocalPropertiesList[Joint.JointId];
|
||||
Eigen::Vector3d JointGlobalPosition = ToEigenVector(Joint.GlobalTransform.GetLocation())/100.f;
|
||||
Eigen::Vector3d CapsulePosition = ToEigenVector(Capsule->GetComponentLocation())/100.f;
|
||||
Eigen::Vector3d ColliderPosition = ToEigenVector(Primitive->GetComponentLocation())/100.f;
|
||||
Eigen::Vector3d CollisionTorque = Eigen::Vector3d::Zero();
|
||||
|
||||
const float SpringStrength = Joint.SpringStrength;
|
||||
if (DebugEnableVisualization)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(DebugEnableVisualization);
|
||||
DrawDebugLine(GetWorld(), ClosestPointOnCapsule, ClosestPointOnCollider, FColor::Green, false, 0.1f, 0.0f, 1.f);
|
||||
static constexpr float DEBUG_SPHERE_SIZE = 5.0f;
|
||||
DrawDebugSphere(GetWorld(), ClosestPointOnCapsule, DEBUG_SPHERE_SIZE, 64, FColor(255, 0, 255, 255));
|
||||
DrawDebugSphere(GetWorld(), ClosestPointOnCollider, DEBUG_SPHERE_SIZE, 64, FColor(255, 0, 255, 255));
|
||||
DrawDebugSphere(GetWorld(), CapsuleLocation, DEBUG_SPHERE_SIZE, 64, FColor(255, 255, 255, 255));
|
||||
DrawDebugSphere(GetWorld(), PrimitiveLocation, DEBUG_SPHERE_SIZE, 64, FColor(0, 0, 0, 255));
|
||||
}
|
||||
|
||||
const int JointId = CapsuleToJointId[Capsule];
|
||||
const FSkeletonJoint& Joint = Skeleton.Joints[JointId];
|
||||
FJointProperties& JointProperties = JointLocalPropertiesList[Joint.JointId];
|
||||
const Eigen::Vector3d JointGlobalPosition = ToEigenVector(Joint.GlobalTransform.GetLocation()) / 100.f;
|
||||
const Eigen::Vector3d CapsulePosition = ToEigenVector(CapsuleLocation) / 100.f;
|
||||
const Eigen::Vector3d PointOnCapsulePosition = ToEigenVector(ClosestPointOnCapsule) / 100.f;
|
||||
const Eigen::Vector3d ColliderPosition = ToEigenVector(ClosestPointOnCollider) / 100.f;
|
||||
Eigen::Vector3d CollisionTorque = Eigen::Vector3d::Zero();
|
||||
|
||||
// Contact forces due to spring strength
|
||||
FRotator CurrRotator = Joint.Transform.Rotator();
|
||||
FRotator RestRotator = Joint.RestingAngles;
|
||||
FRotator DeltaRotator (
|
||||
const FRotator CurrRotator = Joint.Transform.Rotator();
|
||||
const FRotator RestRotator = Joint.RestingAngles;
|
||||
const FRotator DeltaRotator (
|
||||
CurrRotator.Pitch - RestRotator.Pitch,
|
||||
CurrRotator.Yaw - RestRotator.Yaw,
|
||||
CurrRotator.Roll - RestRotator.Roll);
|
||||
const Eigen::Vector3d SpringTorque = SpringStrength*RotatorToEigenVector(DeltaRotator);
|
||||
const Eigen::Vector3d SpringTorque = Joint.SpringStrength * RotatorToEigenVector(DeltaRotator);
|
||||
const Eigen::Vector3d JointCapsuleVector = JointGlobalPosition - CapsulePosition;
|
||||
const Eigen::Vector3d SpringForce = SpringTorque.cross(JointCapsuleVector)*JointCapsuleVector.squaredNorm();
|
||||
const Eigen::Vector3d RepulsionForce = SpringForce;
|
||||
|
||||
Primitive->AddForceAtLocation(-ToUnrealVector(RepulsionForce)*100.f, Capsule->GetComponentLocation());
|
||||
|
||||
const Eigen::Vector3d RepulsionForce = SpringTorque.cross(JointCapsuleVector) * JointCapsuleVector.squaredNorm();
|
||||
|
||||
FVector RepulsionForceUE = -ToUnrealVector(RepulsionForce) * 100.f;
|
||||
Primitive->AddForceAtLocation(RepulsionForceUE, CapsuleLocation);
|
||||
|
||||
// force to repel geometry overlapping
|
||||
Eigen::Vector3d OverlappingForces = (CapsulePosition - ColliderPosition).normalized()*CollisionForceParameter;
|
||||
Primitive->AddForceAtLocation(-ToUnrealVector(OverlappingForces)*100.f, Capsule->GetComponentLocation());
|
||||
CollisionTorque += (JointProperties.CenterOfMass - JointGlobalPosition).cross(RepulsionForce + CollisionImpulse + OverlappingForces);
|
||||
float ForceFactor = 1.f;
|
||||
// from eq f = 1 - a*d^p, f: ForceFactor, a: ProportionalConstant, p: ForceDistanceFalloffExponent, d: DistanceOnCapsule
|
||||
// float ProportionalConstant = 1.f/(FMath::Pow(ForceMaxDistance, ForceDistanceFalloffExponent));
|
||||
// ForceFactor = 1.f - ProportionalConstant * FMath::Pow(DistanceOnCapsule, ForceDistanceFalloffExponent);
|
||||
// from eq f = a*d^p, f: ForceFactor, a: ProportionalConstant, p: ForceDistanceFalloffExponent, d: DistanceToCollider
|
||||
float ProportionalConstant = 1.f/(FMath::Pow(ForceMaxDistance, ForceDistanceFalloffExponent));
|
||||
ForceFactor = ProportionalConstant * FMath::Pow(DistanceToCollider, ForceDistanceFalloffExponent);
|
||||
ForceFactor = FMath::Clamp(ForceFactor, MinForceFactor, 1.f);
|
||||
// const Eigen::Vector3d OverlappingForces = (ColliderPosition - CapsulePosition).normalized() * CollisionForceParameter * ForceFactor;
|
||||
const Eigen::Vector3d OverlappingForces = (ColliderPosition - PointOnCapsulePosition).normalized() * CollisionForceParameter * ForceFactor;
|
||||
Primitive->AddForceAtLocation(-ToUnrealVector(OverlappingForces) * 100.f, ClosestPointOnCollider);
|
||||
CollisionTorque += (JointProperties.CenterOfMass - JointGlobalPosition).cross(CollisionImpulse + OverlappingForces);
|
||||
JointProperties.Torque += CollisionTorque;
|
||||
// COLLISION_LOG(Log, "Joint: %s \n ProjectedSpeed %f, ProportionalFactor %f \n RepulsionForce %s \n", *Joint.JointName,ProjectedSpeed,ProportionalFactor,*EigenToFString(RepulsionForce),*EigenToFString(CollisionTorque));
|
||||
UE_LOG(LogCarla, Display, TEXT("DistanceToCollider: %f, ForceFactor: %f"), DistanceToCollider, ForceFactor);
|
||||
|
||||
if (DebugEnableVisualization)
|
||||
{
|
||||
// drawing
|
||||
const FVector Start = Capsule->GetComponentLocation();
|
||||
const FVector End = Primitive->GetComponentLocation();
|
||||
const FColor LineColor(FColor::Green);
|
||||
DrawDebugLine(GetWorld(), Start, End, LineColor, false, 0.1f, 0.0f, 1.f);
|
||||
DrawDebugLine(GetWorld(), CapsuleLocation, CapsuleLocation+RepulsionForceUE.GetSafeNormal()*5.f, FColor::Red, false, 0.1f, 0.0f, 1.f);
|
||||
}
|
||||
}
|
||||
}
|
||||
if (MinDistance != INFINITY)
|
||||
{
|
||||
|
||||
//DrawDebugPoint(GetWorld(), ClosestSurfacePoint, 5, FColor(255,0,0), false, 100.f);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void USpringBasedVegetationComponent::SolveEquationOfMotion(
|
||||
std::vector<FJointProperties>& JointPropertiesList,
|
||||
float DeltaTime)
|
||||
|
@ -719,6 +725,16 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
|
|||
continue;
|
||||
}
|
||||
FJointProperties& JointProperties = JointPropertiesList[Joint.JointId];
|
||||
|
||||
// drawing
|
||||
if (Joint.ParentId != -1 && DebugEnableVisualization)
|
||||
{
|
||||
const FVector Start = Joint.GlobalTransform.GetLocation();
|
||||
const FVector End = Skeleton.Joints[Joint.ParentId].GlobalTransform.GetLocation();
|
||||
const FColor LineColor(FColor::Blue);
|
||||
DrawDebugLine(GetWorld(), Start, End, LineColor, false, 0.1f, 0.0f, 1.f);
|
||||
}
|
||||
|
||||
float Mass = JointProperties.Mass;
|
||||
Eigen::Vector3d CenterToJoint = JointProperties.CenterOfMass - ToEigenVector(Joint.GlobalTransform.GetLocation())/100.f;
|
||||
Eigen::Matrix3d GlobalToJointMatrix = JointProperties.JointToGlobalMatrix.transpose();
|
||||
|
@ -729,6 +745,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
|
|||
Eigen::Matrix3d I = JointSpaceIntertiaTensor;
|
||||
float SpringStrength = Joint.SpringStrength;
|
||||
float beta = Beta;
|
||||
float alpha = Alpha;
|
||||
Eigen::Matrix3d K;
|
||||
K << SpringStrength,0.f,0.f,
|
||||
0.f,SpringStrength,0.f,
|
||||
|
@ -743,7 +760,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
|
|||
Eigen::Matrix3d U = Linv.transpose()*X;
|
||||
// Eigen::Matrix3d Uinv = U.inverse();
|
||||
Eigen::Matrix3d Uinv = X.transpose()*L.transpose();
|
||||
Eigen::Vector3d Coeffsb = beta*Lambda*Eigen::Vector3d(1,1,1);
|
||||
Eigen::Vector3d Coeffsb = Eigen::Vector3d(alpha,alpha,alpha) + beta*Lambda*Eigen::Vector3d(1,1,1);
|
||||
Eigen::Vector3d Coeffsk = Lambda*Eigen::Vector3d(1,1,1);
|
||||
Eigen::Vector3d Coeffsf = U.transpose()*Torque;
|
||||
FString StringI = EigenToFString(I);
|
||||
|
@ -846,30 +863,6 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
|
|||
FRotator NewAngularVelocity = EigenVectorToRotator(FinalNewThetaVelocity);
|
||||
FRotator NewAngularAccel = EigenVectorToRotator(FinalNewThetaAccel);
|
||||
|
||||
const float ClampedNewPitch = ClampToPositiveDegrees(NewPitch);
|
||||
const float ClampedNewYaw = ClampToPositiveDegrees(MaxYaw);
|
||||
const float ClampedNewRoll = ClampToPositiveDegrees(MaxRoll);
|
||||
|
||||
if (ClampedNewPitch > MaxPitch){
|
||||
NewPitch = ClampedNewPitch;
|
||||
|
||||
NewAngularVelocity.Pitch = 0.0f;
|
||||
NewAngularAccel.Pitch = 0.0f;
|
||||
}
|
||||
|
||||
if (ClampedNewYaw > MaxYaw){
|
||||
NewYaw = ClampedNewYaw;
|
||||
|
||||
NewAngularVelocity.Yaw = 0.0f;
|
||||
NewAngularAccel.Yaw = 0.0f;
|
||||
}
|
||||
|
||||
if (ClampedNewRoll > MaxRoll){
|
||||
NewRoll = ClampedNewRoll;
|
||||
NewAngularVelocity.Roll = 0.0f;
|
||||
NewAngularAccel.Roll = 0.0f;
|
||||
}
|
||||
|
||||
FRotator NewAngle(
|
||||
RestRotator.Pitch + NewPitch,
|
||||
RestRotator.Yaw - NewYaw,
|
||||
|
@ -894,9 +887,8 @@ void USpringBasedVegetationComponent::TickComponent(
|
|||
|
||||
float DeltaTimeFinal = DeltaTime;
|
||||
if (DeltaTimeOverride > 0)
|
||||
{
|
||||
DeltaTimeFinal = DeltaTimeOverride;
|
||||
}
|
||||
|
||||
std::vector<FJointProperties> JointPropertiesList;
|
||||
JointPropertiesList.resize(Skeleton.Joints.Num());
|
||||
std::vector<FJointProperties> JointLocalPropertiesList;
|
||||
|
@ -924,7 +916,25 @@ void USpringBasedVegetationComponent::OnCollisionEvent(
|
|||
FVector NormalImpulse,
|
||||
const FHitResult& Hit)
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Collision with bone %s, with impulse %s"), *Hit.MyBoneName.ToString(), *NormalImpulse.ToString());
|
||||
// prevent self collision
|
||||
if (OtherActor == GetOwner())
|
||||
return;
|
||||
// prevent collision with other tree actors
|
||||
if(OtherActor->GetComponentByClass(USpringBasedVegetationComponent::StaticClass()) != nullptr)
|
||||
return;
|
||||
ACarlaWheeledVehicle* Vehicle = nullptr;
|
||||
if (DebugEnableAllCollisions)
|
||||
{
|
||||
if (!IsValid(OtherActor))
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
Vehicle = Cast<ACarlaWheeledVehicle>(OtherActor);
|
||||
if (!IsValid(Vehicle))
|
||||
return;
|
||||
}
|
||||
COLLISION_LOG(LogCarla, Log, TEXT("Collision with bone %s, with impulse %s"), *Hit.MyBoneName.ToString(), *NormalImpulse.ToString());
|
||||
Skeleton.AddForce(Hit.MyBoneName.ToString(), NormalImpulse);
|
||||
}
|
||||
|
||||
|
@ -937,18 +947,33 @@ void USpringBasedVegetationComponent::OnBeginOverlapEvent(
|
|||
const FHitResult& SweepResult)
|
||||
{
|
||||
// prevent self collision
|
||||
if(OtherActor == GetOwner())
|
||||
{
|
||||
if (OtherActor == GetOwner())
|
||||
return;
|
||||
}
|
||||
// prevent collision with other tree actors
|
||||
if(OtherActor->GetComponentByClass(USpringBasedVegetationComponent::StaticClass()) != nullptr)
|
||||
{
|
||||
return;
|
||||
ACarlaWheeledVehicle* Vehicle = nullptr;
|
||||
if (DebugEnableAllCollisions)
|
||||
{
|
||||
if (!IsValid(OtherActor))
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
Vehicle = Cast<ACarlaWheeledVehicle>(OtherActor);
|
||||
if (!IsValid(Vehicle))
|
||||
return;
|
||||
}
|
||||
|
||||
if (!OverlappingActors.Contains(OtherActor))
|
||||
{
|
||||
OverlappingActors.Add(OtherActor);
|
||||
}
|
||||
// OverlappingActors.Add(OtherActor);
|
||||
TArray<UPrimitiveComponent*>& OverlappingCapsules = OverlappingActors.FindOrAdd(OtherActor);
|
||||
OverlappingCapsules.Add(OverlapComponent);
|
||||
if (!OverlappingCapsules.Contains(OverlapComponent))
|
||||
{
|
||||
OverlappingCapsules.Add(OverlapComponent);
|
||||
}
|
||||
}
|
||||
|
||||
void USpringBasedVegetationComponent::OnEndOverlapEvent(
|
||||
|
@ -957,19 +982,35 @@ void USpringBasedVegetationComponent::OnEndOverlapEvent(
|
|||
UPrimitiveComponent* OtherComponent,
|
||||
int32 OtherBodyIndex)
|
||||
{
|
||||
if(OtherActor == GetOwner())
|
||||
{
|
||||
// prevent self collision
|
||||
if (OtherActor == GetOwner())
|
||||
return;
|
||||
}
|
||||
// prevent collision with other tree actors
|
||||
if(OtherActor->GetComponentByClass(USpringBasedVegetationComponent::StaticClass()) != nullptr)
|
||||
{
|
||||
return;
|
||||
}
|
||||
TArray<UPrimitiveComponent*>& OverlappingCapsules = OverlappingActors.FindOrAdd(OtherActor);
|
||||
OverlappingCapsules.RemoveSingle(OverlapComponent);
|
||||
if (OverlappingCapsules.Num() == 0)
|
||||
ACarlaWheeledVehicle* Vehicle = nullptr;
|
||||
if (DebugEnableAllCollisions)
|
||||
{
|
||||
OverlappingActors.Remove(OtherActor);
|
||||
if (!IsValid(OtherActor))
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
Vehicle = Cast<ACarlaWheeledVehicle>(OtherActor);
|
||||
if (!IsValid(Vehicle))
|
||||
return;
|
||||
}
|
||||
|
||||
if (!OverlappingActors.Contains(OtherActor))
|
||||
return;
|
||||
TArray<UPrimitiveComponent*>& OverlappingCapsules = OverlappingActors.FindOrAdd(OtherActor);
|
||||
if (OverlappingCapsules.Contains(OverlapComponent))
|
||||
{
|
||||
OverlappingCapsules.RemoveSingle(OverlapComponent);
|
||||
if (OverlappingCapsules.Num() == 0)
|
||||
{
|
||||
OverlappingActors.Remove(OtherActor);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1023,8 +1064,5 @@ void USpringBasedVegetationComponent::UpdateGlobalTransform()
|
|||
FTransform Transform = Joint.Transform * ParentJoint.GlobalTransform;
|
||||
Joint.GlobalTransform = Transform;
|
||||
Joint.GolbalInverseTransform = Transform.Inverse();
|
||||
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -214,6 +214,9 @@ private:
|
|||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float Beta = 0.5f;
|
||||
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float Alpha = 0.f;
|
||||
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
FVector Gravity = FVector(0,0,-1);
|
||||
|
||||
|
@ -239,18 +242,23 @@ private:
|
|||
float CollisionForceMinVel = 1.f;
|
||||
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float ForceDistanceFalloffExponent = 1.f;
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float ForceMaxDistance = 180.f;
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float MinForceFactor = 0.01;
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float LineTraceMaxDistance = 180.f;
|
||||
public:
|
||||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Spring Based Vegetation Component")
|
||||
FSkeletonHierarchy Skeleton;
|
||||
|
||||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Spring Based Vegetation Component")
|
||||
bool DebugEnableVisualization { false };
|
||||
|
||||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Spring Based Vegetation Component")
|
||||
bool DebugEnableAllCollisions { false };
|
||||
private:
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
bool bAutoComputeStrength = true;
|
||||
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float MaxYaw = 0.0f;
|
||||
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float MaxPitch = 180.0f;
|
||||
|
||||
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
|
||||
float MaxRoll = 180.0f;
|
||||
};
|
||||
|
||||
|
|
|
@ -81,7 +81,9 @@ void FPooledActor::DisableActor()
|
|||
/********************************************************************************/
|
||||
bool FFoliageBlueprint::IsValid() const
|
||||
{
|
||||
return !BPFullClassName.IsEmpty() && SpawnedClass;
|
||||
if (BPFullClassName.IsEmpty() || !BPFullClassName.Contains("_C"))
|
||||
return false;
|
||||
return SpawnedClass != nullptr;
|
||||
}
|
||||
|
||||
bool FFoliageBlueprint::SetBPClassName(const FString& Path)
|
||||
|
@ -94,7 +96,7 @@ bool FFoliageBlueprint::SetBPClassName(const FString& Path)
|
|||
int Position = ParsedString.Num() - 1;
|
||||
const FString FullVersion = GetVersionFromFString(ParsedString[Position]);
|
||||
const FString Folder = ParsedString[--Position];
|
||||
BPClassName = "BP_" + Folder + FullVersion;
|
||||
const FString BPClassName = "BP_" + Folder + FullVersion;
|
||||
BPFullClassName = "Blueprint'";
|
||||
for (int i = 0; i <= Position; ++i)
|
||||
{
|
||||
|
@ -104,18 +106,17 @@ bool FFoliageBlueprint::SetBPClassName(const FString& Path)
|
|||
BPFullClassName += BPClassName;
|
||||
BPFullClassName += ".";
|
||||
BPFullClassName += BPClassName;
|
||||
BPFullClassName += "'";
|
||||
BPFullClassName += "_C'";
|
||||
return true;
|
||||
}
|
||||
|
||||
bool FFoliageBlueprint::SetSpawnedClass()
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(FoliageBlueprintCache::SetSpawnedClass);
|
||||
UObject* LoadedObject = StaticLoadObject(UObject::StaticClass(), nullptr, *BPFullClassName);
|
||||
UBlueprint* CastedBlueprint = Cast<UBlueprint>(LoadedObject);
|
||||
if (CastedBlueprint && CastedBlueprint->GeneratedClass->IsChildOf(AActor::StaticClass()))
|
||||
UClass* CastedBlueprint = LoadObject< UClass >(nullptr, *BPFullClassName);
|
||||
if (CastedBlueprint)
|
||||
{
|
||||
SpawnedClass = *CastedBlueprint->GeneratedClass;
|
||||
SpawnedClass = CastedBlueprint;
|
||||
return true;
|
||||
}
|
||||
SpawnedClass = nullptr;
|
||||
|
@ -125,12 +126,43 @@ bool FFoliageBlueprint::SetSpawnedClass()
|
|||
/********************************************************************************/
|
||||
/********** TILE DATA STRUCT ****************************************************/
|
||||
/********************************************************************************/
|
||||
void FTileData::UpdateMaterialCache(const FLinearColor& Value)
|
||||
void FTileData::UpdateTileMeshComponent(UInstancedStaticMeshComponent* NewInstancedStaticMeshComponent)
|
||||
{
|
||||
UInstancedStaticMeshComponent* Aux { nullptr };
|
||||
for (FTileMeshComponent& Element : TileMeshesCache)
|
||||
{
|
||||
if (Element.InstancedStaticMeshComponent == NewInstancedStaticMeshComponent)
|
||||
{
|
||||
int32 CurrentCount = Element.InstancedStaticMeshComponent->GetInstanceCount();
|
||||
int32 NewCount = NewInstancedStaticMeshComponent->GetInstanceCount();
|
||||
if (NewCount > CurrentCount)
|
||||
{
|
||||
Element.InstancedStaticMeshComponent = NewInstancedStaticMeshComponent;
|
||||
Element.IndicesInUse.Empty();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool FTileData::ContainsMesh(const UInstancedStaticMeshComponent* Mesh) const
|
||||
{
|
||||
for (const FTileMeshComponent& Element : TileMeshesCache)
|
||||
{
|
||||
if (Element.InstancedStaticMeshComponent == Mesh)
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void FTileData::UpdateMaterialCache(const FLinearColor& Value, bool DebugMaterials)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(FTileData::UpdateMaterialCache);
|
||||
for (UMaterialInstanceDynamic* Material : MaterialInstanceDynamicCache)
|
||||
{
|
||||
Material->SetScalarParameterValue("ActivateDebug", 0);
|
||||
if (DebugMaterials)
|
||||
Material->SetScalarParameterValue("ActivateDebug", 1);
|
||||
else
|
||||
Material->SetScalarParameterValue("ActivateDebug", 0);
|
||||
Material->SetScalarParameterValue("ActivateOpacity", 1);
|
||||
Material->SetVectorParameterValue("VehiclePosition", Value);
|
||||
}
|
||||
|
@ -143,6 +175,9 @@ void AVegetationManager::BeginPlay()
|
|||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::BeginPlay);
|
||||
Super::BeginPlay();
|
||||
LargeMap = UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
FWorldDelegates::LevelAddedToWorld.AddUObject(this, &AVegetationManager::OnLevelAddedToWorld);
|
||||
FWorldDelegates::LevelRemovedFromWorld.AddUObject(this, &AVegetationManager::OnLevelRemovedFromWorld);
|
||||
}
|
||||
|
||||
void AVegetationManager::Tick(float DeltaTime)
|
||||
|
@ -151,21 +186,19 @@ void AVegetationManager::Tick(float DeltaTime)
|
|||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(Parent Tick);
|
||||
Super::Tick(DeltaTime);
|
||||
}
|
||||
}
|
||||
if (!LargeMap)
|
||||
return;
|
||||
bool FoundVehicles = CheckIfAnyVehicleInLevel();
|
||||
if (!FoundVehicles)
|
||||
return;
|
||||
|
||||
UpdateVehiclesDetectionBoxes();
|
||||
bool NewTilesFound = CheckForNewTiles();
|
||||
if (NewTilesFound)
|
||||
{
|
||||
UpdateFoliageBlueprintCache();
|
||||
UpdateTileDataCache();
|
||||
GenerateTileDataInternals();
|
||||
}
|
||||
|
||||
TArray<FString> TilesInUse = GetTilesInUse();
|
||||
if (TilesInUse.Num() == 0)
|
||||
return;
|
||||
|
||||
UpdateMaterials(TilesInUse);
|
||||
TArray<TPair<FFoliageBlueprint, TArray<FTransform>>> ElementsToSpawn = GetElementsToSpawn(TilesInUse);
|
||||
SpawnSkeletalFoliages(ElementsToSpawn);
|
||||
|
@ -200,61 +233,116 @@ void AVegetationManager::RemoveVehicle(ACarlaWheeledVehicle* Vehicle)
|
|||
/********************************************************************************/
|
||||
/********** CACHES **************************************************************/
|
||||
/********************************************************************************/
|
||||
void AVegetationManager::UpdateTileDataCache()
|
||||
void AVegetationManager::CreateOrUpdateTileCache(ULevel* InLevel)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::UpdateTileDataCache);
|
||||
const UObject* World = GetWorld();
|
||||
TArray<FString> NewKeys;
|
||||
TArray<AActor*> ActorsInLevel;
|
||||
UGameplayStatics::GetAllActorsOfClass(World, AInstancedFoliageActor::StaticClass(), ActorsInLevel);
|
||||
for (AActor* Actor : ActorsInLevel)
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::CreateOrUpdateTileCache);
|
||||
FTileData TileData {};
|
||||
for (AActor* Actor : InLevel->Actors)
|
||||
{
|
||||
AInstancedFoliageActor* InstancedFoliageActor = Cast<AInstancedFoliageActor>(Actor);
|
||||
if (!IsValid(InstancedFoliageActor))
|
||||
continue;
|
||||
TileData.InstancedFoliageActor = InstancedFoliageActor;
|
||||
break;
|
||||
}
|
||||
|
||||
for (AActor* Actor : InLevel->Actors)
|
||||
{
|
||||
AProceduralFoliageVolume* ProceduralFoliageVolume = Cast<AProceduralFoliageVolume>(Actor);
|
||||
if (!IsValid(ProceduralFoliageVolume))
|
||||
continue;
|
||||
TileData.ProceduralFoliageVolume = ProceduralFoliageVolume;
|
||||
break;
|
||||
}
|
||||
const FString TileName = TileData.InstancedFoliageActor->GetLevel()->GetOuter()->GetName();
|
||||
FTileData* ExistingTileData = TileCache.Find(TileName);
|
||||
if (ExistingTileData)
|
||||
{
|
||||
ExistingTileData->InstancedFoliageActor = TileData.InstancedFoliageActor;
|
||||
ExistingTileData->ProceduralFoliageVolume = TileData.ProceduralFoliageVolume;
|
||||
SetTileDataInternals(*ExistingTileData);
|
||||
}
|
||||
else
|
||||
{
|
||||
SetTileDataInternals(TileData);
|
||||
TileCache.Emplace(TileName, TileData);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void AVegetationManager::SetTileDataInternals(FTileData& TileData)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::SetTileDataInternals);
|
||||
SetInstancedStaticMeshComponentCache(TileData);
|
||||
SetMaterialCache(TileData);
|
||||
}
|
||||
|
||||
void AVegetationManager::SetInstancedStaticMeshComponentCache(FTileData& TileData)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::SetInstancedStaticMeshComponentCache);
|
||||
const TSet<UActorComponent*>& ActorComponents = TileData.InstancedFoliageActor->GetComponents();
|
||||
for (UActorComponent* Component : ActorComponents)
|
||||
{
|
||||
UInstancedStaticMeshComponent* Mesh = Cast<UInstancedStaticMeshComponent>(Component);
|
||||
if (!IsValid(Mesh))
|
||||
continue;
|
||||
const FString Path = Mesh->GetStaticMesh()->GetPathName();
|
||||
const FFoliageBlueprint* BPCache = FoliageBlueprintCache.Find(Path);
|
||||
if (!BPCache)
|
||||
continue;
|
||||
|
||||
if (TileData.ContainsMesh(Mesh))
|
||||
{
|
||||
TileData.UpdateTileMeshComponent(Mesh);
|
||||
}
|
||||
else
|
||||
{
|
||||
FTileMeshComponent Aux;
|
||||
Aux.InstancedStaticMeshComponent = Mesh;
|
||||
TileData.TileMeshesCache.Emplace(Aux);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AVegetationManager::SetMaterialCache(FTileData& TileData)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::SetMaterialCache);
|
||||
if (TileData.MaterialInstanceDynamicCache.Num() > 0)
|
||||
TileData.MaterialInstanceDynamicCache.Empty();
|
||||
|
||||
const float Distance = VehiclesInLevel.Last()->DetectionSize * 2.0f;
|
||||
for (FTileMeshComponent& Element : TileData.TileMeshesCache)
|
||||
{
|
||||
UInstancedStaticMeshComponent* Mesh = Element.InstancedStaticMeshComponent;
|
||||
int32 Index = -1;
|
||||
for (UMaterialInterface* Material : Mesh->GetMaterials())
|
||||
{
|
||||
++Index;
|
||||
if (!IsValid(Material))
|
||||
continue;
|
||||
UMaterialInstanceDynamic* MaterialInstanceDynamic = UMaterialInstanceDynamic::Create(Material, this);
|
||||
if (!MaterialInstanceDynamic)
|
||||
continue;
|
||||
if (TileData.MaterialInstanceDynamicCache.Contains(MaterialInstanceDynamic))
|
||||
continue;
|
||||
MaterialInstanceDynamic->SetScalarParameterValue("ActivateOpacity", 0);
|
||||
MaterialInstanceDynamic->SetScalarParameterValue("ActivateDebug", 0);
|
||||
MaterialInstanceDynamic->SetScalarParameterValue("Distance", Distance);
|
||||
Mesh->SetMaterial(Index, MaterialInstanceDynamic);
|
||||
TileData.MaterialInstanceDynamicCache.Emplace(MaterialInstanceDynamic);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AVegetationManager::UpdateFoliageBlueprintCache(ULevel* InLevel)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::UpdateFoliageBlueprintCache);
|
||||
for (AActor* Actor : InLevel->Actors)
|
||||
{
|
||||
AInstancedFoliageActor* InstancedFoliageActor = Cast<AInstancedFoliageActor>(Actor);
|
||||
if (!IsValid(InstancedFoliageActor))
|
||||
continue;
|
||||
const FString TileName = InstancedFoliageActor->GetLevel()->GetOuter()->GetName();
|
||||
if (TileDataCache.Contains(TileName))
|
||||
{
|
||||
UE_LOG(LogCarla, Warning, TEXT("Tile: %s is already in the cache."), *TileName);
|
||||
continue;
|
||||
}
|
||||
FTileData TileData {};
|
||||
TileData.InstancedFoliageActor = InstancedFoliageActor;
|
||||
TileDataCache.Emplace(TileName, TileData);
|
||||
NewKeys.Emplace(TileName);
|
||||
}
|
||||
|
||||
ActorsInLevel.Reset();
|
||||
UGameplayStatics::GetAllActorsOfClass(World, AProceduralFoliageVolume::StaticClass(), ActorsInLevel);
|
||||
for (AActor* Actor : ActorsInLevel)
|
||||
{
|
||||
AProceduralFoliageVolume* Procedural = Cast<AProceduralFoliageVolume>(Actor);
|
||||
if (!IsValid(Procedural))
|
||||
continue;
|
||||
const FString TileName = Procedural->GetLevel()->GetOuter()->GetName();
|
||||
if (NewKeys.Contains(TileName))
|
||||
{
|
||||
FTileData* TileData = TileDataCache.Find(TileName);
|
||||
if (TileData)
|
||||
{
|
||||
TileData->ProceduralFoliageVolume = Procedural;
|
||||
UE_LOG(LogCarla, Display, TEXT("Tile: %s added to the cache."), *TileName);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AVegetationManager::UpdateFoliageBlueprintCache()
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::UpdateFoliageBlueprintCache);
|
||||
const UObject* World = GetWorld();
|
||||
TArray<AActor*> ActorsInLevel;
|
||||
UGameplayStatics::GetAllActorsOfClass(World, AInstancedFoliageActor::StaticClass(), ActorsInLevel);
|
||||
for (AActor* Actor : ActorsInLevel)
|
||||
{
|
||||
AInstancedFoliageActor* InstancedFoliageActor = Cast<AInstancedFoliageActor>(Actor);
|
||||
if (!IsValid(InstancedFoliageActor))
|
||||
continue;
|
||||
const TSet<UActorComponent*>& ActorComponents = InstancedFoliageActor->GetComponents();
|
||||
for (UActorComponent* Component : ActorComponents)
|
||||
{
|
||||
|
@ -269,95 +357,48 @@ void AVegetationManager::UpdateFoliageBlueprintCache()
|
|||
FFoliageBlueprint NewFoliageBlueprint;
|
||||
NewFoliageBlueprint.SetBPClassName(Path);
|
||||
NewFoliageBlueprint.SetSpawnedClass();
|
||||
FoliageBlueprintCache.Emplace(Path, NewFoliageBlueprint);
|
||||
|
||||
if (!NewFoliageBlueprint.IsValid())
|
||||
{
|
||||
UE_LOG(LogCarla, Warning, TEXT("Blueprint %s was invalid."), *NewFoliageBlueprint.BPClassName);
|
||||
{
|
||||
UE_LOG(LogCarla, Error, TEXT("Blueprint %s was invalid."), *NewFoliageBlueprint.BPFullClassName);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Display, TEXT("Blueprint %s created."), *NewFoliageBlueprint.BPClassName);
|
||||
UE_LOG(LogCarla, Display, TEXT("Blueprint %s created."), *NewFoliageBlueprint.BPFullClassName);
|
||||
FoliageBlueprintCache.Emplace(Path, NewFoliageBlueprint);
|
||||
CreatePoolForBPClass(NewFoliageBlueprint);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AVegetationManager::GenerateTileDataInternals()
|
||||
void AVegetationManager::FreeTileCache(ULevel* InLevel)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::GenerateTileDataInternals);
|
||||
for (TPair<FString, FTileData>& Element : TileDataCache)
|
||||
FTileData TileData {};
|
||||
for (AActor* Actor : InLevel->Actors)
|
||||
{
|
||||
if (Element.Value.TileMeshesCache.Num() > 0)
|
||||
AInstancedFoliageActor* InstancedFoliageActor = Cast<AInstancedFoliageActor>(Actor);
|
||||
if (!IsValid(InstancedFoliageActor))
|
||||
continue;
|
||||
InitializeInstancedStaticMeshComponentCache(Element.Value);
|
||||
InitializeMaterialCache(Element.Value);
|
||||
TileData.InstancedFoliageActor = InstancedFoliageActor;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void AVegetationManager::InitializeInstancedStaticMeshComponentCache(FTileData& TileData)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::InitializeInstancedStaticMeshComponentCache);
|
||||
const TSet<UActorComponent*>& ActorComponents = TileData.InstancedFoliageActor->GetComponents();
|
||||
for (UActorComponent* Component : ActorComponents)
|
||||
if (TileData.InstancedFoliageActor == nullptr)
|
||||
return;
|
||||
const FString TileName = TileData.InstancedFoliageActor->GetLevel()->GetOuter()->GetName();
|
||||
FTileData* ExistingTileData = TileCache.Find(TileName);
|
||||
if (ExistingTileData)
|
||||
{
|
||||
UInstancedStaticMeshComponent* Mesh = Cast<UInstancedStaticMeshComponent>(Component);
|
||||
if (!IsValid(Mesh))
|
||||
continue;
|
||||
const FString Path = Mesh->GetStaticMesh()->GetPathName();
|
||||
const FFoliageBlueprint* BPCache = FoliageBlueprintCache.Find(Path);
|
||||
if (!BPCache)
|
||||
continue;
|
||||
if (!BPCache->IsValid())
|
||||
continue;
|
||||
bool Found = false;
|
||||
for (auto& Element : TileData.TileMeshesCache)
|
||||
ExistingTileData->MaterialInstanceDynamicCache.Empty();
|
||||
for (FTileMeshComponent& Element : ExistingTileData->TileMeshesCache)
|
||||
{
|
||||
if (Element.InstancedStaticMeshComponent == Mesh)
|
||||
{
|
||||
Found = true;
|
||||
break;
|
||||
}
|
||||
Element.IndicesInUse.Empty();
|
||||
}
|
||||
if (Found)
|
||||
continue;
|
||||
FTileMeshComponent Aux;
|
||||
Aux.InstancedStaticMeshComponent = Mesh;
|
||||
TileData.TileMeshesCache.Emplace(Aux);
|
||||
ExistingTileData->TileMeshesCache.Empty();
|
||||
TileCache.Remove(TileName);
|
||||
}
|
||||
}
|
||||
|
||||
void AVegetationManager::InitializeMaterialCache(FTileData& TileData)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::InitializeMaterialCache);
|
||||
const float Distance = VehiclesInLevel[0]->DetectionSize * 2.0f;
|
||||
for (FTileMeshComponent& Element : TileData.TileMeshesCache)
|
||||
{
|
||||
UInstancedStaticMeshComponent* Mesh = Element.InstancedStaticMeshComponent;
|
||||
UMaterialInterface* Material {nullptr};
|
||||
int32 Index {0};
|
||||
do
|
||||
{
|
||||
Material = Mesh->GetMaterial(Index);
|
||||
if (!Material)
|
||||
continue;
|
||||
UMaterialInstanceDynamic* MaterialInstanceDynamic = UMaterialInstanceDynamic::Create(Material, this);
|
||||
if (!MaterialInstanceDynamic)
|
||||
continue;
|
||||
if (TileData.MaterialInstanceDynamicCache.Contains(MaterialInstanceDynamic))
|
||||
continue;
|
||||
MaterialInstanceDynamic->SetScalarParameterValue("ActivateOpacity", 0);
|
||||
MaterialInstanceDynamic->SetScalarParameterValue("ActivateDebug", 0);
|
||||
MaterialInstanceDynamic->SetScalarParameterValue("Distance", Distance);
|
||||
Mesh->SetMaterial(Index, MaterialInstanceDynamic);
|
||||
TileData.MaterialInstanceDynamicCache.Emplace(MaterialInstanceDynamic);
|
||||
++Index;
|
||||
} while (Material);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/********************************************************************************/
|
||||
/********** TICK ****************************************************************/
|
||||
/********************************************************************************/
|
||||
|
@ -371,13 +412,13 @@ void AVegetationManager::UpdateVehiclesDetectionBoxes()
|
|||
void AVegetationManager::UpdateMaterials(TArray<FString>& Tiles)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::UpdateMaterials);
|
||||
FLinearColor Position = FLinearColor(VehiclesInLevel[0]->GetActorLocation());
|
||||
const FLinearColor Position = VehiclesInLevel.Last()->GetActorLocation();
|
||||
for (const FString& TileName : Tiles)
|
||||
{
|
||||
FTileData* TileData = TileDataCache.Find(TileName);
|
||||
FTileData* TileData = TileCache.Find(TileName);
|
||||
if (!TileData)
|
||||
continue;
|
||||
TileData->UpdateMaterialCache(Position);
|
||||
TileData->UpdateMaterialCache(Position, DebugMaterials);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -385,60 +426,40 @@ TArray<TPair<FFoliageBlueprint, TArray<FTransform>>> AVegetationManager::GetElem
|
|||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::GetElementsToSpawn);
|
||||
TArray<TPair<FFoliageBlueprint, TArray<FTransform>>> Results;
|
||||
ALargeMapManager* LargeMap =
|
||||
UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
check(LargeMap);
|
||||
for (const FString& TileKey : Tiles)
|
||||
{
|
||||
FTileData* Tile = TileDataCache.Find(TileKey);
|
||||
FTileData* Tile = TileCache.Find(TileKey);
|
||||
if (!Tile)
|
||||
continue;
|
||||
for (FTileMeshComponent& Element : Tile->TileMeshesCache)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(Update Foliage Usage);
|
||||
UInstancedStaticMeshComponent* InstancedStaticMeshComponent = Element.InstancedStaticMeshComponent;
|
||||
FString Path = InstancedStaticMeshComponent->GetStaticMesh()->GetPathName();
|
||||
const FString Path = InstancedStaticMeshComponent->GetStaticMesh()->GetPathName();
|
||||
FFoliageBlueprint* BP = FoliageBlueprintCache.Find(Path);
|
||||
if (!BP)
|
||||
continue;
|
||||
if (!BP->IsValid())
|
||||
continue;
|
||||
TArray<int32> Indices = VehiclesInLevel[0]->GetFoliageInstancesCloseToVehicle(InstancedStaticMeshComponent);
|
||||
TArray<int32> Indices = VehiclesInLevel.Last()->GetFoliageInstancesCloseToVehicle(InstancedStaticMeshComponent);
|
||||
if (Indices.Num() == 0)
|
||||
continue;
|
||||
for (int32 i = 0; i < Element.IndicesInUse.Num(); ++i)
|
||||
{
|
||||
if (Element.IndicesInUse[i] == -1)
|
||||
continue;
|
||||
if (Indices.Contains(Element.IndicesInUse[i]))
|
||||
continue;
|
||||
Element.IndicesInUse[i] = -1;
|
||||
}
|
||||
TPair<FFoliageBlueprint, TArray<FTransform>> NewElement {};
|
||||
NewElement.Key = *BP;
|
||||
TArray<FTransform> Transforms;
|
||||
|
||||
TArray<int32> NewIndices;
|
||||
for (int32 Index : Indices)
|
||||
{
|
||||
if (Element.IndicesInUse.Contains(Index))
|
||||
continue;
|
||||
NewIndices.Emplace(Index);
|
||||
}
|
||||
Element.IndicesInUse = Indices;
|
||||
TPair<FFoliageBlueprint, TArray<FTransform>> NewElement {};
|
||||
NewElement.Key = *BP;
|
||||
TArray<FTransform> Transforms;
|
||||
for (int32 Index : NewIndices)
|
||||
{
|
||||
FTransform Transform;
|
||||
InstancedStaticMeshComponent->GetInstanceTransform(Index, Transform, true);
|
||||
FTransform GlobalTransform = LargeMap->LocalToGlobalTransform(Transform);
|
||||
Transforms.Emplace(GlobalTransform);
|
||||
bool Found = false;
|
||||
//Add Index to Array
|
||||
for (int32 i = 0; i < Element.IndicesInUse.Num(); ++i)
|
||||
{
|
||||
if (Element.IndicesInUse[i] == -1)
|
||||
{
|
||||
Element.IndicesInUse[i] = Index;
|
||||
Found = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (!Found)
|
||||
Element.IndicesInUse.Emplace(Index);
|
||||
//----------------------------------------------------
|
||||
}
|
||||
if (Transforms.Num() > 0)
|
||||
{
|
||||
|
@ -453,23 +474,16 @@ TArray<TPair<FFoliageBlueprint, TArray<FTransform>>> AVegetationManager::GetElem
|
|||
void AVegetationManager::SpawnSkeletalFoliages(TArray<TPair<FFoliageBlueprint, TArray<FTransform>>>& ElementsToSpawn)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::SpawnSkeletalFoliages);
|
||||
ALargeMapManager* LargeMap =
|
||||
UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
check(LargeMap);
|
||||
for (TPair<FFoliageBlueprint, TArray<FTransform>>& Element : ElementsToSpawn)
|
||||
{
|
||||
FFoliageBlueprint BP = Element.Key;
|
||||
if (!BP.IsValid())
|
||||
continue;
|
||||
TArray<FPooledActor>* Pool = ActorPool.Find(BP.BPClassName);
|
||||
if (!Pool)
|
||||
continue;
|
||||
TArray<FPooledActor>* Pool = ActorPool.Find(BP.BPFullClassName);
|
||||
for (const FTransform& Transform : Element.Value)
|
||||
{
|
||||
bool Ok = EnableActorFromPool(Transform, *Pool);
|
||||
if (Ok)
|
||||
{
|
||||
UE_LOG(LogCarla, Display, TEXT("Pooled actor from pool: %s"), *BP.BPClassName);
|
||||
UE_LOG(LogCarla, Display, TEXT("Pooled actor: %s"), *BP.BPFullClassName);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -481,7 +495,7 @@ void AVegetationManager::SpawnSkeletalFoliages(TArray<TPair<FFoliageBlueprint, T
|
|||
{
|
||||
NewElement.EnableActor();
|
||||
Pool->Emplace(NewElement);
|
||||
UE_LOG(LogCarla, Display, TEXT("Created actor for pool: %s"), *BP.BPClassName);
|
||||
UE_LOG(LogCarla, Display, TEXT("Created actor: %s"), *BP.BPFullClassName);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -491,9 +505,6 @@ void AVegetationManager::SpawnSkeletalFoliages(TArray<TPair<FFoliageBlueprint, T
|
|||
void AVegetationManager::DestroySkeletalFoliages()
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::DestroySkeletalFoliages);
|
||||
ALargeMapManager* LargeMap =
|
||||
UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
check(LargeMap);
|
||||
for (TPair<FString, TArray<FPooledActor>>& Element : ActorPool)
|
||||
{
|
||||
TArray<FPooledActor>& Pool = Element.Value;
|
||||
|
@ -502,10 +513,10 @@ void AVegetationManager::DestroySkeletalFoliages()
|
|||
if (!Actor.InUse)
|
||||
continue;
|
||||
const FVector Location = Actor.GlobalTransform.GetLocation();
|
||||
if (!VehiclesInLevel[0]->IsInVehicleRange(Location))
|
||||
if (!VehiclesInLevel.Last()->IsInVehicleRange(Location))
|
||||
{
|
||||
Actor.DisableActor();
|
||||
UE_LOG(LogCarla, Display, TEXT("Disabled Actor from pool"));
|
||||
UE_LOG(LogCarla, Display, TEXT("Disabled Actor"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -513,15 +524,14 @@ void AVegetationManager::DestroySkeletalFoliages()
|
|||
|
||||
bool AVegetationManager::EnableActorFromPool(const FTransform& Transform, TArray<FPooledActor>& Pool)
|
||||
{
|
||||
ALargeMapManager* LargeMap =
|
||||
UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
check(LargeMap);
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::EnableActorFromPool);
|
||||
for (FPooledActor& PooledActor : Pool)
|
||||
{
|
||||
if (PooledActor.InUse)
|
||||
continue;
|
||||
PooledActor.GlobalTransform = Transform;
|
||||
FTransform LocalTransform = LargeMap->GlobalToLocalTransform(Transform);
|
||||
FTransform LocalTransform = Transform;
|
||||
LocalTransform = LargeMap->GlobalToLocalTransform(Transform);
|
||||
PooledActor.EnableActor();
|
||||
PooledActor.Actor->SetActorLocationAndRotation(LocalTransform.GetLocation(), LocalTransform.Rotator(), true, nullptr, ETeleportType::ResetPhysics);
|
||||
if (SpawnScale <= 1.01f && SpawnScale >= 0.99f)
|
||||
|
@ -547,34 +557,48 @@ void AVegetationManager::CreatePoolForBPClass(const FFoliageBlueprint& BP)
|
|||
NewElement.Actor = CreateFoliage(BP, Transform);
|
||||
if (IsValid(NewElement.Actor))
|
||||
{
|
||||
UE_LOG(LogCarla, Display, TEXT("Created actor for pool: %s"), *BP.BPClassName);
|
||||
UE_LOG(LogCarla, Display, TEXT("Created actor for pool"));
|
||||
NewElement.DisableActor();
|
||||
AuxPool.Emplace(NewElement);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Error, TEXT("Failed to create actor for pool: %s"), *BP.BPClassName);
|
||||
UE_LOG(LogCarla, Error, TEXT("Failed to create actor for pool"));
|
||||
}
|
||||
}
|
||||
ActorPool.Emplace(BP.BPClassName, AuxPool);
|
||||
ActorPool.Emplace(BP.BPFullClassName, AuxPool);
|
||||
UE_LOG(LogCarla, Display, TEXT("CreatePoolForBPClass: %s"), *BP.BPFullClassName);
|
||||
}
|
||||
|
||||
AActor* AVegetationManager::CreateFoliage(const FFoliageBlueprint& BP, const FTransform& Transform) const
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::CreateFoliage);
|
||||
|
||||
AActor* Actor = GetWorld()->SpawnActor<AActor>(BP.SpawnedClass,
|
||||
Transform.GetLocation(), Transform.Rotator());
|
||||
if (SpawnScale <= 1.01f && SpawnScale >= 0.99f)
|
||||
Actor->SetActorScale3D(Transform.GetScale3D());
|
||||
else
|
||||
Actor->SetActorScale3D({SpawnScale, SpawnScale, SpawnScale});
|
||||
Actor->SetTickableWhenPaused(false);
|
||||
return Actor;
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
/********** OTHER ***************************************************************/
|
||||
/********** TILES ***************************************************************/
|
||||
/********************************************************************************/
|
||||
void AVegetationManager::OnLevelAddedToWorld(ULevel* InLevel, UWorld* InWorld)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::OnLevelAddedToWorld);
|
||||
UpdateFoliageBlueprintCache(InLevel);
|
||||
CreateOrUpdateTileCache(InLevel);
|
||||
}
|
||||
|
||||
void AVegetationManager::OnLevelRemovedFromWorld(ULevel* InLevel, UWorld* InWorld)
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::OnLevelRemovedFromWorld);
|
||||
|
||||
}
|
||||
|
||||
bool AVegetationManager::CheckIfAnyVehicleInLevel() const
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::CheckIfAnyVehicleInLevel);
|
||||
|
@ -585,16 +609,16 @@ bool AVegetationManager::IsFoliageTypeEnabled(const FString& Path) const
|
|||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::IsFoliageTypeEnabled);
|
||||
if (!SpawnRocks)
|
||||
if (Path.Contains("Rock"))
|
||||
if (Path.Contains("/Rock/"))
|
||||
return false;
|
||||
if (!SpawnTrees)
|
||||
if (Path.Contains("Tree"))
|
||||
if (Path.Contains("/Tree/"))
|
||||
return false;
|
||||
if (!SpawnBushes)
|
||||
if (Path.Contains("Bush"))
|
||||
if (Path.Contains("/Bush/"))
|
||||
return false;
|
||||
if (!SpawnPlants)
|
||||
if (Path.Contains("Plant"))
|
||||
if (Path.Contains("/Plant/"))
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
@ -611,7 +635,7 @@ bool AVegetationManager::CheckForNewTiles() const
|
|||
if (!IsValid(InstancedFoliageActor))
|
||||
continue;
|
||||
const FString TileName = InstancedFoliageActor->GetLevel()->GetOuter()->GetName();
|
||||
if (!TileDataCache.Contains(TileName))
|
||||
if (!TileCache.Contains(TileName))
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -622,26 +646,25 @@ TArray<FString> AVegetationManager::GetTilesInUse()
|
|||
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::GetTilesInUse);
|
||||
TArray<FString> Results;
|
||||
|
||||
for (const TPair<FString, FTileData>& Element : TileDataCache)
|
||||
for (const TPair<FString, FTileData>& Element : TileCache)
|
||||
{
|
||||
const FTileData& TileData = Element.Value;
|
||||
if (!IsValid(TileData.InstancedFoliageActor) || !IsValid(TileData.ProceduralFoliageVolume))
|
||||
{
|
||||
TileDataCache.Remove(Element.Key);
|
||||
TileCache.Remove(Element.Key);
|
||||
return Results;
|
||||
}
|
||||
if (Results.Contains(Element.Key))
|
||||
continue;
|
||||
const AProceduralFoliageVolume* Procedural = TileData.ProceduralFoliageVolume;
|
||||
if (!IsValid(Procedural))
|
||||
continue;
|
||||
if (!IsValid(Procedural->ProceduralComponent))
|
||||
continue;
|
||||
if (Element.Key.IsEmpty())
|
||||
if (!IsValid(Procedural->ProceduralComponent))
|
||||
continue;
|
||||
const FBox Box = Procedural->ProceduralComponent->GetBounds();
|
||||
if (!Box.IsValid)
|
||||
continue;
|
||||
continue;
|
||||
|
||||
for (ACarlaWheeledVehicle* Vehicle : VehiclesInLevel)
|
||||
{
|
||||
if (!IsValid(Vehicle))
|
||||
|
|
|
@ -14,6 +14,7 @@
|
|||
#include "Containers/Array.h"
|
||||
#include "Containers/Map.h"
|
||||
|
||||
#include "Carla/MapGen/LargeMapManager.h"
|
||||
#include "Carla/Vehicle/CarlaWheeledVehicle.h"
|
||||
|
||||
#include "VegetationManager.generated.h"
|
||||
|
@ -35,14 +36,15 @@ struct FTileData
|
|||
TArray<FTileMeshComponent> TileMeshesCache {};
|
||||
TArray<UMaterialInstanceDynamic*> MaterialInstanceDynamicCache {};
|
||||
|
||||
void UpdateMaterialCache(const FLinearColor& Value);
|
||||
bool ContainsMesh(const UInstancedStaticMeshComponent*) const;
|
||||
void UpdateTileMeshComponent(UInstancedStaticMeshComponent* NewInstancedStaticMeshComponent);
|
||||
void UpdateMaterialCache(const FLinearColor& Value, bool DebugMaterials);
|
||||
};
|
||||
|
||||
USTRUCT()
|
||||
struct FFoliageBlueprint
|
||||
{
|
||||
GENERATED_BODY()
|
||||
FString BPClassName {};
|
||||
FString BPFullClassName {};
|
||||
TSubclassOf<AActor> SpawnedClass { nullptr };
|
||||
|
||||
|
@ -73,7 +75,8 @@ public:
|
|||
void RemoveVehicle(ACarlaWheeledVehicle* Vehicle);
|
||||
|
||||
public:
|
||||
//Cuando se carge un level engancharme al broadcast del delate del collision
|
||||
UPROPERTY(Category = "CARLA Vegetation Spwaner", EditDefaultsOnly)
|
||||
bool DebugMaterials {false};
|
||||
//Filters for debug
|
||||
UPROPERTY(Category = "CARLA Vegetation Spwaner", EditDefaultsOnly)
|
||||
bool SpawnBushes {true};
|
||||
|
@ -106,6 +109,7 @@ private:
|
|||
bool IsFoliageTypeEnabled(const FString& Path) const;
|
||||
bool CheckIfAnyVehicleInLevel() const;
|
||||
bool CheckForNewTiles() const;
|
||||
|
||||
TArray<FString> GetTilesInUse();
|
||||
|
||||
void UpdateVehiclesDetectionBoxes();
|
||||
|
@ -115,18 +119,29 @@ private:
|
|||
void DestroySkeletalFoliages();
|
||||
bool EnableActorFromPool(const FTransform& Transform, TArray<FPooledActor>& Pool);
|
||||
|
||||
void UpdateTileDataCache();
|
||||
void UpdateFoliageBlueprintCache();
|
||||
void GenerateTileDataInternals();
|
||||
void InitializeInstancedStaticMeshComponentCache(FTileData& TileData);
|
||||
void InitializeMaterialCache(FTileData& TileData);
|
||||
void CreateOrUpdateTileCache(ULevel* InLevel);
|
||||
void UpdateFoliageBlueprintCache(ULevel* InLevel);
|
||||
void SetTileDataInternals(FTileData& TileData);
|
||||
void SetInstancedStaticMeshComponentCache(FTileData& TileData);
|
||||
void SetMaterialCache(FTileData& TileData);
|
||||
|
||||
void FreeTileCache(ULevel* InLevel);
|
||||
|
||||
void OnLevelAddedToWorld(ULevel* InLevel, UWorld* InWorld);
|
||||
void OnLevelRemovedFromWorld(ULevel* InLevel, UWorld* InWorld);
|
||||
|
||||
void CreatePoolForBPClass(const FFoliageBlueprint& BP);
|
||||
AActor* CreateFoliage(const FFoliageBlueprint& BP, const FTransform& Transform) const;
|
||||
|
||||
void GetSketalTemplates();
|
||||
|
||||
private:
|
||||
//Actors
|
||||
ALargeMapManager* LargeMap {nullptr};
|
||||
TArray<ACarlaWheeledVehicle*> VehiclesInLevel {};
|
||||
//Caches
|
||||
TMap<FString, FFoliageBlueprint> FoliageBlueprintCache {};
|
||||
TMap<FString, FTileData> TileCache {};
|
||||
//Pools
|
||||
TMap<FString, TArray<FPooledActor>> ActorPool {};
|
||||
TMap<FString, FTileData> TileDataCache {};
|
||||
};
|
||||
|
|
|
@ -205,11 +205,18 @@ void ACarlaWheeledVehicle::BeginPlay()
|
|||
bool ACarlaWheeledVehicle::IsInVehicleRange(const FVector& Location) const
|
||||
{
|
||||
TRACE_CPUPROFILER_EVENT_SCOPE(ACarlaWheeledVehicle::IsInVehicleRange);
|
||||
ALargeMapManager* LargeMap =
|
||||
UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
check(LargeMap);
|
||||
FTransform GlobalTransform = LargeMap->LocalToGlobalTransform(GetActorTransform());
|
||||
float Distance = Distance = FVector::Distance(Location, GlobalTransform.GetLocation());
|
||||
|
||||
float Distance = 0.0f;
|
||||
ALargeMapManager* LargeMap = UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
if (LargeMap)
|
||||
{
|
||||
FTransform GlobalTransform = LargeMap->LocalToGlobalTransform(GetActorTransform());
|
||||
Distance = FVector::Distance(Location, GlobalTransform.GetLocation());
|
||||
}
|
||||
else
|
||||
{
|
||||
Distance = FVector::Distance(Location, GetActorTransform().GetLocation());
|
||||
}
|
||||
return Distance < DetectionSize * 10.0f;
|
||||
}
|
||||
|
||||
|
@ -236,6 +243,12 @@ void ACarlaWheeledVehicle::DrawFoliageBoundingBox() const
|
|||
|
||||
FBoxSphereBounds ACarlaWheeledVehicle::GetBoxSphereBounds() const
|
||||
{
|
||||
ALargeMapManager* LargeMap = UCarlaStatics::GetLargeMapManager(GetWorld());
|
||||
if (LargeMap)
|
||||
{
|
||||
FTransform GlobalTransform = LargeMap->LocalToGlobalTransform(GetActorTransform());
|
||||
return VehicleBounds->CalcBounds(GlobalTransform);
|
||||
}
|
||||
return VehicleBounds->CalcBounds(GetActorTransform());
|
||||
}
|
||||
|
||||
|
@ -383,8 +396,6 @@ void ACarlaWheeledVehicle::SetWheelsFrictionScale(TArray<float> &WheelsFrictionS
|
|||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
FVehiclePhysicsControl ACarlaWheeledVehicle::GetVehiclePhysicsControl() const
|
||||
{
|
||||
FVehiclePhysicsControl PhysicsControl;
|
||||
|
|
|
@ -354,7 +354,7 @@ private:
|
|||
|
||||
public:
|
||||
UPROPERTY(Category = "CARLA Wheeled Vehicle", EditDefaultsOnly)
|
||||
float DetectionSize {200.0f};
|
||||
float DetectionSize { 200.0f };
|
||||
|
||||
UPROPERTY(Category = "CARLA Wheeled Vehicle", VisibleAnywhere, BlueprintReadOnly)
|
||||
FBox FoliageBoundingBox;
|
||||
|
|
Loading…
Reference in New Issue