diff --git a/LibCarla/cmake/pytorch/CMakeLists.txt b/LibCarla/cmake/pytorch/CMakeLists.txt index 9980293a8..a824c89ef 100644 --- a/LibCarla/cmake/pytorch/CMakeLists.txt +++ b/LibCarla/cmake/pytorch/CMakeLists.txt @@ -18,8 +18,10 @@ find_package(TorchScatter REQUIRED) find_package(TorchCluster 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. -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. diff --git a/LibCarla/source/carla/pytorch/pytorch.cpp b/LibCarla/source/carla/pytorch/pytorch.cpp index 236c0f896..5a7bf1907 100644 --- a/LibCarla/source/carla/pytorch/pytorch.cpp +++ b/LibCarla/source/carla/pytorch/pytorch.cpp @@ -89,11 +89,7 @@ namespace learning { result._particle_forces.emplace_back( 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; } @@ -117,10 +113,6 @@ namespace learning { result._particle_forces.emplace_back( 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; return result; } @@ -183,7 +175,7 @@ namespace learning { Model->module = torch::jit::load(filename_str); std::string cuda_str = "cuda:" + std::to_string(device); 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) { std::cout << "Error loading model: " << e.msg() << std::endl; } @@ -204,7 +196,11 @@ namespace learning { auto drv_inputs = torch::tensor( {_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake TorchInputs.push_back(drv_inputs); + if (_input.terrain_type > 0) { + TorchInputs.push_back(_input.terrain_type); + } TorchInputs.push_back(_input.verbose); + std::cout << _input.verbose << std::endl; torch::jit::IValue Output; try { @@ -235,7 +231,11 @@ namespace learning { auto drv_inputs = torch::tensor( {_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake TorchInputs.push_back(drv_inputs); + if (_input.terrain_type > 0) { + TorchInputs.push_back(_input.terrain_type); + } TorchInputs.push_back(_input.verbose); + std::cout << _input.verbose << std::endl; torch::jit::IValue Output; try { @@ -270,7 +270,11 @@ namespace learning { auto drv_inputs = torch::tensor( {_input.steering, _input.throttle, _input.braking}, torch::kFloat32); //steer, throtle, brake TorchInputs.push_back(drv_inputs.cuda()); + if (_input.terrain_type > 0) { + TorchInputs.push_back(_input.terrain_type); + } TorchInputs.push_back(_input.verbose); + std::cout << _input.verbose << std::endl; torch::jit::IValue Output; try { diff --git a/LibCarla/source/carla/pytorch/pytorch.h b/LibCarla/source/carla/pytorch/pytorch.h index 63d86f0d4..6ee3f8e6d 100644 --- a/LibCarla/source/carla/pytorch/pytorch.h +++ b/LibCarla/source/carla/pytorch/pytorch.h @@ -24,7 +24,6 @@ namespace learning { float* wheel_oritentation; float* wheel_linear_velocity; float* wheel_angular_velocity; - int terrain_type = 0; }; struct Inputs { @@ -36,6 +35,7 @@ namespace learning { float steering = 0; float throttle = 0; float braking = 0; + int terrain_type = 0; bool verbose = false; }; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.cpp index 86a342fc5..692f3d1f7 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.cpp @@ -475,7 +475,7 @@ FIntVector ALargeMapManager::GetTileVectorID(FVector TileLocation) const { FIntVector VectorId = FIntVector( (TileLocation - - (Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0))) + (Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0) + LocalTileOffset)) / TileSide); VectorId.Y *= -1; return VectorId; @@ -485,7 +485,7 @@ FIntVector ALargeMapManager::GetTileVectorID(FDVector TileLocation) const { FIntVector VectorId = ( (TileLocation - - (Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0))) + (Tile0Offset - FVector(0.5f*TileSide,-0.5f*TileSide, 0) + LocalTileOffset)) / TileSide).ToFIntVector(); VectorId.Y *= -1; return VectorId; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.h index 96fd9ff0d..11161e930 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/MapGen/LargeMapManager.h @@ -290,6 +290,9 @@ protected: UPROPERTY(EditAnywhere, Category = "Large Map Manager") 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") bool ShouldTilesBlockOnLoad = false; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.cpp index 8d7b9506a..36c60dc0b 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.cpp @@ -49,12 +49,37 @@ #define OTHER_LOG(...) #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 static T GetSign(T n) { return n < 0.0f ? -1.0f : 1.0f; } - template static FString EigenToFString(T& t) { @@ -352,6 +377,8 @@ void USpringBasedVegetationComponent::BeginPlay() { ComputeSpringStrengthForBranches(); } + + JointCollisionList.resize(Skeleton.Joints.Num()); } void USpringBasedVegetationComponent::ResetComponent() @@ -603,6 +630,13 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions( std::vector& JointPropertiesList) { TRACE_CPUPROFILER_EVENT_SCOPE(USpringBasedVegetationComponent::ResolveContactsAndCollisions); + + // set all joints that can rest + for (auto &Joint : JointCollisionList) + { + Joint.CanRest = true; + } + for (auto& ActorCapsules : OverlappingActors) { TRACE_CPUPROFILER_EVENT_SCOPE(ActorLoop); @@ -662,6 +696,7 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions( const int JointId = CapsuleToJointId[Capsule]; const FSkeletonJoint& Joint = Skeleton.Joints[JointId]; FJointProperties& JointProperties = JointLocalPropertiesList[Joint.JointId]; + FJointCollision& JointCollision = JointCollisionList[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; @@ -671,10 +706,8 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions( // Contact forces due to spring strength 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 FRotator DeltaRotator = + GetDeltaRotator(CurrRotator, RestRotator); const Eigen::Vector3d SpringTorque = Joint.SpringStrength * RotatorToEigenVector(DeltaRotator); const Eigen::Vector3d JointCapsuleVector = JointGlobalPosition - CapsulePosition; const Eigen::Vector3d RepulsionForce = SpringTorque.cross(JointCapsuleVector) * JointCapsuleVector.squaredNorm(); @@ -691,14 +724,29 @@ void USpringBasedVegetationComponent::ResolveContactsAndCollisions( 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; + // 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); 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); + //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) { // 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( @@ -725,16 +792,26 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion( continue; } FJointProperties& JointProperties = JointPropertiesList[Joint.JointId]; + FJointCollision& JointCollision = JointCollisionList[Joint.JointId]; - // drawing - if (Joint.ParentId != -1 && DebugEnableVisualization) + // debug drawing + if (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); + if (Joint.ParentId != -1) + { + FVector Start = Joint.GlobalTransform.GetLocation(); + 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; Eigen::Vector3d CenterToJoint = JointProperties.CenterOfMass - ToEigenVector(Joint.GlobalTransform.GetLocation())/100.f; Eigen::Matrix3d GlobalToJointMatrix = JointProperties.JointToGlobalMatrix.transpose(); @@ -774,10 +851,14 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion( FRotator CurrRotator = Joint.Transform.Rotator(); FRotator RestRotator = Joint.RestingAngles; FRotator AngularVelocity = Joint.AngularVelocity; - FRotator DeltaRotator ( - CurrRotator.Pitch - RestRotator.Pitch, - CurrRotator.Yaw - RestRotator.Yaw, - CurrRotator.Roll - RestRotator.Roll); + FRotator DeltaRotator = + GetDeltaRotator(CurrRotator, RestRotator); + if (!JointCollision.CanRest) + { + float Factor = 1.0f - ((JointCollision.Iteration / 100.0f) * RestFactor); + // DeltaRotator *= Factor; + AngularVelocity *= Factor; + } Eigen::Vector3d InitialTheta = Uinv*RotatorToEigenVector(DeltaRotator); Eigen::Vector3d InitialThetaVelocity = Uinv*RotatorToEigenVector(AngularVelocity); 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 deltatheta = 0; - double angulavelocity = 0; + double angularvelocity = 0; float angularaccel = 0; if (discriminant > 0) { @@ -812,7 +893,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion( double c1 = (r2*(theta0 - f/k) - dtheta0)/(r2-r1); double c2 = (dtheta0 - c1*r1)/r2; 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); } else if (discriminant == 0) @@ -821,7 +902,7 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion( double c1 = theta0 - f/k; double c2 = dtheta0 - c1*r; 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); } else @@ -833,18 +914,18 @@ void USpringBasedVegetationComponent::SolveEquationOfMotion( deltatheta = c1*std::exp(gamma*DeltaTime)*std::cos(mu*DeltaTime) + 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)) + 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); } - angularaccel = f - b*angulavelocity - k*deltatheta; + angularaccel = f - b*angularvelocity - k*deltatheta; if (!FMath::IsNaN(deltatheta)) { NewTheta(i) = deltatheta; - if (angulavelocity > 1e-4) + if (angularvelocity > 1e-4) { - NewThetaVelocity(i) = angulavelocity; + NewThetaVelocity(i) = angularvelocity; } if (angularaccel > 1e-2) { diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.h index a2c06a116..03b7e32ee 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/SpringBasedVegetationComponent.h @@ -78,6 +78,12 @@ struct FSkeletonJoint FVector ExternalForces = FVector(0,0,0); }; +struct FJointCollision +{ + bool CanRest = true; + int Iteration = 1; +}; + struct FJointProperties { float Mass = 0.0; @@ -202,6 +208,8 @@ private: std::vector& JointPropertiesList); void SolveEquationOfMotion(std::vector& JointPropertiesList, float DeltaTime); + std::vector JointCollisionList; + UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") USkeletalMeshComponent* SkeletalMesh; @@ -232,6 +240,9 @@ private: UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") float VerticalFallof = 0.1f; + UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") + float RestFactor = 0.5f; + UPROPERTY(EditAnywhere, Category = "Spring Based Vegetation Component") float DeltaTimeOverride = -1.f; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/VegetationManager.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/VegetationManager.cpp index 05bb20303..460d85837 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/VegetationManager.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vegetation/VegetationManager.cpp @@ -260,6 +260,12 @@ void AVegetationManager::CreateOrUpdateTileCache(ULevel* InLevel) { ExistingTileData->InstancedFoliageActor = TileData.InstancedFoliageActor; ExistingTileData->ProceduralFoliageVolume = TileData.ProceduralFoliageVolume; + for (FTileMeshComponent& Element : ExistingTileData->TileMeshesCache) + { + Element.InstancedStaticMeshComponent = nullptr; + Element.IndicesInUse.Empty(); + } + ExistingTileData->TileMeshesCache.Empty(); SetTileDataInternals(*ExistingTileData); } else @@ -314,6 +320,8 @@ void AVegetationManager::SetMaterialCache(FTileData& TileData) for (FTileMeshComponent& Element : TileData.TileMeshesCache) { UInstancedStaticMeshComponent* Mesh = Element.InstancedStaticMeshComponent; + if (!IsValid(Mesh)) + continue; int32 Index = -1; for (UMaterialInterface* Material : Mesh->GetMaterials()) { @@ -374,9 +382,13 @@ void AVegetationManager::UpdateFoliageBlueprintCache(ULevel* InLevel) void AVegetationManager::FreeTileCache(ULevel* InLevel) { + if (!IsValid(InLevel)) + return; FTileData TileData {}; for (AActor* Actor : InLevel->Actors) { + if (!IsValid(Actor)) + continue; AInstancedFoliageActor* InstancedFoliageActor = Cast(Actor); if (!IsValid(InstancedFoliageActor)) continue; @@ -596,7 +608,7 @@ void AVegetationManager::OnLevelAddedToWorld(ULevel* InLevel, UWorld* InWorld) void AVegetationManager::OnLevelRemovedFromWorld(ULevel* InLevel, UWorld* InWorld) { TRACE_CPUPROFILER_EVENT_SCOPE(AVegetationManager::OnLevelRemovedFromWorld); - + FreeTileCache(InLevel); } bool AVegetationManager::CheckIfAnyVehicleInLevel() const @@ -609,16 +621,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; } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp index 6260c43dd..d6e766954 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.cpp @@ -4,6 +4,8 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . +#undef CreateDirectory + #include "CustomTerrainPhysicsComponent.h" #include "Runtime/Core/Public/Async/ParallelFor.h" #include "Engine/CollisionProfile.h" @@ -60,8 +62,6 @@ constexpr float MToCM = 100.f; constexpr float CMToM = 0.01f; -static bool bDebugLoadingTiles = false; - const int CacheExtraRadius = 10; #ifdef _WIN32 @@ -90,81 +90,6 @@ FVector UEFrameToSIDirection(const FVector& In) return FVector(In.X, -In.Y, In.Z); } -void FHeightMapData::InitializeHeightmap( - UTexture2D* Texture, FDVector Size, FDVector Origin, - float Min, float Max, FDVector Tile0, float ScaleZ) -{ - Tile0Position = Tile0; - MinHeight = Min; - MaxHeight = Max; - WorldSize = Size; - Offset = Origin; - Pixels.clear(); - - // setup required parameters - Texture->CompressionSettings = TextureCompressionSettings::TC_VectorDisplacementmap; - Texture->SRGB = false; - Texture->UpdateResource(); - - FTexture2DMipMap* TileMipMap = &Texture->PlatformData->Mips[0]; - FByteBulkData* TileRawImageData = &TileMipMap->BulkData; - FColor* FormatedImageData = (FColor*)(TileRawImageData->Lock(LOCK_READ_ONLY)); - Size_X = Texture->GetSizeX(); - Size_Y = Texture->GetSizeY(); - for(uint32_t j = 0; j < Size_Y; j++) - { - for(uint32_t i = 0; i < Size_X; i++) - { - uint32_t idx = j*Size_X + i; - float HeightLevel; - FColor PixelColor = FormatedImageData[idx]; - uint8* HeightLevelPtr = (uint8*) &HeightLevel; - HeightLevelPtr[0] = PixelColor.B; - HeightLevelPtr[1] = PixelColor.G; - HeightLevelPtr[2] = PixelColor.R; - HeightLevelPtr[3] = PixelColor.A; - // HeightLevel = Scale_Z*(MinHeight + (MaxHeight - MinHeight) * FormatedImageData[idx].R/255.f); - Pixels.emplace_back(HeightLevel); - } - } - TileRawImageData->Unlock(); - UE_LOG(LogCarla, Log, - TEXT("Height Map initialized with %d pixels"), Pixels.size()); -} -void FHeightMapData::InitializeHeightmapFloat( - UTexture2D* Texture, FDVector Size, FDVector Origin, - float Min, float Max, FDVector Tile0, float ScaleZ) -{ - Tile0Position = Tile0; - MinHeight = Min; - MaxHeight = Max; - WorldSize = Size; - Offset = Origin; - Pixels.clear(); - // setup required parameters - Texture->CompressionSettings = TextureCompressionSettings::TC_VectorDisplacementmap; - Texture->SRGB = false; - Texture->UpdateResource(); - - FTexture2DMipMap* TileMipMap = &Texture->PlatformData->Mips[0]; - FByteBulkData* TileRawImageData = &TileMipMap->BulkData; - FFloat16Color* FormatedImageData = (FFloat16Color*)(TileRawImageData->Lock(LOCK_READ_ONLY)); - Size_X = Texture->GetSizeX(); - Size_Y = Texture->GetSizeY(); - for(uint32_t j = 0; j < Size_Y; j++) - { - for(uint32_t i = 0; i < Size_X; i++) - { - uint32_t idx = j*Size_X + i; - float HeightLevel = Scale_Z*(MinHeight + (MaxHeight - MinHeight) * FormatedImageData[idx].R.GetFloat()); - Pixels.emplace_back(HeightLevel); - } - } - TileRawImageData->Unlock(); - UE_LOG(LogCarla, Log, - TEXT("Height Map initialized with %d pixels"), Pixels.size()); -} - void FHeightMapData::InitializeHeightmap( UHeightMapDataAsset* DataAsset, FDVector Size, FDVector Origin, FDVector Tile0, float ScaleZ) @@ -199,26 +124,26 @@ void FHeightMapData::Clear() } FDenseTile::FDenseTile(){ - Particles.empty(); - ParticlesHeightMap.empty(); + Particles.clear(); + ParticlesHeightMap.clear(); TilePosition = FDVector(0.0,0.0,0.0); SavePath = FString("NotValidPath"); - bHeightmapNeedToUpdate = false; + bHeightmapNeedToUpdate = true; } FDenseTile::~FDenseTile(){ - Particles.empty(); - ParticlesHeightMap.empty(); - ParticlesZOrdered.empty(); + Particles.clear(); + ParticlesHeightMap.clear(); + ParticlesZOrdered.clear(); TilePosition = FDVector(0.0,0.0,0.0); SavePath = FString("NotValidPath"); - bHeightmapNeedToUpdate = false; + bHeightmapNeedToUpdate = true; } FDenseTile::FDenseTile(const FDenseTile& Origin){ TilePosition = Origin.TilePosition; SavePath = Origin.SavePath; - bHeightmapNeedToUpdate = false; + bHeightmapNeedToUpdate = true; Particles = Origin.Particles; ParticlesHeightMap = Origin.ParticlesHeightMap; ParticlesZOrdered = Origin.ParticlesZOrdered; @@ -227,7 +152,7 @@ FDenseTile::FDenseTile(const FDenseTile& Origin){ FDenseTile::FDenseTile(FDenseTile&& Origin){ TilePosition = Origin.TilePosition; SavePath = Origin.SavePath; - bHeightmapNeedToUpdate = false; + bHeightmapNeedToUpdate = true; Particles = std::move(Origin.Particles); ParticlesHeightMap = std::move(Origin.ParticlesHeightMap); ParticlesZOrdered = std::move(Origin.ParticlesZOrdered); @@ -237,7 +162,7 @@ FDenseTile& FDenseTile::operator=(FDenseTile&& Origin) { TilePosition = Origin.TilePosition; SavePath = Origin.SavePath; - bHeightmapNeedToUpdate = false; + bHeightmapNeedToUpdate = true; Particles = std::move(Origin.Particles); ParticlesHeightMap = std::move(Origin.ParticlesHeightMap); ParticlesZOrdered = std::move(Origin.ParticlesZOrdered); @@ -250,7 +175,6 @@ void FDenseTile::InitializeTile(uint32_t TextureSize, float AffectedRadius, floa { uint32_t TileSize = (TileEnd.X - TileOrigin.X ); - // uint32_t PartialHeightMapSize = TextureSize / ( (AffectedRadius * 2) / TileSize); uint32_t PartialHeightMapSize = TileSize * TextureSize / (2*AffectedRadius); std::string FileName = std::string(TCHAR_TO_UTF8(*( SavePath + TileOrigin.ToString() + ".tile" ) ) ); @@ -263,7 +187,6 @@ void FDenseTile::InitializeTile(uint32_t TextureSize, float AffectedRadius, floa ReadFVector(ReadStream, VectorToRead ); TilePosition = FDVector(VectorToRead); ReadStdVector (ReadStream, Particles); - ReadStdVector (ReadStream, ParticlesHeightMap); //UE_LOG(LogCarla, Log, TEXT("Reading data, got %d particles"), Particles.size()); } else @@ -297,15 +220,15 @@ void FDenseTile::InitializeTile(uint32_t TextureSize, float AffectedRadius, floa } } - UE_LOG(LogCarla, Log, TEXT("Building local heightMap of %d pixels"), PartialHeightMapSize); - for(float& Height : ParticlesHeightMap) - { - Height = 0; - } + //UE_LOG(LogCarla, Log, TEXT("Building local heightMap of %d pixels"), PartialHeightMapSize); - //UE_LOG(LogCarla, Log, TEXT("Initialized, got %d particles"), Particles.size()); - //UE_LOG(LogCarla, Log, TEXT("Initialized ParticlesHeightMap, got %d particles"), ParticlesHeightMap.size()); } + ParticlesHeightMap.resize( PartialHeightMapSize*PartialHeightMapSize ); + for(float& Height : ParticlesHeightMap) + { + Height = 0; + } + { TRACE_CPUPROFILER_EVENT_SCOPE(DenseTile::InitializeTile::ParticlesZOrdered); ParticlesZOrdered.resize( PartialHeightMapSize*PartialHeightMapSize ); @@ -316,27 +239,19 @@ void FDenseTile::InitializeTile(uint32_t TextureSize, float AffectedRadius, floa const FParticle& P = Particles[i]; FDVector ParticleLocalPosition = P.Position - TilePosition; // Recalculate position to get it into heightmap coords - // ParticleLocalPosition.X *= ( Transformation ); - // ParticleLocalPosition.Y *= ( Transformation ); FIntVector HeightMapCoords = FIntVector( ParticleLocalPosition.X * Transformation, ParticleLocalPosition.Y * Transformation, 0); - // uint32_t Index = std::floor(ParticleLocalPosition.Y) * PartialHeightMapSize + std::floor(ParticleLocalPosition.X); uint32_t Index = HeightMapCoords.Y * PartialHeightMapSize + HeightMapCoords.X; // Compare to the current value, if higher replace - if( Index < ParticlesZOrdered.size() ){ + if(Index < ParticlesZOrdered.size() ){ ParticlesZOrdered[Index].insert(P.Position.Z); - }else{ - /* - UE_LOG(LogCarla, Log, TEXT("Invalid Index on Z order %d, Size %d"), Index,ParticlesZOrdered.size() ); - UE_LOG(LogCarla, Log, TEXT("ParticleLocalPosition X: %f, Y %f"), ParticleLocalPosition.X, ParticleLocalPosition.Y); - UE_LOG(LogCarla, Log, TEXT("FParticle X: %f, Y %f"), P.Position.X, P.Position.Y); - UE_LOG(LogCarla, Log, TEXT("TilePosition X: %f, Y %f"), TilePosition.X, TilePosition.Y); - */ } } } + + bHeightmapNeedToUpdate = true; } @@ -396,9 +311,16 @@ void FDenseTile::UpdateLocalHeightmap() TRACE_CPUPROFILER_EVENT_SCOPE(FDenseTile::UpdateLocalHeightmap); if( bHeightmapNeedToUpdate ){ for( uint32_t i = 0; i < ParticlesHeightMap.size() ; ++i ){ - auto it = ParticlesZOrdered[i].begin(); - ParticlesHeightMap[i] = *it; + if( ParticlesZOrdered.size() == ParticlesHeightMap.size() ){ + auto it = ParticlesZOrdered[i].begin(); + ParticlesHeightMap[i] = *it; + }else{ + UE_LOG(LogCarla, Log, TEXT("ParticlesZOrdered is not correct sized %d Heightmap size %d"), ParticlesZOrdered.size(), ParticlesHeightMap.size() ); + } } + }else{ + UE_LOG(LogCarla, Log, TEXT("Not updated") ); + } } @@ -643,6 +565,10 @@ std::vector FSparseHighDetailMap::GetLoadedTilesInRange(FDVector Posit MaxX = Tile_X + RadiusInTiles; MaxY = Tile_Y + RadiusInTiles; } + + //UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::GetLoadedTilesInRange Position X: %f, Y %f"), Position.X, Position.Y); + //UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::GetLoadedTilesInRange Loading Tiles Between X: %d %d Y: %d %d "), MinX, MaxX, MinY, MaxY ); + std::vector LoadedTiles; { TRACE_CPUPROFILER_EVENT_SCOPE(Looping); @@ -844,39 +770,6 @@ FDenseTile& FSparseHighDetailMap::InitializeRegionInCache(uint64_t TileId) return Tile; } -void FSparseHighDetailMap::InitializeMap(UTexture2D* HeightMapTexture, - FDVector Origin, FDVector MapSize, float Size, float MinHeight, float MaxHeight, - float ScaleZ) -{ - Tile0Position = Origin; - TileSize = Size; - Extension = MapSize; - EPixelFormat TexFormat = HeightMapTexture->GetPixelFormat(0); - if(TexFormat == PF_B8G8R8A8 || TexFormat == PF_G8 || TexFormat == PF_DXT5) - { - UE_LOG(LogCarla, Log, - TEXT("Using 8 bit height map, pixel format %d"), TexFormat); - Heightmap.InitializeHeightmap( - HeightMapTexture, Extension, Tile0Position, - MinHeight, MaxHeight, Tile0Position, ScaleZ); - } - else if (TexFormat == PF_FloatRGB || TexFormat == PF_FloatRGBA || - TexFormat == PF_G16) - { - UE_LOG(LogCarla, Log, - TEXT("Using 16 bit height map, pixel format %d"), TexFormat); - Heightmap.InitializeHeightmapFloat( - HeightMapTexture, Extension, Tile0Position, - MinHeight, MaxHeight, Tile0Position, ScaleZ); - } - else - { - UE_LOG(LogCarla, Error, - TEXT("Unrecofnized pixel format %d"), TexFormat); - } - UE_LOG(LogCarla, Log, - TEXT("Sparse Map initialized")); -} void FSparseHighDetailMap::InitializeMap(UHeightMapDataAsset* DataAsset, FDVector Origin, FDVector MapSize, float Size, float ScaleZ) { @@ -894,18 +787,6 @@ void FSparseHighDetailMap::InitializeMap(UHeightMapDataAsset* DataAsset, TEXT("Map Extension %f %f %f"), MapSize.X, MapSize.Y, MapSize.Z ); } -void FSparseHighDetailMap::UpdateHeightMap(UTexture2D* HeightMapTexture, - FDVector Origin, FDVector MapSize, float Size, float MinHeight, float MaxHeight, - float ScaleZ) -{ - Heightmap.Clear(); - Heightmap.InitializeHeightmap( - HeightMapTexture, Extension, Origin, - MinHeight, MaxHeight, Origin, ScaleZ); - UE_LOG(LogCarla, Log, - TEXT("Height map updated")); -} - void FSparseHighDetailMap::UpdateHeightMap(UHeightMapDataAsset* DataAsset, FDVector Origin, FDVector MapSize, float Size, float ScaleZ) @@ -940,12 +821,12 @@ void FSparseHighDetailMap::UpdateMaps( FIntVector CacheMaxVector = GetVectorTileId( FDVector(Position.X + CacheRadiusX, Position.Y + CacheRadiusY, 0)); - auto IsInCacheRange = [&](uint32_t Tile_X, uint32_t Tile_Y) -> bool + auto IsInCacheRange = [&](int32_t Tile_X, int32_t Tile_Y) -> bool { return Tile_X >= CacheMinVector.X && Tile_X <= CacheMaxVector.X && Tile_Y >= CacheMinVector.Y && Tile_Y <= CacheMaxVector.Y; }; - auto IsInMapRange = [&](uint32_t Tile_X, uint32_t Tile_Y) -> bool + auto IsInMapRange = [&](int32_t Tile_X, int32_t Tile_Y) -> bool { return Tile_X >= MinVector.X && Tile_X <= MaxVector.X && Tile_Y >= MinVector.Y && Tile_Y <= MaxVector.Y; @@ -956,9 +837,9 @@ void FSparseHighDetailMap::UpdateMaps( TRACE_CPUPROFILER_EVENT_SCOPE(UpdateMap); // load tiles to map std::vector TilesToInitialize; - for(uint32_t Tile_X = MinVector.X; Tile_X < MaxVector.X; ++Tile_X ) + for(int32_t Tile_X = MinVector.X; Tile_X < MaxVector.X; ++Tile_X ) { - for(uint32_t Tile_Y = MinVector.Y; Tile_Y < MaxVector.Y; ++Tile_Y ) + for(int32_t Tile_Y = MinVector.Y; Tile_Y < MaxVector.Y; ++Tile_Y ) { uint64_t CurrentTileID = GetTileId(Tile_X, Tile_Y); if (Map.find(CurrentTileID) == Map.end()) @@ -1002,9 +883,9 @@ void FSparseHighDetailMap::UpdateMaps( { FScopeLock ScopeCacheLock(&Lock_CacheMap); TRACE_CPUPROFILER_EVENT_SCOPE(UpdateCache); - for(uint32_t Tile_X = CacheMinVector.X; Tile_X < CacheMaxVector.X; ++Tile_X ) + for(int32_t Tile_X = CacheMinVector.X; Tile_X < CacheMaxVector.X; ++Tile_X ) { - for(uint32_t Tile_Y = CacheMinVector.Y; Tile_Y < CacheMaxVector.Y; ++Tile_Y ) + for(int32_t Tile_Y = CacheMinVector.Y; Tile_Y < CacheMaxVector.Y; ++Tile_Y ) { if (IsInMapRange(Tile_X, Tile_Y)) { @@ -1059,148 +940,6 @@ void FSparseHighDetailMap::UpdateMaps( } -void FSparseHighDetailMap::LoadTilesAtPositionFromCache(FDVector Position, float RadiusX , float RadiusY ) -{ - // Translate UE4 Position to our coords - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::LoadTilesAtPosition); - - // double MinX = std::min( std::max( Position.X - RadiusX, 0.0) , Extension.X - 1.0); - // double MinY = std::min( std::max( Position.Y - RadiusY, 0.0) , -Extension.Y + 1.0); - // double MaxX = std::min( std::max( Position.X + RadiusX, 0.0) , Extension.X - 1.0); - // double MaxY = std::min( std::max( Position.Y + RadiusY, 0.0) , -Extension.Y + 1.0); - double MinX = Position.X - RadiusX; - double MinY = Position.Y - RadiusY; - double MaxX = Position.X + RadiusX; - double MaxY = Position.Y + RadiusY; - - FIntVector MinVector = GetVectorTileId(FDVector(MinX, MinY, 0)); - FIntVector MaxVector = GetVectorTileId(FDVector(MaxX, MaxY, 0)); - - FIntVector CacheMinVector = GetVectorTileId(FDVector(MinX - CacheExtraRadius, MinY - CacheExtraRadius, 0)); - FIntVector CacheMaxVector = GetVectorTileId(FDVector(MaxX + CacheExtraRadius, MaxY + CacheExtraRadius, 0)); - - if( bDebugLoadingTiles ){ - static FDateTime CurrentTime = FDateTime::Now(); - if( ( FDateTime::Now() - CurrentTime).GetTotalSeconds() > 20.0f ) - { - UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::LoadTilesAtPositionFromCache Position X: %f, Y %f"), Position.X, Position.Y); - UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::LoadTilesAtPositionFromCache Loading Tiles Between X: %d %d Y: %d %d "), MinVector.X, MaxVector.X, MinVector.Y, MaxVector.Y ); - UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::LoadTilesAtPositionFromCache Cache Tiles Between X: %d %d Y: %d %d "), CacheMinVector.X, CacheMaxVector.X, CacheMinVector.Y, CacheMaxVector.Y ); - //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::LoadTilesAtPositionFromCache Extension X: %f, Y %f"), Extension.X, Extension.Y); - //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::LoadTilesAtPositionFromCache Before MapSize : %d"), Map.size() ); - CurrentTime = FDateTime::Now(); - } - } - - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::LoadTilesAtPosition::Process); - for(uint32_t CacheX = CacheMinVector.X; CacheX < CacheMaxVector.X; CacheX++ ) - { - for(uint32_t CacheY = CacheMinVector.Y; CacheY < CacheMaxVector.Y; CacheY++ ) - { - uint64_t CurrentTileID = GetTileId(CacheX, CacheY); - if( Map.find(CurrentTileID) == Map.end() ) - { - if ( MinVector.X <= CacheX && CacheX <= MaxVector.X && MinVector.Y <= CacheY && CacheY <= MaxVector.Y ) - { - FDenseTile NewTile; - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::LoadTilesAtPosition::Insert); - // FScopeLock ScopeLock(&Lock_Map); - // FScopeLock ScopeCacheLock(&Lock_CacheMap); - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::LoadTilesAtPosition::Insert::Emplace); - Map.emplace(CurrentTileID, std::move( CacheMap[CurrentTileID] ) ); - } - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::LoadTilesAtPosition::Insert::Erase); - CacheMap.erase(CurrentTileID); - } - } - } - } - } - } -} - -void FSparseHighDetailMap::ReloadCache(FDVector Position, float RadiusX , float RadiusY ) -{ - // Translate UE4 Position to our coords - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::ReloadCache); - std::unordered_set KeysToRemove; - std::unordered_set KeysToLoad; - - double MinX = std::min( std::max( Position.X - RadiusX, 0.0) , Extension.X - 1.0); - double MinY = std::min( std::max( Position.Y - RadiusY, 0.0) , -Extension.Y + 1.0); - double MaxX = std::min( std::max( Position.X + RadiusX, 0.0) , Extension.X - 1.0); - double MaxY = std::min( std::max( Position.Y + RadiusY, 0.0) , -Extension.Y + 1.0); - - FIntVector MinVector = GetVectorTileId(FDVector(MinX, MinY, 0)); - FIntVector MaxVector = GetVectorTileId(FDVector(MaxX, MaxY, 0)); - - FIntVector CacheMinVector = GetVectorTileId(FDVector(MinX - RadiusX * 2, MinY - RadiusY * 2, 0)); - FIntVector CacheMaxVector = GetVectorTileId(FDVector(MaxX + RadiusX * 2, MaxY + RadiusY * 2, 0)); - - UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::ReloadCache Position X: %f, Y %f"), Position.X, Position.Y); - //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::ReloadCache Extension X: %f, Y %f"), Extension.X, Extension.Y); - UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::ReloadCache Loading Tiles Between X: %d %d Y: %d %d "), MinVector.X, MaxVector.X, MinVector.Y, MaxVector.Y ); - - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::ReloadCache::Process); - for(uint32_t CacheX = CacheMinVector.X; CacheX < CacheMaxVector.X; CacheX++ ) - { - for(uint32_t CacheY = CacheMinVector.Y; CacheY < CacheMaxVector.Y; CacheY++ ) - { - uint64_t CurrentTileID = GetTileId(CacheX, CacheY); - if( Map.find(CurrentTileID) != Map.end() ) - { - if ( MinVector.X <= CacheX && CacheX <= MaxVector.X && MinVector.Y <= CacheY && CacheY <= MaxVector.Y ) - { - - }else{ - KeysToRemove.insert( CurrentTileID ); - } - }else{ - if ( MinVector.X <= CacheX && CacheX <= MaxVector.X && MinVector.Y <= CacheY && CacheY <= MaxVector.Y ) - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::ReloadCache::Insert); - FScopeLock ScopeCacheLock(&Lock_CacheMap); - KeysToLoad.insert(CurrentTileID); - CacheMap.emplace(CurrentTileID, FDenseTile() ); - } - } - } - } - } - - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::ReloadCache::Load); - std::vector KeysToBeLoaded; - KeysToBeLoaded.insert(KeysToBeLoaded.end(), KeysToLoad.begin(), KeysToLoad.end()); - - ParallelFor(KeysToBeLoaded.size(), [&](int32 Idx) - { - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::ReloadCache::LoadOne); - InitializeRegionInCache(KeysToBeLoaded[Idx]); - }); - } - - { - FScopeLock ScopeLock(&Lock_CacheMap); - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::ReloadCache::Save); - for(auto it : KeysToRemove) - { - //UE_LOG(LogCarla, Log, TEXT("Offlloading tile id %llu, (%f, %f) (%f, %f)"), it, MinX, MinY, MaxX, MaxY); - std::string FileToSavePath = std::string(TCHAR_TO_UTF8(*( SavePath + CacheMap[it].TilePosition.ToString() + ".tile"))); - std::ofstream OutputStream(FileToSavePath.c_str()); - WriteFVector(OutputStream, CacheMap[it].TilePosition.ToFVector()); - WriteStdVector (OutputStream, CacheMap[it].Particles); - WriteStdVector (OutputStream, CacheMap[it].ParticlesHeightMap); - OutputStream.close(); - CacheMap.erase(it); - } - } -} - void FSparseHighDetailMap::Update(FVector Position, float RadiusX, float RadiusY) { FVector PositionTranslated; @@ -1219,9 +958,9 @@ void FSparseHighDetailMap::Update(FVector Position, float RadiusX, float RadiusY { TRACE_CPUPROFILER_EVENT_SCOPE(TEXT("FSparseHighDetailMap::WaitUntilProperTilesAreLoaded")); - for(uint32_t X = MinVector.X; X < MaxVector.X; X++ ) + for(int32_t X = MinVector.X; X < MaxVector.X; X++ ) { - for(uint32_t Y = MinVector.Y; Y < MaxVector.Y; Y++ ) + for(int32_t Y = MinVector.Y; Y < MaxVector.Y; Y++ ) { bool ConditionToStopWaiting = true; // Check if tiles are already loaded @@ -1235,27 +974,10 @@ void FSparseHighDetailMap::Update(FVector Position, float RadiusX, float RadiusY ConditionToStopWaiting = Map.find(CurrentTileID) == Map.end(); } - if(ConditionToStopWaiting) { - bDebugLoadingTiles = true; - FGenericPlatformProcess::Sleep(0.0001f); - static FDateTime CurrentTime = FDateTime::Now(); - if( ( FDateTime::Now() - CurrentTime).GetTotalSeconds() > 5.0f ) - { - UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::Update PositionToUpdate X: %f, Y %f"), PositionToUpdate.X, PositionToUpdate.Y); - UE_LOG(LogCarla, Warning, TEXT("FSparseHighDetailMap::Update Waiting Tiles Between X: %d %d Y: %d %d "), MinVector.X, MaxVector.X, MinVector.Y, MaxVector.Y ); - /* - UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::Update Position X: %f, Y %f"), Position.X, Position.Y); - UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::Update PositionTranslated X: %f, Y %f"), PositionTranslated.X, PositionTranslated.Y); - UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::Update Extension X: %f, Y %f"), Extension.X, Extension.Y); - */ - CurrentTime = FDateTime::Now(); - } - } } } } } - bDebugLoadingTiles = false; } @@ -1263,30 +985,32 @@ void FSparseHighDetailMap::SaveMap() { UE_LOG(LogCarla, Warning, TEXT("Save directory %s"), *SavePath ); TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::SaveMap); - for(auto& it: Map) + ParallelFor(Map.size(), [this](int32 Idx) { - std::string FileToSavePath = std::string(TCHAR_TO_UTF8(*( SavePath + it.second.TilePosition.ToString() + ".tile"))); + std::pair it = *(std::next(this->Map.begin(), Idx) ); + std::string FileToSavePath = std::string(TCHAR_TO_UTF8(*( this->SavePath + it.second.TilePosition.ToString() + ".tile"))); std::ofstream OutputStream(FileToSavePath.c_str()); WriteFVector(OutputStream, it.second.TilePosition.ToFVector()); WriteStdVector (OutputStream, it.second.Particles); WriteStdVector (OutputStream, it.second.ParticlesHeightMap); OutputStream.close(); - } - for(auto& it: CacheMap) + }); + + ParallelFor(CacheMap.size(), [this](int32 Idx) { - std::string FileToSavePath = std::string(TCHAR_TO_UTF8(*( SavePath + it.second.TilePosition.ToString() + ".tile"))); + std::pair it = *(std::next(this->CacheMap.begin(), Idx) ); + std::string FileToSavePath = std::string(TCHAR_TO_UTF8(*( this->SavePath + it.second.TilePosition.ToString() + ".tile"))); std::ofstream OutputStream(FileToSavePath.c_str()); WriteFVector(OutputStream, it.second.TilePosition.ToFVector()); WriteStdVector (OutputStream, it.second.Particles); WriteStdVector (OutputStream, it.second.ParticlesHeightMap); - OutputStream.close(); - } + }); + } void UCustomTerrainPhysicsComponent::UpdateTexture() { - // UpdateTextureData(); UpdateLoadedTextureDataRegions(); ENQUEUE_RENDER_COMMAND(UpdateDynamicTextureCode) @@ -1312,29 +1036,32 @@ void UCustomTerrainPhysicsComponent::InitTexture(){ if( Data.Num() == 0 && TextureToUpdate ){ float LimitX = TextureToUpdate->GetSizeX(); float LimitY = TextureToUpdate->GetSizeY(); - Data.Init(0, LimitX * LimitY); + Data.Init(128, LimitX * LimitY); } if( LargeData.Num() == 0 && LargeTextureToUpdate ){ float LimitX = LargeTextureToUpdate->GetSizeX(); float LimitY = LargeTextureToUpdate->GetSizeY(); - LargeData.Init(0, LimitX * LimitY); + LargeData.Init(128, LimitX * LimitY); } } void UCustomTerrainPhysicsComponent::UpdateLoadedTextureDataRegions() { TRACE_CPUPROFILER_EVENT_SCOPE("UCustomTerrainPhysicsComponent::UpdateLoadedTextureDataRegions"); - FDVector TextureCenterPosition = UEFrameToSI(LastUpdatedPosition); + if (TextureToUpdate->GetSizeX() == 0) return; + + + FDVector TextureCenterPosition = UEFrameToSI(GetTileCenter(LastUpdatedPosition)); std::vector LoadedTiles = - SparseMap.GetLoadedTilesInRange(TextureCenterPosition, TextureRadius); + SparseMap.GetLoadedTilesInRange(TextureCenterPosition, UEFrameToSI(TileRadius.X) ); FDVector TextureOrigin = TextureCenterPosition - FDVector(TextureRadius, TextureRadius, 0); - float GlobalTexelSize = std::round( ( (2.0f * TextureRadius) / TextureToUpdate->GetSizeX() ) * 10000.0f) / 10000.0f; - uint32_t PartialHeightMapSize = std::round( SparseMap.GetTileSize() * TextureToUpdate->GetSizeX() / (2*TextureRadius) ); + float GlobalTexelSize = (2.0f * TextureRadius) / TextureToUpdate->GetSizeX(); + int32_t PartialHeightMapSize = std::floor( SparseMap.GetTileSize() * TextureToUpdate->GetSizeX() / (2*TextureRadius) ); float LocalTexelSize = SparseMap.GetTileSize() / PartialHeightMapSize; - LocalTexelSize = std::round( LocalTexelSize * 1000.0f ) / 1000.0f; + LocalTexelSize = std::floor( LocalTexelSize * 1000.0f ) / 1000.0f; for(uint8_t &Value : Data) { @@ -1345,19 +1072,19 @@ void UCustomTerrainPhysicsComponent::UpdateLoadedTextureDataRegions() { FDenseTile& CurrentTile = SparseMap.GetTile(TileId); FDVector& TilePosition = CurrentTile.TilePosition; - for (uint32_t Local_Y = 0; Local_Y < PartialHeightMapSize; ++Local_Y) + for (int32_t Local_Y = 0; Local_Y < PartialHeightMapSize; ++Local_Y) { - for (uint32_t Local_X = 0; Local_X < PartialHeightMapSize; ++Local_X) + for (int32_t Local_X = 0; Local_X < PartialHeightMapSize; ++Local_X) { - uint32_t LocalIndex = Local_Y * PartialHeightMapSize + Local_X; - float Height = CurrentTile.ParticlesHeightMap[LocalIndex]; + int32_t LocalIndex = Local_Y * PartialHeightMapSize + Local_X; + float Height = *(CurrentTile.ParticlesZOrdered[LocalIndex].begin()); FDVector LocalTexelPosition = TilePosition + FDVector(Local_X*LocalTexelSize, Local_Y*LocalTexelSize, 0); - uint32_t Coord_X = std::round( (LocalTexelPosition.X - TextureOrigin.X ) / GlobalTexelSize ); - uint32_t Coord_Y = std::round( (LocalTexelPosition.Y - TextureOrigin.Y ) / GlobalTexelSize ); + int32_t Coord_X = std::floor( (LocalTexelPosition.X - TextureOrigin.X ) / GlobalTexelSize ); + int32_t Coord_Y = std::floor( (LocalTexelPosition.Y - TextureOrigin.Y ) / GlobalTexelSize ); - if (Coord_X >= 0 && Coord_X < TextureToUpdate->GetSizeX() && - Coord_Y >= 0 && Coord_Y < TextureToUpdate->GetSizeY()) + if ( Coord_X >= 0 && Coord_X < TextureToUpdate->GetSizeX() && + Coord_Y >= 0 && Coord_Y < TextureToUpdate->GetSizeY() ) { float OriginalHeight = SparseMap.GetHeight(LocalTexelPosition); float Displacement = Height - OriginalHeight; @@ -1372,62 +1099,6 @@ void UCustomTerrainPhysicsComponent::UpdateLoadedTextureDataRegions() } } -void UCustomTerrainPhysicsComponent::UpdateTextureData() -{ - uint32_t NumberOfParticlesIn1AxisInHeightmap = TextureToUpdate->GetSizeX() / (TextureRadius * 2); - std::vector ParticlesPositions; - { - TRACE_CPUPROFILER_EVENT_SCOPE(TEXT("UCustomTerrainPhysicsComponent::UpdateTextureData::GettingHeightMaps")); - ParticlesPositions = SparseMap.GetParticlesHeightMapInTileRadius(UEFrameToSI(LastUpdatedPosition), TextureRadius); - //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::UpdateTextureData OriginPosition X: %f, Y %f"), OriginPosition.X, OriginPosition.Y); - } - - { - TRACE_CPUPROFILER_EVENT_SCOPE(TEXT("UCustomTerrainPhysicsComponent::UpdateTextureData")); - - uint32_t LimitX = TextureToUpdate->GetSizeX() - 1; - uint32_t LimitY = TextureToUpdate->GetSizeY() - 1; - uint32_t OffsetAbsolutX = 0; - uint32_t OffsetAbsolutY = 0; - uint32_t LocalOffset = 0; - uint32_t NumberOfTexturesMiniHeightMaps = (TextureRadius * 2) / TileSize; - //UE_LOG(LogCarla, Log, TEXT("Data : %d, ParticlesPositions %d"), Data.Num(), ParticlesPositions.size() ); - //UE_LOG(LogCarla, Log, TEXT("LimitX : %d, LimitY %d"), LimitX, LimitY ); - - while( OffsetAbsolutY < NumberOfTexturesMiniHeightMaps ) - { - for(uint32_t y = 0; y < NumberOfParticlesIn1AxisInHeightmap; y++) - { - for(uint32_t x = 0; x < NumberOfParticlesIn1AxisInHeightmap; x++) - { - uint32_t AbsolutIndex = (OffsetAbsolutX * NumberOfParticlesIn1AxisInHeightmap) + x + (LimitX * ( (OffsetAbsolutY * NumberOfParticlesIn1AxisInHeightmap) + y) ); - uint32_t LocalIndex = x + y * NumberOfParticlesIn1AxisInHeightmap; - if ( Data.IsValidIndex(AbsolutIndex) && LocalIndex + LocalOffset < ParticlesPositions.size() ) - { - //Data[AbsolutIndex] = 127; - Data[AbsolutIndex] = ParticlesPositions[LocalIndex + LocalOffset] + 127; - }else{ - /* - UE_LOG(LogCarla, Log, TEXT("Invalid Indices AbsolutIndex %d LocalIndex + LocalOffset %d"), AbsolutIndex, LocalIndex + LocalOffset); - UE_LOG(LogCarla, Log, TEXT("Sized Data: %d ParticlesPositions %d"), Data.Num(), ParticlesPositions.size() ); - UE_LOG(LogCarla, Log, TEXT("OffsetAbsolutY : %d, OffsetAbsolutX %d"), OffsetAbsolutY, OffsetAbsolutX ); - UE_LOG(LogCarla, Log, TEXT("x : %d, y %d"), x, y ); - UE_LOG(LogCarla, Log, TEXT("NumberOfTexturesMiniHeightMaps: %d"), NumberOfTexturesMiniHeightMaps ); - */ - } - } - } - LocalOffset += (TextureToUpdate->GetSizeX() / NumberOfParticlesIn1AxisInHeightmap) * (TextureToUpdate->GetSizeY() / NumberOfParticlesIn1AxisInHeightmap) ; - OffsetAbsolutX++; - if(OffsetAbsolutX >= NumberOfTexturesMiniHeightMaps ) - { - OffsetAbsolutX = 0; - OffsetAbsolutY++; - } - } - } -} - void UCustomTerrainPhysicsComponent::UpdateLargeTexture() { UpdateLargeTextureData(); @@ -1468,8 +1139,8 @@ void UCustomTerrainPhysicsComponent::UpdateLargeTextureData() //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::UpdateTextureData OriginPosition X: %f, Y %f"), OriginPosition.X, OriginPosition.Y); } - uint32_t OffsetX = 0; - uint32_t OffsetY = 0; + int32_t OffsetX = 0; + int32_t OffsetY = 0; float* Ptr = &ParticlesPositions[0]; while( OffsetY < LargeTextureToUpdate->GetSizeY() ) { @@ -1527,10 +1198,11 @@ void UCustomTerrainPhysicsComponent::BeginPlay() bShowForces = true; bBenchMark = false; bDrawHeightMap = false; - ForceMulFactor = 1.0; + ForceMulFactor = 1.f; + ParticleForceMulFactor = 1.f; FloorHeight = 0.0; bDrawLoadedTiles = false; - + bUseSoilType = false; #endif int IntValue; @@ -1571,6 +1243,10 @@ void UCustomTerrainPhysicsComponent::BeginPlay() { ForceMulFactor = Value; } + if (FParse::Value(FCommandLine::Get(), TEXT("-particle-force-mul-factor="), Value)) + { + ParticleForceMulFactor = Value; + } if (FParse::Value(FCommandLine::Get(), TEXT("-max-force="), Value)) { MaxForceMagnitude = MToCM*Value; @@ -1622,6 +1298,10 @@ void UCustomTerrainPhysicsComponent::BeginPlay() { NNVerbose = false; } + if (FParse::Param(FCommandLine::Get(), TEXT("-use-terrain-type"))) + { + bUseSoilType = true; + } if (FParse::Param(FCommandLine::Get(), TEXT("-use-impulse"))) { bUseImpulse = true; @@ -1706,17 +1386,6 @@ void UCustomTerrainPhysicsComponent::BeginPlay() } } - - // UpdateMaps(FVector(100,100, 0), TileRadius.X, TileRadius.Y, CacheRadius.X, CacheRadius.Y); - // IterationCompleted.Reset(); - // IterationCompleted = Async(EAsyncExecution::LargeThreadPool, - // [&]() - // { - // UpdateMaps(FVector(100,100, 0), TileRadius.X, TileRadius.Y, CacheRadius.X, CacheRadius.Y); - // return true; - // }); - // ReloadCache(FVector(100,100, 0), CacheRadius.X, CacheRadius.Y ); - // LoadTilesAtPosition(FVector(100,100, 0), TileRadius.X, TileRadius.Y ); InitTexture(); UE_LOG(LogCarla, Log, TEXT("MainThread Data ArraySize %d "), Data.Num()); @@ -1730,28 +1399,6 @@ void UCustomTerrainPhysicsComponent::BeginPlay() } -TArray UCustomTerrainPhysicsComponent::BuildLandscapeHeightMap(ALandscapeProxy* Landscape, int Resolution) -{ - TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::BuildLandscapeHeightMap); - TArray HeightMap; - HeightMap.Reserve(Resolution*Resolution); - FVector Origin = Landscape->GetActorLocation(); - float DeltaX = WorldSize.X; - float DeltaY = WorldSize.Y; - for (size_t i = 0; i < Resolution; ++i) - { - float PosX = Origin.X + i*DeltaX; - for (size_t j = 0; j < Resolution; ++j) - { - float PosY = Origin.Y + j*DeltaY; - FVector Location = FVector(PosX, PosY, 0); - float Height = Landscape->GetHeightAtLocation(Location).Get(-1); - HeightMap.Emplace(Height); - } - } - return HeightMap; -} - void UCustomTerrainPhysicsComponent::BuildLandscapeHeightMapDataAasset(ALandscapeProxy* Landscape, int Resolution, FVector MapSize, FString AssetPath, FString AssetName) { @@ -1823,15 +1470,16 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, TArray VehiclesActors; UGameplayStatics::GetAllActorsOfClass(GetWorld(), ACarlaWheeledVehicle::StaticClass(), VehiclesActors); - + for (AActor* VehicleActor : VehiclesActors) { + ACarlaWheeledVehicle* Vehicle = Cast (VehicleActor); FVector GlobalLocation = Vehicle->GetActorLocation(); if(LargeMapManager) { - GlobalLocation = - LargeMapManager->LocalToGlobalLocation(Vehicle->GetActorLocation()); + GlobalLocation = LargeMapManager->LocalToGlobalLocation(Vehicle->GetActorLocation()); + uint64_t TileId = LargeMapManager->GetTileID(GlobalLocation); FIntVector CurrentTileId = LargeMapManager->GetTileVectorID(GlobalLocation); @@ -1839,7 +1487,7 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, { //load new height map FCarlaMapTile* LargeMapTile = LargeMapManager->GetCarlaMapTile(TileId); - if(LargeMapTile && false) + if(LargeMapTile) { CurrentLargeMapTileId = CurrentTileId; FString FullTileNamePath = LargeMapTile->Name; @@ -1876,53 +1524,10 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, } } } - { - // TRACE_CPUPROFILER_EVENT_SCOPE(WaitForMap); - // IterationCompleted.Wait(); - // bool bIterationFinished = IterationCompleted.Get(); - } - // SparseMap.Update(LastUpdatedPosition, TextureRadius, TextureRadius ); + SparseMap.LockMutex(); RunNNPhysicsSimulation(Vehicle, DeltaTime); - // if(bUpdateParticles) - // { - // { - // TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::DebugToBeRemoved); - // std::vector ParticlesWheel0; - // std::vector ParticlesWheel1; - // std::vector ParticlesWheel2; - // std::vector ParticlesWheel3; - - // { - // TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::RemoveParticles); - // RemoveParticlesFromOrderedContainer( ParticlesWheel0 ); - // RemoveParticlesFromOrderedContainer( ParticlesWheel1 ); - // RemoveParticlesFromOrderedContainer( ParticlesWheel2 ); - // RemoveParticlesFromOrderedContainer( ParticlesWheel3 ); - // } - // { - // TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::UpdateParticles); - // UpdateParticlesDebug( ParticlesWheel1 ); - // UpdateParticlesDebug( ParticlesWheel2 ); - // UpdateParticlesDebug( ParticlesWheel0 ); - // UpdateParticlesDebug( ParticlesWheel3 ); - // } - - // { - // TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::AddParticles); - // AddParticlesToOrderedContainer( ParticlesWheel0 ); - // AddParticlesToOrderedContainer( ParticlesWheel1 ); - // AddParticlesToOrderedContainer( ParticlesWheel2 ); - // AddParticlesToOrderedContainer( ParticlesWheel3 ); - // } - - // { - // TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::UpdateTilesHeightMaps); - // UpdateTilesHeightMapsInRadius(LastUpdatedPosition, 4); - // } - // } - // } LastUpdatedPosition = GlobalLocation; UpdateTexture(); @@ -1933,14 +1538,6 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, DrawTiles(GetWorld(), SparseMap.GetTileIdInCache(), GlobalLocation.Z + 300, FLinearColor(1.0,0.0,0.0,0.0)); } SparseMap.UnLockMutex(); - // UpdateMaps(LastUpdatedPosition, TileRadius.X, TileRadius.Y, CacheRadius.X, CacheRadius.Y); - // IterationCompleted.Reset(); - // IterationCompleted = Async(EAsyncExecution::LargeThreadPool, - // [&]() - // { - // UpdateMaps(LastUpdatedPosition, TileRadius.X, TileRadius.Y, CacheRadius.X, CacheRadius.Y); - // return true; - // }); if( MPCInstance == nullptr ) { @@ -1950,7 +1547,7 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, } if( MPCInstance ){ - MPCInstance->SetVectorParameterValue("PositionToUpdate", LastUpdatedPosition); + MPCInstance->SetVectorParameterValue("PositionToUpdate", GetTileCenter(LastUpdatedPosition)); // We set texture radius in cm as is UE4 default measure unit MPCInstance->SetScalarParameterValue("TextureRadius", TextureRadius * 100); MPCInstance->SetScalarParameterValue("LargeTextureRadius", TextureRadius * 100); @@ -1975,7 +1572,6 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, } } } - } if (bDrawHeightMap) @@ -2013,37 +1609,6 @@ void UCustomTerrainPhysicsComponent::TickComponent(float DeltaTime, } } -void FSparseHighDetailMap::UnLoadTilesAtPositionToCache(FDVector Position, float RadiusX , float RadiusY ) -{ - // Translate UE4 Position to our coords - TRACE_CPUPROFILER_EVENT_SCOPE(FSparseHighDetailMap::LoadTilesAtPosition); - std::set KeysToRemove; - - double MinX = std::min( std::max( Position.X - RadiusX, 0.0) , Extension.X - 1.0); - double MinY = std::min( std::max( Position.Y - RadiusY, 0.0) , -Extension.Y + 1.0); - double MaxX = std::min( std::max( Position.X + RadiusX, 0.0) , Extension.X - 1.0); - double MaxY = std::min( std::max( Position.Y + RadiusY, 0.0) , -Extension.Y + 1.0); - - FIntVector MinVector = GetVectorTileId(FDVector(MinX, MinY, 0)); - FIntVector MaxVector = GetVectorTileId(FDVector(MaxX, MaxY, 0)); - - FIntVector CacheMinVector = GetVectorTileId(FDVector(MinX - 10.0, MinY - 10.0, 0)); - FIntVector CacheMaxVector = GetVectorTileId(FDVector(MaxX + 10.0, MaxY + 10.0, 0)); - - if( bDebugLoadingTiles ){ - static FDateTime CurrentTime = FDateTime::Now(); - if( ( FDateTime::Now() - CurrentTime).GetTotalSeconds() > 20.0f ) - { - UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::UnLoadTilesAtPositionToCache Position X: %f, Y %f"), Position.X, Position.Y); - UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::UnLoadTilesAtPositionToCache Loading Tiles Between X: %d %d Y: %d %d "), MinVector.X, MaxVector.X, MinVector.Y, MaxVector.Y ); - UE_LOG(LogCarla, Error, TEXT("FSparseHighDetailMap::UnLoadTilesAtPositionToCache Cache Tiles Between X: %d %d Y: %d %d "), CacheMinVector.X, CacheMaxVector.X, CacheMinVector.Y, CacheMaxVector.Y ); - //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::UnLoadTilesAtPositionToCache Extension X: %f, Y %f"), Extension.X, Extension.Y); - //UE_LOG(LogCarla, Log, TEXT("FSparseHighDetailMap::UnLoadTilesAtPositionToCache Before MapSize : %d"), Map.size() ); - CurrentTime = FDateTime::Now(); - } - } -} - void UCustomTerrainPhysicsComponent::DrawParticles(UWorld* World, std::vector& Particles, FLinearColor Color) { @@ -2365,7 +1930,11 @@ void UCustomTerrainPhysicsComponent::RunNNPhysicsSimulation( const FVehicleControl& VehicleControl = Vehicle->GetVehicleControl(); carla::learning::Inputs NNInput {Wheel0,Wheel1,Wheel2,Wheel3, VehicleControl.Steer, VehicleControl.Throttle, VehicleControl.Brake, - NNVerbose}; + SoilType, NNVerbose}; + if (!bUseSoilType) + { + NNInput.terrain_type = -1; + } if (VehicleControl.bReverse) { NNInput.throttle *= -1; @@ -2390,7 +1959,6 @@ void UCustomTerrainPhysicsComponent::RunNNPhysicsSimulation( if(bUpdateParticles) { - { TRACE_CPUPROFILER_EVENT_SCOPE(RemoveParticlesFromOrderedContainer); RemoveParticlesFromOrderedContainer( ParticlesWheel0 ); @@ -2422,7 +1990,7 @@ void UCustomTerrainPhysicsComponent::RunNNPhysicsSimulation( } { TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::UpdateTilesHeightMaps); - UpdateTilesHeightMapsInRadius(LastUpdatedPosition, 4); + UpdateTilesHeightMapsInRadius( LastUpdatedPosition, TextureRadius); } } @@ -2482,6 +2050,113 @@ void UCustomTerrainPhysicsComponent::RunNNPhysicsSimulation( Output.wheel3.wheel_torque_y, Output.wheel3.wheel_torque_z))); } + #else + FTransform VehicleTransform; + VehicleTransform = Vehicle->GetTransform(); + + FVector WheelPosition0 = VehicleTransform.TransformPosition(FVector(140, -70, 40)); + FVector WheelPosition1 = VehicleTransform.TransformPosition(FVector(140, 70, 40)); + FVector WheelPosition2 = VehicleTransform.TransformPosition(FVector(-140, -70, 40)); + FVector WheelPosition3 = VehicleTransform.TransformPosition(FVector(-140, 70, 40)); + if(LargeMapManager) + { + WheelPosition0 = LargeMapManager->LocalToGlobalLocation(WheelPosition0); + WheelPosition1 = LargeMapManager->LocalToGlobalLocation(WheelPosition1); + WheelPosition2 = LargeMapManager->LocalToGlobalLocation(WheelPosition2); + WheelPosition3 = LargeMapManager->LocalToGlobalLocation(WheelPosition3); + } + FOrientedBox BboxWheel0; + BboxWheel0.AxisX = VehicleTransform.GetUnitAxis(EAxis::X); + BboxWheel0.AxisY = VehicleTransform.GetUnitAxis(EAxis::Y); + BboxWheel0.AxisZ = VehicleTransform.GetUnitAxis(EAxis::Z); + BboxWheel0.Center = WheelPosition0 + FVector(0,0,-TireRadius); + BboxWheel0.ExtentX = BoxSearchForwardDistance; + BboxWheel0.ExtentY = BoxSearchLateralDistance; + BboxWheel0.ExtentZ = BoxSearchDepthDistance; + FOrientedBox BboxWheel1 = BboxWheel0; + BboxWheel1.Center = WheelPosition1 + FVector(0,0,-TireRadius); + FOrientedBox BboxWheel2 = BboxWheel0; + BboxWheel2.Center = WheelPosition2 + FVector(0,0,-TireRadius); + FOrientedBox BboxWheel3 = BboxWheel0; + BboxWheel3.Center = WheelPosition3 + FVector(0,0,-TireRadius); + if (DrawDebugInfo) + { + DrawOrientedBox(GetWorld(), {BboxWheel0, BboxWheel1, BboxWheel2, BboxWheel3}); + } + + std::vector ParticlesWheel0, ParticlesWheel1, ParticlesWheel2, ParticlesWheel3; + { + TRACE_CPUPROFILER_EVENT_SCOPE(ParticleSearch); + auto GetAndFilterParticlesInBox = + [&] (FOrientedBox& OBox) -> std::vector + { + std::vector Particles; + Particles = SparseMap.GetParticlesInBox(OBox); + LimitParticlesPerWheel(Particles); + return Particles; + }; + auto FutureParticles0 = Async(EAsyncExecution::ThreadPool, + [&]() {return GetAndFilterParticlesInBox(BboxWheel0);}); + auto FutureParticles2 = Async(EAsyncExecution::ThreadPool, + [&]() {return GetAndFilterParticlesInBox(BboxWheel2);}); + auto FutureParticles1 = Async(EAsyncExecution::ThreadPool, + [&]() {return GetAndFilterParticlesInBox(BboxWheel1);}); + auto FutureParticles3 = Async(EAsyncExecution::ThreadPool, + [&]() {return GetAndFilterParticlesInBox(BboxWheel3);}); + ParticlesWheel0 = FutureParticles0.Get(); + ParticlesWheel2 = FutureParticles2.Get(); + ParticlesWheel1 = FutureParticles1.Get(); + ParticlesWheel3 = FutureParticles3.Get(); + } + + if(DrawDebugInfo) + { + DrawParticles(GetWorld(), ParticlesWheel0); + DrawParticles(GetWorld(), ParticlesWheel1); + DrawParticles(GetWorld(), ParticlesWheel2); + DrawParticles(GetWorld(), ParticlesWheel3); + DrawTiles(GetWorld(), SparseMap.GetIntersectingTiles(BboxWheel0), BboxWheel0.Center.Z); + DrawTiles(GetWorld(), SparseMap.GetIntersectingTiles(BboxWheel1), BboxWheel1.Center.Z); + DrawTiles(GetWorld(), SparseMap.GetIntersectingTiles(BboxWheel2), BboxWheel2.Center.Z); + DrawTiles(GetWorld(), SparseMap.GetIntersectingTiles(BboxWheel3), BboxWheel3.Center.Z); + } + + if(bUpdateParticles) + { + { + TRACE_CPUPROFILER_EVENT_SCOPE(RemoveParticlesFromOrderedContainer); + RemoveParticlesFromOrderedContainer( ParticlesWheel0 ); + RemoveParticlesFromOrderedContainer( ParticlesWheel1 ); + RemoveParticlesFromOrderedContainer( ParticlesWheel2 ); + RemoveParticlesFromOrderedContainer( ParticlesWheel3 ); + } + { + TRACE_CPUPROFILER_EVENT_SCOPE(UpdateParticles); + for( auto it : ParticlesWheel0 ){ + it->Position.Z = -10; + } + for( auto it : ParticlesWheel1 ){ + it->Position.Z = -10; + } + for( auto it : ParticlesWheel2 ){ + it->Position.Z = -10; + } + for( auto it : ParticlesWheel3 ){ + it->Position.Z = -10; + } + } + { + TRACE_CPUPROFILER_EVENT_SCOPE(AddParticles); + AddParticlesToOrderedContainer( ParticlesWheel0 ); + AddParticlesToOrderedContainer( ParticlesWheel1 ); + AddParticlesToOrderedContainer( ParticlesWheel2 ); + AddParticlesToOrderedContainer( ParticlesWheel3 ); + } + { + TRACE_CPUPROFILER_EVENT_SCOPE(UCustomTerrainPhysicsComponent::UpdateTilesHeightMaps); + UpdateTilesHeightMapsInRadius( LastUpdatedPosition, 64); + } + } #endif } @@ -2587,7 +2262,32 @@ void UCustomTerrainPhysicsComponent::RemoveParticlesFromOrderedContainer( HeightMapCoords.Y = std::min( std::max( HeightMapCoords.Y, 0) , static_cast(PartialHeightMapSize-1)); // uint32_t Index = std::floor(ParticleLocalPosition.Y) * PartialHeightMapSize + std::floor(ParticleLocalPosition.X); uint32_t Index = HeightMapCoords.Y * PartialHeightMapSize + HeightMapCoords.X; - CurrentTile.ParticlesZOrdered[Index].erase(P->Position.Z); + + if( Index < CurrentTile.ParticlesZOrdered.size() ) + { + if( CurrentTile.ParticlesZOrdered[Index].size() > 1 ) + { + auto it = CurrentTile.ParticlesZOrdered[Index].find(P->Position.Z ); + if( it != CurrentTile.ParticlesZOrdered[Index].end() ) + { + CurrentTile.ParticlesZOrdered[Index].erase(it); + } + else + { + UE_LOG(LogCarla, Error, TEXT("Cannot find in %d, position %f"), Index, P->Position.Z ); + } + + } + else + { + UE_LOG(LogCarla, Error, TEXT("Cannot Remove more from %d, currentsize %d Tile : %s"), Index,CurrentTile.ParticlesZOrdered[Index].size(), *(TilePosition.ToString()) ); + } + } + else + { + UE_LOG(LogCarla, Error, TEXT("RemoveParticlesFromOrderedContainer Invalid Index %d ZOrderedSize %d Tile: %s"), Index,CurrentTile.ParticlesZOrdered.size(), *(TilePosition.ToString()) ); + } + } } @@ -2596,8 +2296,8 @@ void UCustomTerrainPhysicsComponent::AddParticlesToOrderedContainer( { TRACE_CPUPROFILER_EVENT_SCOPE(AddParticlesToOrderedContainer); - uint32_t PartialHeightMapSize = - SparseMap.GetTileSize() * TextureToUpdate->GetSizeX() / (2*TextureRadius); + uint32_t PartialHeightMapSize = + SparseMap.GetTileSize() * TextureToUpdate->GetSizeX() / (2*TextureRadius); float InverseTileSize = 1.f/SparseMap.GetTileSize(); float Transformation = InverseTileSize * PartialHeightMapSize; float ParticlesInARowInHeightMap = TextureToUpdate->GetSizeX() / (TextureRadius * 2); @@ -2609,13 +2309,18 @@ void UCustomTerrainPhysicsComponent::AddParticlesToOrderedContainer( FDVector TilePosition = CurrentTile.TilePosition; FDVector ParticleLocalPosition = P->Position - TilePosition; FIntVector HeightMapCoords = FIntVector( - ParticleLocalPosition.X * Transformation, - ParticleLocalPosition.Y * Transformation, 0); - - HeightMapCoords.X = std::min( std::max( HeightMapCoords.X, 0) , static_cast(PartialHeightMapSize-1)); - HeightMapCoords.Y = std::min( std::max( HeightMapCoords.Y, 0) , static_cast(PartialHeightMapSize-1)); + std::floor(ParticleLocalPosition.X * Transformation), + std::floor(ParticleLocalPosition.Y * Transformation), 0); + //HeightMapCoords.X = std::min( std::max( HeightMapCoords.X, 0) , static_cast(PartialHeightMapSize-1)); + //HeightMapCoords.Y = std::min( std::max( HeightMapCoords.Y, 0) , static_cast(PartialHeightMapSize-1)); uint32_t Index = HeightMapCoords.Y * PartialHeightMapSize + HeightMapCoords.X; - CurrentTile.ParticlesZOrdered[Index].insert(P->Position.Z); + if( Index < CurrentTile.ParticlesZOrdered.size() ) + { + CurrentTile.ParticlesZOrdered[Index].insert(P->Position.Z); + }else{ + UE_LOG(LogCarla, Error, TEXT("RemoveParticlesFromOrderedContainer Invalid Index %d ZOrderedSize %d Tile: %s"), Index,CurrentTile.ParticlesZOrdered.size(), *(TilePosition.ToString()) ); + + } } } @@ -2721,24 +2426,6 @@ void UCustomTerrainPhysicsComponent::ApplyForcesToVehicle( WheelPosition3 + FVector(0,0,50)+ ForceWheel3.GetSafeNormal()*(5 + ForceMulFactor*10*ForceWheel3.Size()), FLinearColor(0.0,1.0,0.0), 0, 3.0, 0.3); } - /* - UE_LOG(LogCarla, Log, TEXT("Forces0 %s"), - *ForceWheel0.ToString()); - UE_LOG(LogCarla, Log, TEXT("Forces1 %s"), - *ForceWheel1.ToString()); - UE_LOG(LogCarla, Log, TEXT("Forces2 %s"), - *ForceWheel2.ToString()); - UE_LOG(LogCarla, Log, TEXT("Forces3 %s"), - *ForceWheel3.ToString()); - UE_LOG(LogCarla, Log, TEXT("Torque0 %s"), - *TorqueWheel0.ToString()); - UE_LOG(LogCarla, Log, TEXT("Torque1 %s"), - *TorqueWheel1.ToString()); - UE_LOG(LogCarla, Log, TEXT("Torque2 %s"), - *TorqueWheel2.ToString()); - UE_LOG(LogCarla, Log, TEXT("Torque3 %s"), - *TorqueWheel3.ToString()); - */ } void UCustomTerrainPhysicsComponent::ApplyMeanAccelerationToVehicle( @@ -2895,26 +2582,6 @@ void UCustomTerrainPhysicsComponent::UpdateMaps( UEFrameToSI(CacheRadiusX), UEFrameToSI(CacheRadiusY)); } -void UCustomTerrainPhysicsComponent::LoadTilesAtPosition(FVector Position, float RadiusX, float RadiusY) -{ - SparseMap.LoadTilesAtPositionFromCache( UEFrameToSI(Position), UEFrameToSI(RadiusX), UEFrameToSI(RadiusY) ); -} - -void UCustomTerrainPhysicsComponent::UnloadTilesAtPosition(FVector Position, float RadiusX, float RadiusY) -{ - SparseMap.UnLoadTilesAtPositionToCache( UEFrameToSI(Position), UEFrameToSI(RadiusX), UEFrameToSI(RadiusY) ); -} - -void UCustomTerrainPhysicsComponent::ReloadCache(FVector Position, float RadiusX, float RadiusY) -{ - if( MPCInstance ){ - MPCInstance->SetVectorParameterValue("CacheLastUpdatedPosition", Position); - CachePosition = Position; - } - - SparseMap.ReloadCache(UEFrameToSI(Position), UEFrameToSI(RadiusX), UEFrameToSI(RadiusY)); -} - FTilesWorker::FTilesWorker(UCustomTerrainPhysicsComponent* TerrainComp, FVector NewPosition, float NewRadiusX, float NewRadiusY ) { CustomTerrainComp = TerrainComp; @@ -2948,22 +2615,6 @@ uint32 FTilesWorker::Run(){ { break; } - // if( ( FDateTime::Now() - LoadTilesCurrentTime ).GetTotalMilliseconds() > CustomTerrainComp->TimeToTriggerLoadTiles ){ - // CustomTerrainComp->LoadTilesAtPosition( CustomTerrainComp->LastUpdatedPosition, RadiusX, RadiusY ); - // LoadTilesCurrentTime = FDateTime::Now(); - // } - - // if( ( FDateTime::Now() - UnloadTilesCurrentTime ).GetTotalMilliseconds() > CustomTerrainComp->TimeToTriggerUnLoadTiles ){ - // CustomTerrainComp->UnloadTilesAtPosition( CustomTerrainComp->LastUpdatedPosition, RadiusX, RadiusY ); - // UnloadTilesCurrentTime = FDateTime::Now(); - // } - - // if( ( FDateTime::Now() - LoadTilesCurrentTime ).GetTotalSeconds() > CustomTerrainComp->TimeToTriggerCacheReload ){ - // UE_LOG(LogCarla, Warning, TEXT("Tiles Cache reloaded")); - // CustomTerrainComp->ReloadCache(CustomTerrainComp->LastUpdatedPosition, - // CustomTerrainComp->CacheRadius.X, CustomTerrainComp->CacheRadius.Y); - // CacheCurrentTime = FDateTime::Now(); - // } } return 0; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.h index 5db7155d5..72a65da50 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CustomTerrainPhysicsComponent.h @@ -39,7 +39,7 @@ public: int SizeX = 0; UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = HeightMapDataAsset) int SizeY = 0; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = HeightMapDataAsset) + UPROPERTY(BlueprintReadWrite, Category = HeightMapDataAsset) TArray HeightValues; }; @@ -52,12 +52,6 @@ struct FParticle 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( UHeightMapDataAsset* DataAsset, FDVector Size, FDVector Origin, FDVector Tile0, float ScaleZ); @@ -93,7 +87,6 @@ struct FDenseTile void UpdateLocalHeightmap(); std::vector Particles; std::vector ParticlesHeightMap; - //std::vector> ParticlesZOrdered; std::vector>> ParticlesZOrdered; FDVector TilePosition; FString SavePath; @@ -150,21 +143,12 @@ public: return Heightmap.GetHeight(Position); } - void InitializeMap(UTexture2D* HeightMapTexture, - FDVector Origin, FDVector MapSize, float Size, float MinHeight, float MaxHeight, - float ScaleZ); void InitializeMap(UHeightMapDataAsset* DataAsset, 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, 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 Update(FVector Position, float RadiusX, float RadiusY); @@ -255,9 +239,6 @@ public: UFUNCTION(BlueprintCallable) void AddForces(const TArray &Forces); - UFUNCTION(BlueprintCallable) - TArray BuildLandscapeHeightMap(ALandscapeProxy* Landscape, int Resolution); - UFUNCTION(BlueprintCallable) static void BuildLandscapeHeightMapDataAasset(ALandscapeProxy* Landscape, int Resolution, FVector MapSize, FString AssetPath, FString AssetName); @@ -274,27 +255,15 @@ public: UFUNCTION(BlueprintCallable) FVector GetTileCenter(FVector Position); - UFUNCTION(BlueprintCallable, Category="Tiles") - void LoadTilesAtPosition(FVector Position, float RadiusX = 100.0f, float RadiusY = 100.0f); - UFUNCTION(BlueprintCallable, Category="Tiles") 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") void InitTexture(); UFUNCTION(BlueprintCallable, Category="Texture") void UpdateTexture(); - UFUNCTION(BlueprintCallable, Category="Texture") - void UpdateTextureData(); UFUNCTION(BlueprintCallable, Category="Texture") void UpdateLoadedTextureDataRegions(); @@ -307,9 +276,6 @@ public: UFUNCTION(BlueprintCallable, Category="Texture") void UpdateLargeTextureData(); - UPROPERTY(EditAnywhere, BlueprintReadWrite) - UTexture2D *HeightMap; - UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="MaterialParameters") UTexture2D* TextureToUpdate; UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="MaterialParameters") @@ -338,6 +304,10 @@ public: float ForceMulFactor = 1.0; UPROPERTY(EditAnywhere, BlueprintReadWrite) float ParticleForceMulFactor = 1.0; + UPROPERTY(EditAnywhere, BlueprintReadWrite) + int SoilType = 0; + UPROPERTY(EditAnywhere, BlueprintReadWrite) + bool bUseSoilType = false; UPROPERTY(EditAnywhere) bool NNVerbose = false; @@ -438,8 +408,6 @@ private: UPROPERTY() UMaterialParameterCollectionInstance* MPCInstance; - - UPROPERTY(EditAnywhere) float SearchRadius = 100;