Terramechanics and Vegetation fixes (#5820)

* Added sparse map reprsentation

* Added pytorch for terramechanics modules

* Added saving loading particles in independent thread

* Added blank space at the EOF

* Added texture creation lambda

* Moving function to component

* Added input/output architecture for neural network

* Filling heightmap with particles data. Adding Logging to debug

* Updating Texture data at realtime

* Connected 3 stages, using MPC Position to Update and Texture

* Added square particle sampling. Added second model input/output scheme. Fixed start up crash.

* Added new flags and fixes

* Position to update not updating in material but yes in MPC

* Fixed coordinate frame issues and crashes

* Prepared to follow position in the 1st vehicle in map

* Fixed height map alignment

* Fixed large map and terrain tiles alignment

* Fixed inputs for new model

* Added scale factor

* Fixed slow read write operations

* Bug fixes

* Removed debug output

* Removed nvidia profinling marks

* Preparing merge debug code removed, runtime working by rounding the loading data properly

* Made pytorch optional module

* Added TRACE_CPUPROFILER_EVENT_SCOPE to Update and UpdateTexture

* Added optional pytorch conditions and macros

* Removed static Path

* fixed not finding skeletal blueprints in shipping builds

* Fixed #ifdef clause. Added missing include.

* Deformation on vehicle working. Ready to start optimisation

* First optimsation done. Heightmap per Tile

* Updated tiles'heightmap to make their size relative to texture and tilesize

* Physics fixed.
- Removed re-aplying forces all the time.
- Removed collisions with the static meshes.

* Fixed slow frames. Added functionality

* Removed unecessary library links

* Fixed pytorch link

* Limited search to relevant tiles

* Added parameter to modify torque and forces for nested bones.

* Forgot to add file.

* Added multithreaded particle search. Fixed cuda architectures compilation

* 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

* Deformation plane added

* Added missing resources

* Updated particle movement update methods

* Spawn on runtime deformation plane

* Added cachemap lock when initializing a region

* Added UHeightMapDataAsset to hold heightmap data

* Changes to tile location computation and threaded structure

* Added lock to prevent parallel intialization of tiles

* Adding support for large texture

* Fixed infinite loop

* Removed unnecessary function, changed particle ordering

* Disable Enable plane and Change path to create folder

* Added debug options for particles, added fraction based displacement

* Tried to round to have deterministic rounds in Coords calculations

* Revert files

* Fixes to enable UCustomTerrainPhysicsComponent to interact with ALargeMapManager

* 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

* Added Local tile displacement field

* Removed Freeing CacheData

* Fixes to enable UCustomTerrainPhysicsComponent to interact with ALargeMapManager

* Added Local tile displacement field

* Update Heightmaps

* Mark for initial update generated tiles

* Added soil component field and code clean up

* Fix with the path for debug foliages.

* Added flag to atenuate particle forces

* Fix compilation in windows

* Removing 'can rest' feature

* Removed Tile being recreated losing tree references.

* Fixing sleep

* Check index is valid before accesing it preventing crash when loading  tiles from files

* Add debug position, add logging when removing and adding particles to zordered map, now only remove one element from multisets

* Initialize tile's heightmap on the fly not read it from file

* Fixed link errors

* Added debug to location when not vehicle loaded. Taking Height from ZOrdered particles instead from tile local heightmap

* Mitigation of vibration

* Remove unused code

* fixed white textures

* Fixed Z spin in some situations

* Multithread savemap and added more logging for debug purpouses

* Removing non used code. Updating texture based on tiles position instead of cars position

* Fixed terrain type flag not working

* add checks for tile removing only with valid pointers.

* Fixed map loading crash

Co-authored-by: Aaron <samaniegoaaron112@gmail.com>
Co-authored-by: LuisPoveda <lpoveda@cvc.uab.cat>
Co-authored-by: bernatx <bernatx@gmail.com>
This commit is contained in:
Axel1092 2022-10-10 12:32:25 +02:00 committed by GitHub
parent 67d7da7e88
commit aeac45b09c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
10 changed files with 405 additions and 673 deletions

View File

@ -18,8 +18,10 @@ find_package(TorchScatter REQUIRED)
find_package(TorchCluster REQUIRED) find_package(TorchCluster REQUIRED)
find_package(Python3 REQUIRED) find_package(Python3 REQUIRED)
set(PYTORCH_CPP_STD_INCLUDES "/usr/include/c++/7")
# @todo These flags need to be compatible with setup.py compilation. # @todo These flags need to be compatible with setup.py compilation.
set(CMAKE_CXX_FLAGS_RELEASE "-DDEBUG -std=c++14 -O2 -fPIC -D_GLIBCXX_USE_CXX11_ABI=0" CACHE STRING "" FORCE) set(CMAKE_CXX_FLAGS_RELEASE "-DDEBUG -std=c++14 -O2 -fPIC -D_GLIBCXX_USE_CXX11_ABI=0 -I${PYTORCH_CPP_STD_INCLUDES}" CACHE STRING "" FORCE)
# ============================================================================== # ==============================================================================
# Create targets for debug and release in the same build type. # Create targets for debug and release in the same build type.

View File

@ -89,11 +89,7 @@ namespace learning {
result._particle_forces.emplace_back( result._particle_forces.emplace_back(
particle_forces_data[i*num_dimensions + 2]); particle_forces_data[i*num_dimensions + 2]);
} }
if(num_particles > 0) // std::cout << "Output: " << result._particle_forces.size()/3 << " particles" << std::endl;
{
std::cout << particle_forces_data[0] << " " << particle_forces_data[1] << " " << particle_forces_data[0] << std::endl;
}
std::cout << "Output: " << result._particle_forces.size()/3 << " particles" << std::endl;
return result; return result;
} }
@ -117,10 +113,6 @@ namespace learning {
result._particle_forces.emplace_back( result._particle_forces.emplace_back(
particle_forces_data[i*num_dimensions + 2]); particle_forces_data[i*num_dimensions + 2]);
} }
if(num_particles > 0)
{
std::cout << particle_forces_data[0] << " " << particle_forces_data[1] << " " << particle_forces_data[0] << std::endl;
}
// std::cout << "Output: " << result._particle_forces.size()/3 << " particles" << std::endl; // std::cout << "Output: " << result._particle_forces.size()/3 << " particles" << std::endl;
return result; return result;
} }
@ -183,7 +175,7 @@ namespace learning {
Model->module = torch::jit::load(filename_str); Model->module = torch::jit::load(filename_str);
std::string cuda_str = "cuda:" + std::to_string(device); std::string cuda_str = "cuda:" + std::to_string(device);
std::cout << "Using CUDA device " << cuda_str << std::endl; std::cout << "Using CUDA device " << cuda_str << std::endl;
Model->module.to(at::Device(cuda_str)); // Model->module.to(at::Device(cuda_str));
} catch (const c10::Error& e) { } catch (const c10::Error& e) {
std::cout << "Error loading model: " << e.msg() << std::endl; std::cout << "Error loading model: " << e.msg() << std::endl;
} }
@ -204,7 +196,11 @@ namespace learning {
auto drv_inputs = torch::tensor( auto drv_inputs = torch::tensor(
{_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake {_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake
TorchInputs.push_back(drv_inputs); TorchInputs.push_back(drv_inputs);
if (_input.terrain_type > 0) {
TorchInputs.push_back(_input.terrain_type);
}
TorchInputs.push_back(_input.verbose); TorchInputs.push_back(_input.verbose);
std::cout << _input.verbose << std::endl;
torch::jit::IValue Output; torch::jit::IValue Output;
try { try {
@ -235,7 +231,11 @@ namespace learning {
auto drv_inputs = torch::tensor( auto drv_inputs = torch::tensor(
{_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake {_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake
TorchInputs.push_back(drv_inputs); TorchInputs.push_back(drv_inputs);
if (_input.terrain_type > 0) {
TorchInputs.push_back(_input.terrain_type);
}
TorchInputs.push_back(_input.verbose); TorchInputs.push_back(_input.verbose);
std::cout << _input.verbose << std::endl;
torch::jit::IValue Output; torch::jit::IValue Output;
try { try {
@ -270,7 +270,11 @@ namespace learning {
auto drv_inputs = torch::tensor( auto drv_inputs = torch::tensor(
{_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake {_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake
TorchInputs.push_back(drv_inputs.cuda()); TorchInputs.push_back(drv_inputs.cuda());
if (_input.terrain_type > 0) {
TorchInputs.push_back(_input.terrain_type);
}
TorchInputs.push_back(_input.verbose); TorchInputs.push_back(_input.verbose);
std::cout << _input.verbose << std::endl;
torch::jit::IValue Output; torch::jit::IValue Output;
try { try {

View File

@ -24,7 +24,6 @@ namespace learning {
float* wheel_oritentation; float* wheel_oritentation;
float* wheel_linear_velocity; float* wheel_linear_velocity;
float* wheel_angular_velocity; float* wheel_angular_velocity;
int terrain_type = 0;
}; };
struct Inputs { struct Inputs {
@ -36,6 +35,7 @@ namespace learning {
float steering = 0; float steering = 0;
float throttle = 0; float throttle = 0;
float braking = 0; float braking = 0;
int terrain_type = 0;
bool verbose = false; bool verbose = false;
}; };

View File

@ -475,7 +475,7 @@ FIntVector ALargeMapManager::GetTileVectorID(FVector TileLocation) const
{ {
FIntVector VectorId = FIntVector( FIntVector VectorId = FIntVector(
(TileLocation - (TileLocation -
(Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0))) (Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0) + LocalTileOffset))
/ TileSide); / TileSide);
VectorId.Y *= -1; VectorId.Y *= -1;
return VectorId; return VectorId;
@ -485,7 +485,7 @@ FIntVector ALargeMapManager::GetTileVectorID(FDVector TileLocation) const
{ {
FIntVector VectorId = ( FIntVector VectorId = (
(TileLocation - (TileLocation -
(Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0))) (Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0) + LocalTileOffset))
/ TileSide).ToFIntVector(); / TileSide).ToFIntVector();
VectorId.Y *= -1; VectorId.Y *= -1;
return VectorId; return VectorId;

View File

@ -290,6 +290,9 @@ protected:
UPROPERTY(EditAnywhere, Category = "Large Map Manager") UPROPERTY(EditAnywhere, Category = "Large Map Manager")
float TileSide = 2.0f * 1000.0f * 100.0f; // 2km float TileSide = 2.0f * 1000.0f * 100.0f; // 2km
UPROPERTY(EditAnywhere, Category = "Large Map Manager")
FVector LocalTileOffset = FVector(0,0,0);
UPROPERTY(EditAnywhere, Category = "Large Map Manager") UPROPERTY(EditAnywhere, Category = "Large Map Manager")
bool ShouldTilesBlockOnLoad = false; bool ShouldTilesBlockOnLoad = false;

View File

@ -49,12 +49,37 @@
#define OTHER_LOG(...) #define OTHER_LOG(...)
#endif #endif
FRotator GetDeltaRotator(const FRotator & Rotator1, const FRotator & Rotator2)
{
float HalfCircle = 180.f;
float FullCircle = 360.f;
auto GetDeltaAngle = [&](float Angle1, float Angle2) -> float
{
if (Angle1 < 0)
{
Angle1 = FullCircle + Angle1;
}
if (Angle2 < 0)
{
Angle2 = FullCircle + Angle2;
}
float Diff = fmod( Angle1 - Angle2 + HalfCircle , FullCircle) - HalfCircle;
return Diff < -HalfCircle ? Diff + FullCircle : Diff;
};
return FRotator(
GetDeltaAngle(Rotator1.Pitch, Rotator2.Pitch),
GetDeltaAngle(Rotator1.Yaw, Rotator2.Yaw),
GetDeltaAngle(Rotator1.Roll, Rotator2.Roll)
);
}
template <class T> template <class T>
static T GetSign(T n) static T GetSign(T n)
{ {
return n < 0.0f ? -1.0f : 1.0f; return n < 0.0f ? -1.0f : 1.0f;
} }
template <class T> template <class T>
static FString EigenToFString(T& t) static FString EigenToFString(T& t)
{ {
@ -352,6 +377,8 @@ void USpringBasedVegetationComponent::BeginPlay()
{ {
ComputeSpringStrengthForBranches(); ComputeSpringStrengthForBranches();
} }
JointCollisionList.resize(Skeleton.Joints.Num());
} }
void USpringBasedVegetationComponent::ResetComponent() void USpringBasedVegetationComponent::ResetComponent()
@ -603,6 +630,13 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions(
std::vector<FJointProperties>& JointPropertiesList) std::vector<FJointProperties>& JointPropertiesList)
{ {
TRACE_CPUPROFILER_EVENT_SCOPE(USpringBasedVegetationComponent::ResolveContactsAndCollisions); TRACE_CPUPROFILER_EVENT_SCOPE(USpringBasedVegetationComponent::ResolveContactsAndCollisions);
// set all joints that can rest
for (auto &Joint : JointCollisionList)
{
Joint.CanRest = true;
}
for (auto& ActorCapsules : OverlappingActors) for (auto& ActorCapsules : OverlappingActors)
{ {
TRACE_CPUPROFILER_EVENT_SCOPE(ActorLoop); TRACE_CPUPROFILER_EVENT_SCOPE(ActorLoop);
@ -662,6 +696,7 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions(
const int JointId = CapsuleToJointId[Capsule]; const int JointId = CapsuleToJointId[Capsule];
const FSkeletonJoint& Joint = Skeleton.Joints[JointId]; const FSkeletonJoint& Joint = Skeleton.Joints[JointId];
FJointProperties& JointProperties = JointLocalPropertiesList[Joint.JointId]; FJointProperties& JointProperties = JointLocalPropertiesList[Joint.JointId];
FJointCollision& JointCollision = JointCollisionList[Joint.JointId];
const Eigen::Vector3d JointGlobalPosition = ToEigenVector(Joint.GlobalTransform.GetLocation()) / 100.f; const Eigen::Vector3d JointGlobalPosition = ToEigenVector(Joint.GlobalTransform.GetLocation()) / 100.f;
const Eigen::Vector3d CapsulePosition = ToEigenVector(CapsuleLocation) / 100.f; const Eigen::Vector3d CapsulePosition = ToEigenVector(CapsuleLocation) / 100.f;
const Eigen::Vector3d PointOnCapsulePosition = ToEigenVector(ClosestPointOnCapsule) / 100.f; const Eigen::Vector3d PointOnCapsulePosition = ToEigenVector(ClosestPointOnCapsule) / 100.f;
@ -671,10 +706,8 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions(
// Contact forces due to spring strength // Contact forces due to spring strength
const FRotator CurrRotator = Joint.Transform.Rotator(); const FRotator CurrRotator = Joint.Transform.Rotator();
const FRotator RestRotator = Joint.RestingAngles; const FRotator RestRotator = Joint.RestingAngles;
const FRotator DeltaRotator ( const FRotator DeltaRotator =
CurrRotator.Pitch - RestRotator.Pitch, GetDeltaRotator(CurrRotator, RestRotator);
CurrRotator.Yaw - RestRotator.Yaw,
CurrRotator.Roll - RestRotator.Roll);
const Eigen::Vector3d SpringTorque = Joint.SpringStrength * RotatorToEigenVector(DeltaRotator); const Eigen::Vector3d SpringTorque = Joint.SpringStrength * RotatorToEigenVector(DeltaRotator);
const Eigen::Vector3d JointCapsuleVector = JointGlobalPosition - CapsulePosition; const Eigen::Vector3d JointCapsuleVector = JointGlobalPosition - CapsulePosition;
const Eigen::Vector3d RepulsionForce = SpringTorque.cross(JointCapsuleVector) * JointCapsuleVector.squaredNorm(); const Eigen::Vector3d RepulsionForce = SpringTorque.cross(JointCapsuleVector) * JointCapsuleVector.squaredNorm();
@ -691,14 +724,29 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions(
float ProportionalConstant = 1.f/(FMath::Pow(ForceMaxDistance, ForceDistanceFalloffExponent)); float ProportionalConstant = 1.f/(FMath::Pow(ForceMaxDistance, ForceDistanceFalloffExponent));
ForceFactor = ProportionalConstant * FMath::Pow(DistanceToCollider, ForceDistanceFalloffExponent); ForceFactor = ProportionalConstant * FMath::Pow(DistanceToCollider, ForceDistanceFalloffExponent);
ForceFactor = FMath::Clamp(ForceFactor, MinForceFactor, 1.f); ForceFactor = FMath::Clamp(ForceFactor, MinForceFactor, 1.f);
// const Eigen::Vector3d OverlappingForces = (ColliderPosition - CapsulePosition).normalized() * CollisionForceParameter * ForceFactor; // const Eigen::Vector3d OverlappingForces = (ColliderPosition - CapsulePosition).normalized() * CollisionForceParameter * ForceFactor;
const Eigen::Vector3d OverlappingForces = (ColliderPosition - PointOnCapsulePosition).normalized() * CollisionForceParameter * ForceFactor; // const Eigen::Vector3d OverlappingForces = (ColliderPosition - PointOnCapsulePosition).normalized() * CollisionForceParameter * ForceFactor;
float Factor = 1.0f - ((JointCollision.Iteration / 100.0f) * RestFactor);
const Eigen::Vector3d OverlappingForces = (ColliderPosition - PointOnCapsulePosition).normalized() * CollisionForceParameter * ForceFactor * Factor;
Primitive->AddForceAtLocation(-ToUnrealVector(OverlappingForces) * 100.f, ClosestPointOnCollider); Primitive->AddForceAtLocation(-ToUnrealVector(OverlappingForces) * 100.f, ClosestPointOnCollider);
CollisionTorque += (JointProperties.CenterOfMass - JointGlobalPosition).cross(CollisionImpulse + OverlappingForces); CollisionTorque += (JointProperties.CenterOfMass - JointGlobalPosition).cross(CollisionImpulse + OverlappingForces);
JointProperties.Torque += CollisionTorque; 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)); // 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); //UE_LOG(LogCarla, Display, TEXT("DistanceToCollider: %f, ForceFactor: %f"), DistanceToCollider, ForceFactor);
// block forces to go to rest angles
int TempId = JointId;
do
{
FJointCollision& TempJointCollision = JointCollisionList[TempId];
TempJointCollision.CanRest = false;
FSkeletonJoint &TempJoint = Skeleton.Joints[TempId];
TempId = TempJoint.ParentId;
}
while (TempId != -1);
if (DebugEnableVisualization) if (DebugEnableVisualization)
{ {
// drawing // drawing
@ -710,6 +758,25 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions(
} }
} }
} }
// reset iteration
for (auto &Joint : JointCollisionList)
{
if (Joint.CanRest)
{
if (Joint.Iteration > 1)
{
--Joint.Iteration;
}
}
else
{
if (Joint.Iteration <= 95)
{
Joint.Iteration += 5;
}
}
}
} }
void USpringBasedVegetationComponent::SolveEquationOfMotion( void USpringBasedVegetationComponent::SolveEquationOfMotion(
@ -725,16 +792,26 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
continue; continue;
} }
FJointProperties& JointProperties = JointPropertiesList[Joint.JointId]; FJointProperties& JointProperties = JointPropertiesList[Joint.JointId];
FJointCollision& JointCollision = JointCollisionList[Joint.JointId];
// drawing // debug drawing
if (Joint.ParentId != -1 && DebugEnableVisualization) if (DebugEnableVisualization)
{ {
const FVector Start = Joint.GlobalTransform.GetLocation(); if (Joint.ParentId != -1)
const FVector End = Skeleton.Joints[Joint.ParentId].GlobalTransform.GetLocation(); {
const FColor LineColor(FColor::Blue); FVector Start = Joint.GlobalTransform.GetLocation();
DrawDebugLine(GetWorld(), Start, End, LineColor, false, 0.1f, 0.0f, 1.f); FVector End = Skeleton.Joints[Joint.ParentId].GlobalTransform.GetLocation();
if (!JointCollision.CanRest)
{
DrawDebugLine(GetWorld(), Start, End, FColor::Red, false, 0.3f, 0.0f, 1.f);
}
else
{
DrawDebugLine(GetWorld(), Start, End, FColor::Blue, false, 0.1f, 0.0f, 1.f);
}
}
} }
float Mass = JointProperties.Mass; float Mass = JointProperties.Mass;
Eigen::Vector3d CenterToJoint = JointProperties.CenterOfMass - ToEigenVector(Joint.GlobalTransform.GetLocation())/100.f; Eigen::Vector3d CenterToJoint = JointProperties.CenterOfMass - ToEigenVector(Joint.GlobalTransform.GetLocation())/100.f;
Eigen::Matrix3d GlobalToJointMatrix = JointProperties.JointToGlobalMatrix.transpose(); Eigen::Matrix3d GlobalToJointMatrix = JointProperties.JointToGlobalMatrix.transpose();
@ -774,10 +851,14 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
FRotator CurrRotator = Joint.Transform.Rotator(); FRotator CurrRotator = Joint.Transform.Rotator();
FRotator RestRotator = Joint.RestingAngles; FRotator RestRotator = Joint.RestingAngles;
FRotator AngularVelocity = Joint.AngularVelocity; FRotator AngularVelocity = Joint.AngularVelocity;
FRotator DeltaRotator ( FRotator DeltaRotator =
CurrRotator.Pitch - RestRotator.Pitch, GetDeltaRotator(CurrRotator, RestRotator);
CurrRotator.Yaw - RestRotator.Yaw, if (!JointCollision.CanRest)
CurrRotator.Roll - RestRotator.Roll); {
float Factor = 1.0f - ((JointCollision.Iteration / 100.0f) * RestFactor);
// DeltaRotator *= Factor;
AngularVelocity *= Factor;
}
Eigen::Vector3d InitialTheta = Uinv*RotatorToEigenVector(DeltaRotator); Eigen::Vector3d InitialTheta = Uinv*RotatorToEigenVector(DeltaRotator);
Eigen::Vector3d InitialThetaVelocity = Uinv*RotatorToEigenVector(AngularVelocity); Eigen::Vector3d InitialThetaVelocity = Uinv*RotatorToEigenVector(AngularVelocity);
SOLVER_LOG(Log, "Old angle for joint %s, %s", *Joint.JointName, *CurrRotator.ToString()); SOLVER_LOG(Log, "Old angle for joint %s, %s", *Joint.JointName, *CurrRotator.ToString());
@ -803,7 +884,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
} }
double dtheta0 = InitialThetaVelocity(i); // compute double dtheta0 = InitialThetaVelocity(i); // compute
double deltatheta = 0; double deltatheta = 0;
double angulavelocity = 0; double angularvelocity = 0;
float angularaccel = 0; float angularaccel = 0;
if (discriminant > 0) if (discriminant > 0)
{ {
@ -812,7 +893,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
double c1 = (r2*(theta0 - f/k) - dtheta0)/(r2-r1); double c1 = (r2*(theta0 - f/k) - dtheta0)/(r2-r1);
double c2 = (dtheta0 - c1*r1)/r2; double c2 = (dtheta0 - c1*r1)/r2;
deltatheta = c1*std::exp(r1*DeltaTime) + c2*std::exp(r2*DeltaTime) + f/k; deltatheta = c1*std::exp(r1*DeltaTime) + c2*std::exp(r2*DeltaTime) + f/k;
angulavelocity = c1*r1*std::exp(r1*DeltaTime) + c2*r2*std::exp(r2*DeltaTime); angularvelocity = c1*r1*std::exp(r1*DeltaTime) + c2*r2*std::exp(r2*DeltaTime);
SOLVER_LOG(Log, "r1 %f, r2 %f, c1 %f, c2 %f, deltatheta %f", r1, r2, c1, c2, deltatheta); SOLVER_LOG(Log, "r1 %f, r2 %f, c1 %f, c2 %f, deltatheta %f", r1, r2, c1, c2, deltatheta);
} }
else if (discriminant == 0) else if (discriminant == 0)
@ -821,7 +902,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
double c1 = theta0 - f/k; double c1 = theta0 - f/k;
double c2 = dtheta0 - c1*r; double c2 = dtheta0 - c1*r;
deltatheta = (c1 + c2*DeltaTime)*std::exp(r*DeltaTime) + f/k; deltatheta = (c1 + c2*DeltaTime)*std::exp(r*DeltaTime) + f/k;
angulavelocity = (c1*r + c2 + c2*r*DeltaTime)*std::exp(r*DeltaTime); angularvelocity = (c1*r + c2 + c2*r*DeltaTime)*std::exp(r*DeltaTime);
SOLVER_LOG(Log, "r %f, c1 %f, c2 %f, deltatheta %f", r, c1, c2, deltatheta); SOLVER_LOG(Log, "r %f, c1 %f, c2 %f, deltatheta %f", r, c1, c2, deltatheta);
} }
else else
@ -833,18 +914,18 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion(
deltatheta = deltatheta =
c1*std::exp(gamma*DeltaTime)*std::cos(mu*DeltaTime) + c1*std::exp(gamma*DeltaTime)*std::cos(mu*DeltaTime) +
c2*std::exp(gamma*DeltaTime)*std::sin(mu*DeltaTime) + f/k; c2*std::exp(gamma*DeltaTime)*std::sin(mu*DeltaTime) + f/k;
angulavelocity = angularvelocity =
c1*std::exp(gamma*DeltaTime)*(gamma*std::cos(mu*DeltaTime) + mu*std::sin(mu*DeltaTime)) + c1*std::exp(gamma*DeltaTime)*(gamma*std::cos(mu*DeltaTime) + mu*std::sin(mu*DeltaTime)) +
c2*std::exp(gamma*DeltaTime)*(gamma*std::sin(mu*DeltaTime) - mu*std::cos(mu*DeltaTime)); c2*std::exp(gamma*DeltaTime)*(gamma*std::sin(mu*DeltaTime) - mu*std::cos(mu*DeltaTime));
SOLVER_LOG(Log, "gamma %f, mu %f, c1 %f, c2 %f, deltatheta %f", gamma, mu, c1, c2, deltatheta); SOLVER_LOG(Log, "gamma %f, mu %f, c1 %f, c2 %f, deltatheta %f", gamma, mu, c1, c2, deltatheta);
} }
angularaccel = f - b*angulavelocity - k*deltatheta; angularaccel = f - b*angularvelocity - k*deltatheta;
if (!FMath::IsNaN(deltatheta)) if (!FMath::IsNaN(deltatheta))
{ {
NewTheta(i) = deltatheta; NewTheta(i) = deltatheta;
if (angulavelocity > 1e-4) if (angularvelocity > 1e-4)
{ {
NewThetaVelocity(i) = angulavelocity; NewThetaVelocity(i) = angularvelocity;
} }
if (angularaccel > 1e-2) if (angularaccel > 1e-2)
{ {

View File

@ -78,6 +78,12 @@ struct FSkeletonJoint
FVector ExternalForces = FVector(0,0,0); FVector ExternalForces = FVector(0,0,0);
}; };
struct FJointCollision
{
bool CanRest = true;
int Iteration = 1;
};
struct FJointProperties struct FJointProperties
{ {
float Mass = 0.0; float Mass = 0.0;
@ -202,6 +208,8 @@ private:
std::vector<FJointProperties>& JointPropertiesList); std::vector<FJointProperties>& JointPropertiesList);
void SolveEquationOfMotion(std::vector<FJointProperties>& JointPropertiesList, float DeltaTime); void SolveEquationOfMotion(std::vector<FJointProperties>& JointPropertiesList, float DeltaTime);
std::vector<FJointCollision> JointCollisionList;
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
USkeletalMeshComponent* SkeletalMesh; USkeletalMeshComponent* SkeletalMesh;
@ -232,6 +240,9 @@ private:
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
float VerticalFallof = 0.1f; float VerticalFallof = 0.1f;
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
float RestFactor = 0.5f;
UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component")
float DeltaTimeOverride = -1.f; float DeltaTimeOverride = -1.f;

View File

@ -260,6 +260,12 @@ void AVegetationManager::CreateOrUpdateTileCache(ULevel* InLevel)
{ {
ExistingTileData->InstancedFoliageActor = TileData.InstancedFoliageActor; ExistingTileData->InstancedFoliageActor = TileData.InstancedFoliageActor;
ExistingTileData->ProceduralFoliageVolume = TileData.ProceduralFoliageVolume; ExistingTileData->ProceduralFoliageVolume = TileData.ProceduralFoliageVolume;
for (FTileMeshComponent& Element : ExistingTileData->TileMeshesCache)
{
Element.InstancedStaticMeshComponent = nullptr;
Element.IndicesInUse.Empty();
}
ExistingTileData->TileMeshesCache.Empty();
SetTileDataInternals(*ExistingTileData); SetTileDataInternals(*ExistingTileData);
} }
else else
@ -314,6 +320,8 @@ void AVegetationManager::SetMaterialCache(FTileData& TileData)
for (FTileMeshComponent& Element : TileData.TileMeshesCache) for (FTileMeshComponent& Element : TileData.TileMeshesCache)
{ {
UInstancedStaticMeshComponent* Mesh = Element.InstancedStaticMeshComponent; UInstancedStaticMeshComponent* Mesh = Element.InstancedStaticMeshComponent;
if (!IsValid(Mesh))
continue;
int32 Index = -1; int32 Index = -1;
for (UMaterialInterface* Material : Mesh->GetMaterials()) for (UMaterialInterface* Material : Mesh->GetMaterials())
{ {
@ -374,9 +382,13 @@ void AVegetationManager::UpdateFoliageBlueprintCache(ULevel* InLevel)
void AVegetationManager::FreeTileCache(ULevel* InLevel) void AVegetationManager::FreeTileCache(ULevel* InLevel)
{ {
if (!IsValid(InLevel))
return;
FTileData TileData {}; FTileData TileData {};
for (AActor* Actor : InLevel->Actors) for (AActor* Actor : InLevel->Actors)
{ {
if (!IsValid(Actor))
continue;
AInstancedFoliageActor* InstancedFoliageActor = Cast<AInstancedFoliageActor>(Actor); AInstancedFoliageActor* InstancedFoliageActor = Cast<AInstancedFoliageActor>(Actor);
if (!IsValid(InstancedFoliageActor)) if (!IsValid(InstancedFoliageActor))
continue; continue;
@ -596,7 +608,7 @@ void AVegetationManager::OnLevelAddedToWorld(ULevel* InLevel, UWorld* InWorld)
void AVegetationManager::OnLevelRemovedFromWorld(ULevel* InLevel, UWorld* InWorld) void AVegetationManager::OnLevelRemovedFromWorld(ULevel* InLevel, UWorld* InWorld)
{ {
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::OnLevelRemovedFromWorld); TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::OnLevelRemovedFromWorld);
FreeTileCache(InLevel);
} }
bool AVegetationManager::CheckIfAnyVehicleInLevel() const bool AVegetationManager::CheckIfAnyVehicleInLevel() const
@ -609,16 +621,16 @@ bool AVegetationManager::IsFoliageTypeEnabled(const FString& Path) const
{ {
TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::IsFoliageTypeEnabled); TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::IsFoliageTypeEnabled);
if (!SpawnRocks) if (!SpawnRocks)
if (Path.Contains("/Rock/")) if (Path.Contains("/Rock"))
return false; return false;
if (!SpawnTrees) if (!SpawnTrees)
if (Path.Contains("/Tree/")) if (Path.Contains("/Tree"))
return false; return false;
if (!SpawnBushes) if (!SpawnBushes)
if (Path.Contains("/Bush/")) if (Path.Contains("/Bush"))
return false; return false;
if (!SpawnPlants) if (!SpawnPlants)
if (Path.Contains("/Plant/")) if (Path.Contains("/Plant"))
return false; return false;
return true; return true;
} }

View File

@ -39,7 +39,7 @@ public:
int SizeX = 0; int SizeX = 0;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = HeightMapDataAsset) UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = HeightMapDataAsset)
int SizeY = 0; int SizeY = 0;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = HeightMapDataAsset) UPROPERTY(BlueprintReadWrite, Category = HeightMapDataAsset)
TArray<float> HeightValues; TArray<float> HeightValues;
}; };
@ -52,12 +52,6 @@ struct FParticle
struct FHeightMapData struct FHeightMapData
{ {
void InitializeHeightmap(
UTexture2D* Texture, FDVector Size, FDVector Origin,
float MinHeight, float MaxHeight, FDVector Tile0, float ScaleZ);
void InitializeHeightmapFloat(
UTexture2D* Texture, FDVector Size, FDVector Origin,
float MinHeight, float MaxHeight, FDVector Tile0, float ScaleZ);
void InitializeHeightmap( void InitializeHeightmap(
UHeightMapDataAsset* DataAsset, FDVector Size, FDVector Origin, UHeightMapDataAsset* DataAsset, FDVector Size, FDVector Origin,
FDVector Tile0, float ScaleZ); FDVector Tile0, float ScaleZ);
@ -93,7 +87,6 @@ struct FDenseTile
void UpdateLocalHeightmap(); void UpdateLocalHeightmap();
std::vector<FParticle> Particles; std::vector<FParticle> Particles;
std::vector<float> ParticlesHeightMap; std::vector<float> ParticlesHeightMap;
//std::vector<std::vector<float>> ParticlesZOrdered;
std::vector<std::multiset<float,std::greater<float>>> ParticlesZOrdered; std::vector<std::multiset<float,std::greater<float>>> ParticlesZOrdered;
FDVector TilePosition; FDVector TilePosition;
FString SavePath; FString SavePath;
@ -150,21 +143,12 @@ public:
return Heightmap.GetHeight(Position); return Heightmap.GetHeight(Position);
} }
void InitializeMap(UTexture2D* HeightMapTexture,
FDVector Origin, FDVector MapSize, float Size, float MinHeight, float MaxHeight,
float ScaleZ);
void InitializeMap(UHeightMapDataAsset* DataAsset, void InitializeMap(UHeightMapDataAsset* DataAsset,
FDVector Origin, FDVector MapSize, float Size, float ScaleZ); FDVector Origin, FDVector MapSize, float Size, float ScaleZ);
void UpdateHeightMap(UTexture2D* HeightMapTexture,
FDVector Origin, FDVector MapSize, float Size, float MinHeight, float MaxHeight,
float ScaleZ);
void UpdateHeightMap(UHeightMapDataAsset* DataAsset, void UpdateHeightMap(UHeightMapDataAsset* DataAsset,
FDVector Origin, FDVector MapSize, float Size, float ScaleZ); FDVector Origin, FDVector MapSize, float Size, float ScaleZ);
void LoadTilesAtPositionFromCache(FDVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f);
void UnLoadTilesAtPositionToCache(FDVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f);
void ReloadCache(FDVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f);
void UpdateMaps(FDVector Position, float RadiusX, float RadiusY, float CacheRadiusX, float CacheRadiusY); void UpdateMaps(FDVector Position, float RadiusX, float RadiusY, float CacheRadiusX, float CacheRadiusY);
void Update(FVector Position, float RadiusX, float RadiusY); void Update(FVector Position, float RadiusX, float RadiusY);
@ -255,9 +239,6 @@ public:
UFUNCTION(BlueprintCallable) UFUNCTION(BlueprintCallable)
void AddForces(const TArray<FForceAtLocation> &Forces); void AddForces(const TArray<FForceAtLocation> &Forces);
UFUNCTION(BlueprintCallable)
TArray<float> BuildLandscapeHeightMap(ALandscapeProxy* Landscape, int Resolution);
UFUNCTION(BlueprintCallable) UFUNCTION(BlueprintCallable)
static void BuildLandscapeHeightMapDataAasset(ALandscapeProxy* Landscape, static void BuildLandscapeHeightMapDataAasset(ALandscapeProxy* Landscape,
int Resolution, FVector MapSize, FString AssetPath, FString AssetName); int Resolution, FVector MapSize, FString AssetPath, FString AssetName);
@ -274,27 +255,15 @@ public:
UFUNCTION(BlueprintCallable) UFUNCTION(BlueprintCallable)
FVector GetTileCenter(FVector Position); FVector GetTileCenter(FVector Position);
UFUNCTION(BlueprintCallable, Category="Tiles")
void LoadTilesAtPosition(FVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f);
UFUNCTION(BlueprintCallable, Category="Tiles") UFUNCTION(BlueprintCallable, Category="Tiles")
void UpdateMaps(FVector Position, float RadiusX, float RadiusY, float CacheRadiusX, float CacheRadiusY); void UpdateMaps(FVector Position, float RadiusX, float RadiusY, float CacheRadiusX, float CacheRadiusY);
UFUNCTION(BlueprintCallable, Category="Tiles")
void UnloadTilesAtPosition(FVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f);
UFUNCTION(BlueprintCallable, Category="Tiles")
void ReloadCache(FVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f);
UFUNCTION(BlueprintCallable, Category="Texture") UFUNCTION(BlueprintCallable, Category="Texture")
void InitTexture(); void InitTexture();
UFUNCTION(BlueprintCallable, Category="Texture") UFUNCTION(BlueprintCallable, Category="Texture")
void UpdateTexture(); void UpdateTexture();
UFUNCTION(BlueprintCallable, Category="Texture")
void UpdateTextureData();
UFUNCTION(BlueprintCallable, Category="Texture") UFUNCTION(BlueprintCallable, Category="Texture")
void UpdateLoadedTextureDataRegions(); void UpdateLoadedTextureDataRegions();
@ -307,9 +276,6 @@ public:
UFUNCTION(BlueprintCallable, Category="Texture") UFUNCTION(BlueprintCallable, Category="Texture")
void UpdateLargeTextureData(); void UpdateLargeTextureData();
UPROPERTY(EditAnywhere, BlueprintReadWrite)
UTexture2D *HeightMap;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="MaterialParameters") UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="MaterialParameters")
UTexture2D* TextureToUpdate; UTexture2D* TextureToUpdate;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="MaterialParameters") UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="MaterialParameters")
@ -338,6 +304,10 @@ public:
float ForceMulFactor = 1.0; float ForceMulFactor = 1.0;
UPROPERTY(EditAnywhere, BlueprintReadWrite) UPROPERTY(EditAnywhere, BlueprintReadWrite)
float ParticleForceMulFactor = 1.0; float ParticleForceMulFactor = 1.0;
UPROPERTY(EditAnywhere, BlueprintReadWrite)
int SoilType = 0;
UPROPERTY(EditAnywhere, BlueprintReadWrite)
bool bUseSoilType = false;
UPROPERTY(EditAnywhere) UPROPERTY(EditAnywhere)
bool NNVerbose = false; bool NNVerbose = false;
@ -438,8 +408,6 @@ private:
UPROPERTY() UPROPERTY()
UMaterialParameterCollectionInstance* MPCInstance; UMaterialParameterCollectionInstance* MPCInstance;
UPROPERTY(EditAnywhere) UPROPERTY(EditAnywhere)
float SearchRadius = 100; float SearchRadius = 100;