├── AiNavInterop ├── AiCrowd.cpp ├── AiCrowd.hpp ├── AiNav.cpp ├── AiNav.h ├── AiNav.sln ├── AiNav.vcxproj ├── AiNav.vcxproj.filters ├── AiNav.vcxproj.user ├── AiQuery.cpp ├── AiQuery.hpp ├── Detour │ ├── CMakeLists.txt │ ├── Include │ │ ├── DetourAlloc.h │ │ ├── DetourAssert.h │ │ ├── DetourCommon.h │ │ ├── DetourMath.h │ │ ├── DetourNavMesh.h │ │ ├── DetourNavMeshBuilder.h │ │ ├── DetourNavMeshQuery.h │ │ ├── DetourNode.h │ │ └── DetourStatus.h │ └── Source │ │ ├── DetourAlloc.cpp │ │ ├── DetourAssert.cpp │ │ ├── DetourCommon.cpp │ │ ├── DetourNavMesh.cpp │ │ ├── DetourNavMeshBuilder.cpp │ │ ├── DetourNavMeshQuery.cpp │ │ └── DetourNode.cpp ├── DetourCrowd │ ├── CMakeLists.txt │ ├── Include │ │ ├── DetourCrowd.h │ │ ├── DetourLocalBoundary.h │ │ ├── DetourObstacleAvoidance.h │ │ ├── DetourPathCorridor.h │ │ ├── DetourPathQueue.h │ │ └── DetourProximityGrid.h │ └── Source │ │ ├── DetourCrowd.cpp │ │ ├── DetourLocalBoundary.cpp │ │ ├── DetourObstacleAvoidance.cpp │ │ ├── DetourPathCorridor.cpp │ │ ├── DetourPathQueue.cpp │ │ └── DetourProximityGrid.cpp ├── DetourTileCache │ ├── CMakeLists.txt │ ├── Include │ │ ├── DetourTileCache.h │ │ └── DetourTileCacheBuilder.h │ └── Source │ │ ├── DetourTileCache.cpp │ │ └── DetourTileCacheBuilder.cpp ├── Navigation.hpp ├── NavigationBuilder.cpp ├── NavigationBuilder.hpp ├── NavigationMesh.cpp ├── NavigationMesh.hpp ├── Recast │ ├── CMakeLists.txt │ ├── Include │ │ ├── Recast.h │ │ ├── RecastAlloc.h │ │ └── RecastAssert.h │ └── Source │ │ ├── Recast.cpp │ │ ├── RecastAlloc.cpp │ │ ├── RecastArea.cpp │ │ ├── RecastAssert.cpp │ │ ├── RecastContour.cpp │ │ ├── RecastFilter.cpp │ │ ├── RecastLayers.cpp │ │ ├── RecastMesh.cpp │ │ ├── RecastMeshDetail.cpp │ │ ├── RecastRasterization.cpp │ │ └── RecastRegion.cpp ├── dllmain.cpp ├── framework.h ├── pch.cpp ├── pch.h └── x64 │ └── Release │ ├── AiNav.Build.CppClean.log │ └── AiNav.log ├── Assets ├── AiNav │ ├── AiNavSurface.cs │ ├── AiNavSurface.cs.meta │ ├── Components.meta │ ├── Components │ │ ├── AgentPathBuffer.cs │ │ ├── AgentPathBuffer.cs.meta │ │ ├── AgentPathData.cs │ │ ├── AgentPathData.cs.meta │ │ ├── Authoring.meta │ │ ├── Authoring │ │ │ ├── BoxFilterAuthoring.cs │ │ │ ├── BoxFilterAuthoring.cs.meta │ │ │ ├── LayerAttribute.cs │ │ │ ├── LayerAttribute.cs.meta │ │ │ ├── MeshSourceAuthorBase.cs │ │ │ ├── MeshSourceAuthorBase.cs.meta │ │ │ ├── SimpleMeshSourceAuthor.cs │ │ │ └── SimpleMeshSourceAuthor.cs.meta │ │ ├── BoxFilter.cs │ │ ├── BoxFilter.cs.meta │ │ ├── MeshSource.cs │ │ ├── MeshSource.cs.meta │ │ ├── NavAgent.cs │ │ ├── NavAgent.cs.meta │ │ ├── NavAgentDebug.cs │ │ ├── NavAgentDebug.cs.meta │ │ ├── PathHandler.cs │ │ └── PathHandler.cs.meta │ ├── Editor.meta │ ├── Editor │ │ ├── AiNavSurfaceEditor.cs │ │ ├── AiNavSurfaceEditor.cs.meta │ │ ├── AiNavTests.cs │ │ ├── AiNavTests.cs.meta │ │ ├── EcsWorldEditor.cs │ │ ├── EcsWorldEditor.cs.meta │ │ ├── LayerAttributeEditor.cs │ │ ├── LayerAttributeEditor.cs.meta │ │ ├── SharedMeshDbEditor.cs │ │ ├── SharedMeshDbEditor.cs.meta │ │ ├── SimpleSourceAuthorEditor.cs │ │ ├── SimpleSourceAuthorEditor.cs.meta │ │ └── Test │ │ │ ├── NavigationTests.cs │ │ │ └── NavigationTests.cs.meta │ ├── NativeBuildUtitls.cs │ ├── NativeBuildUtitls.cs.meta │ ├── NavAgentMotor.cs │ ├── NavAgentMotor.cs.meta │ ├── NavMeshNativeInputBuilder.cs │ ├── NavMeshNativeInputBuilder.cs.meta │ ├── NavigationTests.cs │ ├── Prefabs.meta │ ├── Prefabs │ │ ├── AiNavSurface.prefab │ │ ├── AiNavSurface.prefab.meta │ │ ├── BoundsFilterMaterial.mat │ │ ├── BoundsFilterMaterial.mat.meta │ │ ├── BoxFilter.prefab │ │ ├── BoxFilter.prefab.meta │ │ ├── CapsuleSource.prefab │ │ ├── CapsuleSource.prefab.meta │ │ ├── SimpleMeshSourceAuthor.prefab │ │ ├── SimpleMeshSourceAuthor.prefab.meta │ │ ├── agent.mat │ │ ├── agent.mat.meta │ │ ├── agent.prefab │ │ ├── agent.prefab.meta │ │ ├── surface.mat │ │ └── surface.mat.meta │ ├── Resources.meta │ ├── Resources │ │ ├── SharedMeshDb.asset │ │ └── SharedMeshDb.asset.meta │ ├── SharedMeshDb.cs │ ├── SharedMeshDb.cs.meta │ ├── Systems.meta │ ├── Systems │ │ ├── AiNavSystem.cs │ │ ├── AiNavSystem.cs.meta │ │ ├── AiNavTestSystem.cs │ │ ├── AiNavTestSystem.cs.meta │ │ ├── CrowdController.cs │ │ ├── CrowdController.cs.meta │ │ ├── CrowdControllerJobs.cs │ │ ├── CrowdControllerJobs.cs.meta │ │ ├── EcsWorld.cs │ │ ├── EcsWorld.cs.meta │ │ ├── GeometryCollectors.meta │ │ ├── GeometryCollectors │ │ │ ├── ConvexHullGeometryCollector.cs │ │ │ ├── ConvexHullGeometryCollector.cs.meta │ │ │ ├── GeometryFilter.cs │ │ │ ├── GeometryFilter.cs.meta │ │ │ ├── MeshGeometryCollector.cs │ │ │ ├── MeshGeometryCollector.cs.meta │ │ │ ├── PrimitiveGeometryCollector.cs │ │ │ ├── PrimitiveGeometryCollector.cs.meta │ │ │ ├── TerrainGeometryCollector.cs │ │ │ └── TerrainGeometryCollector.cs.meta │ │ ├── MeshSourceMap.cs │ │ ├── MeshSourceMap.cs.meta │ │ ├── NavMeshStoreSystem.cs │ │ ├── NavMeshStoreSystem.cs.meta │ │ ├── SurfaceController.cs │ │ ├── SurfaceController.cs.meta │ │ ├── SurfaceControllerConfig.cs │ │ ├── SurfaceControllerConfig.cs.meta │ │ ├── SurfaceControllerJobs.cs │ │ ├── SurfaceControllerJobs.cs.meta │ │ ├── SurfaceData.cs │ │ └── SurfaceData.cs.meta │ ├── Util.meta │ └── Util │ │ ├── AiNavExtensions.cs │ │ ├── AiNavExtensions.cs.meta │ │ ├── UnityPhysicsHelper.cs │ │ └── UnityPhysicsHelper.cs.meta ├── AiNavCore │ ├── AiCrowd.cs │ ├── AiCrowd.cs.meta │ ├── AiNavMesh.cs │ ├── AiNavMesh.cs.meta │ ├── AiNavQuery.cs │ ├── AiNavQuery.cs.meta │ ├── AiNavWorld.cs │ ├── AiNavWorld.cs.meta │ ├── Collections.meta │ ├── Collections │ │ ├── AiNativeArray.cs │ │ ├── AiNativeArray.cs.meta │ │ ├── AiNativeList.cs │ │ ├── AiNativeList.cs.meta │ │ ├── CollectionStore.cs │ │ ├── CollectionStore.cs.meta │ │ ├── MemoryCopy.cs │ │ ├── MemoryCopy.cs.meta │ │ ├── UnsafeArrayData.cs │ │ ├── UnsafeArrayData.cs.meta │ │ ├── UnsafeCollectionExtensions.cs │ │ ├── UnsafeCollectionExtensions.cs.meta │ │ ├── UnsafeCollectionUtility.cs │ │ ├── UnsafeCollectionUtility.cs.meta │ │ ├── UnsafeListData.cs │ │ └── UnsafeListData.cs.meta │ ├── NavAgentSettings.cs │ ├── NavAgentSettings.cs.meta │ ├── NavMeshBuildInput.cs │ ├── NavMeshBuildInput.cs.meta │ ├── NavMeshBuildResult.cs │ ├── NavMeshBuildResult.cs.meta │ ├── NavMeshBuildSettings.cs │ ├── NavMeshBuildSettings.cs.meta │ ├── NavMeshBuildUtils.cs │ ├── NavMeshBuildUtils.cs.meta │ ├── NavMeshBuilder.cs │ ├── NavMeshBuilder.cs.meta │ ├── NavMeshBuilderSettings.cs │ ├── NavMeshBuilderSettings.cs.meta │ ├── NavMeshInputBuilder.cs │ ├── NavMeshInputBuilder.cs.meta │ ├── NavMeshTestData.cs │ ├── NavMeshTestData.cs.meta │ ├── NavMeshTile.cs │ ├── NavMeshTile.cs.meta │ ├── NavMeshTileBounds.cs │ ├── NavMeshTileBounds.cs.meta │ ├── NavQuerySettings.cs │ ├── NavQuerySettings.cs.meta │ ├── NavTypes.meta │ ├── NavTypes │ │ ├── DtAgentParams.cs │ │ ├── DtAgentParams.cs.meta │ │ ├── DtArea.cs │ │ ├── DtArea.cs.meta │ │ ├── DtBoundingBox.cs │ │ ├── DtBoundingBox.cs.meta │ │ ├── DtBuildSettings.cs │ │ ├── DtBuildSettings.cs.meta │ │ ├── DtCrowdAgent.cs │ │ ├── DtCrowdAgent.cs.meta │ │ ├── DtCrowdAgentsResult.cs │ │ ├── DtCrowdAgentsResult.cs.meta │ │ ├── DtGeneratedData.cs │ │ ├── DtGeneratedData.cs.meta │ │ ├── DtPathFindQuery.cs │ │ ├── DtPathFindQuery.cs.meta │ │ ├── DtPathFindResult.cs │ │ ├── DtPathFindResult.cs.meta │ │ ├── DtPoly.cs │ │ ├── DtPoly.cs.meta │ │ ├── DtRaycastQuery.cs │ │ ├── DtRaycastQuery.cs.meta │ │ ├── DtRaycastResult.cs │ │ ├── DtRaycastResult.cs.meta │ │ ├── DtTileHeader.cs │ │ └── DtTileHeader.cs.meta │ ├── Navigation.cs │ ├── Navigation.cs.meta │ ├── Util.meta │ └── Util │ │ ├── GameClock.cs │ │ ├── GameClock.cs.meta │ │ ├── NavExtensions.cs │ │ └── NavExtensions.cs.meta ├── Plugins │ ├── x86_64.meta │ └── x86_64 │ │ ├── AiNav.dll │ │ └── AiNav.dll.meta └── UnityPhysics │ ├── CHANGELOG.md │ ├── CHANGELOG.md.meta │ ├── Documentation~ │ ├── collision_queries.md │ ├── core_components.md │ ├── design.md │ ├── getting_started.md │ ├── glossary.md │ ├── images │ │ ├── BoxShape.png │ │ ├── Compunds.gif │ │ ├── CompundsH.png │ │ ├── Convex_Hull_Teapot.png │ │ ├── DynamicBody.png │ │ ├── StaticBody.png │ │ ├── StepPhysics.png │ │ ├── closest_points.gif │ │ ├── closest_points_all_hits.gif │ │ └── collider_cast_queries.gif │ ├── index.md │ ├── runtime_overview.md │ ├── simulation_modification.md │ └── simulation_results.md │ ├── LICENSE.md │ ├── LICENSE.md.meta │ ├── Unity.Physics.Editor.meta │ ├── Unity.Physics.Editor │ ├── AssemblyInfo.cs │ ├── AssemblyInfo.cs.meta │ ├── Editor.meta │ ├── Editor │ │ ├── Resources.meta │ │ └── Resources │ │ │ ├── CustomPhysicsBodyTagNames Icon.psd │ │ │ ├── CustomPhysicsBodyTagNames Icon.psd.meta │ │ │ ├── CustomPhysicsMaterialTagNames Icon.psd │ │ │ ├── CustomPhysicsMaterialTagNames Icon.psd.meta │ │ │ ├── PhysicsCategoryNames Icon.psd │ │ │ ├── PhysicsCategoryNames Icon.psd.meta │ │ │ ├── PhysicsMaterialTemplate Icon.psd │ │ │ └── PhysicsMaterialTemplate Icon.psd.meta │ ├── EditorTools.meta │ ├── EditorTools │ │ ├── BeveledBoxBoundsHandle.cs │ │ ├── BeveledBoxBoundsHandle.cs.meta │ │ ├── BeveledCylinderBoundsHandle.cs │ │ └── BeveledCylinderBoundsHandle.cs.meta │ ├── Editors.meta │ ├── Editors │ │ ├── BaseEditor.cs │ │ ├── BaseEditor.cs.meta │ │ ├── CustomPhysicsBodyTagNamesEditor.cs │ │ ├── CustomPhysicsBodyTagNamesEditor.cs.meta │ │ ├── CustomPhysicsMaterialTagNamesEditor.cs │ │ ├── CustomPhysicsMaterialTagNamesEditor.cs.meta │ │ ├── PhysicsBodyAuthoringEditor.cs │ │ ├── PhysicsBodyAuthoringEditor.cs.meta │ │ ├── PhysicsCategoryNamesEditor.cs │ │ ├── PhysicsCategoryNamesEditor.cs.meta │ │ ├── PhysicsShapeAuthoringEditor.cs │ │ └── PhysicsShapeAuthoringEditor.cs.meta │ ├── PropertyDrawers.meta │ ├── PropertyDrawers │ │ ├── BaseDrawer.cs │ │ ├── BaseDrawer.cs.meta │ │ ├── EnumFlagsDrawer.cs │ │ ├── EnumFlagsDrawer.cs.meta │ │ ├── EulerAnglesDrawer.cs │ │ ├── EulerAnglesDrawer.cs.meta │ │ ├── ExpandChildrenDrawer.cs │ │ ├── ExpandChildrenDrawer.cs.meta │ │ ├── PhysicsMaterialCoefficientDrawer.cs │ │ ├── PhysicsMaterialCoefficientDrawer.cs.meta │ │ ├── PhysicsMaterialPropertiesDrawer.cs │ │ ├── PhysicsMaterialPropertiesDrawer.cs.meta │ │ ├── SoftRangeDrawer.cs │ │ ├── SoftRangeDrawer.cs.meta │ │ ├── TagsDrawer.cs │ │ └── TagsDrawer.cs.meta │ ├── Unity.Physics.Editor.asmdef │ ├── Unity.Physics.Editor.asmdef.meta │ ├── Utilities.meta │ └── Utilities │ │ ├── EditorGUIControls.cs │ │ ├── EditorGUIControls.cs.meta │ │ ├── ManipulatorUtility.cs │ │ ├── ManipulatorUtility.cs.meta │ │ ├── SceneViewUtility.cs │ │ ├── SceneViewUtility.cs.meta │ │ ├── StatusMessageUtility.cs │ │ └── StatusMessageUtility.cs.meta │ ├── Unity.Physics.Hybrid.meta │ ├── Unity.Physics.Hybrid │ ├── AssemblyInfo.cs │ ├── AssemblyInfo.cs.meta │ ├── Assets.meta │ ├── Assets │ │ ├── CustomPhysicsBodyTagNames.cs │ │ ├── CustomPhysicsBodyTagNames.cs.meta │ │ ├── CustomPhysicsMaterialTagNames.cs │ │ ├── CustomPhysicsMaterialTagNames.cs.meta │ │ ├── PhysicsCategoryNames.cs │ │ ├── PhysicsCategoryNames.cs.meta │ │ ├── PhysicsMaterialTemplate.cs │ │ └── PhysicsMaterialTemplate.cs.meta │ ├── Components.meta │ ├── Components │ │ ├── PhysicsBodyAuthoring.cs │ │ ├── PhysicsBodyAuthoring.cs.meta │ │ ├── PhysicsDebugDisplayAuthoring.cs │ │ ├── PhysicsDebugDisplayAuthoring.cs.meta │ │ ├── PhysicsShapeAuthoring.cs │ │ ├── PhysicsShapeAuthoring.cs.meta │ │ ├── PhysicsStepAuthoring.cs │ │ └── PhysicsStepAuthoring.cs.meta │ ├── Conversion.meta │ ├── Conversion │ │ ├── BaseShapeConversionSystem.cs │ │ ├── BaseShapeConversionSystem.cs.meta │ │ ├── ConversionExtensions.cs │ │ ├── ConversionExtensions.cs.meta │ │ ├── LegacyColliderConversionSystem.cs │ │ ├── LegacyColliderConversionSystem.cs.meta │ │ ├── LegacyRigidbodyConversionSystem.cs │ │ ├── LegacyRigidbodyConversionSystem.cs.meta │ │ ├── PhysicsBodyConversionSystem.cs │ │ ├── PhysicsBodyConversionSystem.cs.meta │ │ ├── PhysicsShapeConversionSystem.cs │ │ └── PhysicsShapeConversionSystem.cs.meta │ ├── Data.meta │ ├── Data │ │ ├── CustomPhysicsBodyTags.cs │ │ ├── CustomPhysicsBodyTags.cs.meta │ │ ├── CustomPhysicsMaterialTags.cs │ │ ├── CustomPhysicsMaterialTags.cs.meta │ │ ├── PhysicsCategoryTags.cs │ │ ├── PhysicsCategoryTags.cs.meta │ │ ├── PhysicsMaterialProperties.cs │ │ └── PhysicsMaterialProperties.cs.meta │ ├── Deprecated.cs │ ├── Deprecated.cs.meta │ ├── PropertyAttributes.meta │ ├── PropertyAttributes │ │ ├── PropertyAttributes.cs │ │ └── PropertyAttributes.cs.meta │ ├── Unity.Physics.Hybrid.asmdef │ ├── Unity.Physics.Hybrid.asmdef.meta │ ├── Utilities.meta │ └── Utilities │ │ ├── ConvexHullGenerationParametersExtensions.cs │ │ ├── ConvexHullGenerationParametersExtensions.cs.meta │ │ ├── DebugDisplay.meta │ │ ├── DebugDisplay │ │ ├── DebugStream.cs │ │ ├── DebugStream.cs.meta │ │ ├── DisplayBroadphaseSystem.cs │ │ ├── DisplayBroadphaseSystem.cs.meta │ │ ├── DisplayColliderBoundingVolumeSystem.cs │ │ ├── DisplayColliderBoundingVolumeSystem.cs.meta │ │ ├── DisplayCollidersSystem.cs │ │ ├── DisplayCollidersSystem.cs.meta │ │ ├── DisplayCollisionEventsSystem.cs │ │ ├── DisplayCollisionEventsSystem.cs.meta │ │ ├── DisplayContactsSystem.cs │ │ ├── DisplayContactsSystem.cs.meta │ │ ├── DisplayJointsSystem.cs │ │ ├── DisplayJointsSystem.cs.meta │ │ ├── DisplayMassPropertiesSystem.cs │ │ ├── DisplayMassPropertiesSystem.cs.meta │ │ ├── DisplayTriggerEventsSystem.cs │ │ └── DisplayTriggerEventsSystem.cs.meta │ │ ├── DrawingUtility.cs │ │ ├── DrawingUtility.cs.meta │ │ ├── PhysicsShapeExtensions.cs │ │ └── PhysicsShapeExtensions.cs.meta │ ├── Unity.Physics.meta │ ├── Unity.Physics │ ├── AOTHint.cs │ ├── AOTHint.cs.meta │ ├── AssemblyInfo.cs │ ├── AssemblyInfo.cs.meta │ ├── Base.meta │ ├── Base │ │ ├── Containers.meta │ │ ├── Containers │ │ │ ├── BlobArray.cs │ │ │ ├── BlobArray.cs.meta │ │ │ ├── BlockStream.cs │ │ │ ├── BlockStream.cs.meta │ │ │ ├── ElementPool.cs │ │ │ ├── ElementPool.cs.meta │ │ │ ├── NativeListTemp.cs │ │ │ ├── NativeListTemp.cs.meta │ │ │ ├── UnsafeEx.cs │ │ │ └── UnsafeEx.cs.meta │ │ ├── Jobs.meta │ │ ├── Jobs │ │ │ ├── IJobParallelForDeferExtensionsPhysics.cs │ │ │ └── IJobParallelForDeferExtensionsPhysics.cs.meta │ │ ├── Math.meta │ │ └── Math │ │ │ ├── Aabb.cs │ │ │ ├── Aabb.cs.meta │ │ │ ├── FourTransposedAabbs.cs │ │ │ ├── FourTransposedAabbs.cs.meta │ │ │ ├── FourTransposedPoints.cs │ │ │ ├── FourTransposedPoints.cs.meta │ │ │ ├── Math.cs │ │ │ ├── Math.cs.meta │ │ │ ├── Physics_Transform.cs │ │ │ ├── Physics_Transform.cs.meta │ │ │ ├── Plane.cs │ │ │ └── Plane.cs.meta │ ├── Collision.meta │ ├── Collision │ │ ├── Colliders.meta │ │ ├── Colliders │ │ │ ├── CompoundCollider.cs │ │ │ ├── CompoundCollider.cs.meta │ │ │ ├── ConvexCollider.cs │ │ │ ├── ConvexCollider.cs.meta │ │ │ ├── CylinderCollider.cs │ │ │ ├── CylinderCollider.cs.meta │ │ │ ├── Physics_BoxCollider.cs │ │ │ ├── Physics_BoxCollider.cs.meta │ │ │ ├── Physics_CapsuleCollider.cs │ │ │ ├── Physics_CapsuleCollider.cs.meta │ │ │ ├── Physics_Collider.cs │ │ │ ├── Physics_Collider.cs.meta │ │ │ ├── Physics_MeshCollider.cs │ │ │ ├── Physics_MeshCollider.cs.meta │ │ │ ├── Physics_SphereCollider.cs │ │ │ ├── Physics_SphereCollider.cs.meta │ │ │ ├── Physics_TerrainCollider.cs │ │ │ ├── Physics_TerrainCollider.cs.meta │ │ │ ├── PolygonCollider.cs │ │ │ └── PolygonCollider.cs.meta │ │ ├── Filter.meta │ │ ├── Filter │ │ │ ├── CollisionFilter.cs │ │ │ └── CollisionFilter.cs.meta │ │ ├── Geometry.meta │ │ ├── Geometry │ │ │ ├── BoundingVolumeHierarchy.cs │ │ │ ├── BoundingVolumeHierarchy.cs.meta │ │ │ ├── BoundingVolumeHierarchyBuilder.cs │ │ │ ├── BoundingVolumeHierarchyBuilder.cs.meta │ │ │ ├── ConvexHull.cs │ │ │ ├── ConvexHull.cs.meta │ │ │ ├── ConvexHullBuilder.cs │ │ │ ├── ConvexHullBuilder.cs.meta │ │ │ ├── Mesh.cs │ │ │ ├── Mesh.cs.meta │ │ │ ├── MeshBuilder.cs │ │ │ └── MeshBuilder.cs.meta │ │ ├── Queries.meta │ │ ├── Queries │ │ │ ├── Collector.cs │ │ │ ├── Collector.cs.meta │ │ │ ├── Collidable.cs │ │ │ ├── Collidable.cs.meta │ │ │ ├── ColliderCast.cs │ │ │ ├── ColliderCast.cs.meta │ │ │ ├── ConvexConvexDistance.cs │ │ │ ├── ConvexConvexDistance.cs.meta │ │ │ ├── ConvexConvexManifold.cs │ │ │ ├── ConvexConvexManifold.cs.meta │ │ │ ├── Distance.cs │ │ │ ├── Distance.cs.meta │ │ │ ├── Manifold.cs │ │ │ ├── Manifold.cs.meta │ │ │ ├── Overlap.cs │ │ │ ├── Overlap.cs.meta │ │ │ ├── Raycast.cs │ │ │ └── Raycast.cs.meta │ │ ├── RigidBody.meta │ │ ├── RigidBody │ │ │ ├── RigidBody.cs │ │ │ └── RigidBody.cs.meta │ │ ├── World.meta │ │ └── World │ │ │ ├── Broadphase.cs │ │ │ ├── Broadphase.cs.meta │ │ │ ├── CollisionWorld.cs │ │ │ └── CollisionWorld.cs.meta │ ├── Deprecated.cs │ ├── Deprecated.cs.meta │ ├── Dynamics.meta │ ├── Dynamics │ │ ├── Integrator.meta │ │ ├── Integrator │ │ │ ├── Integrator.cs │ │ │ └── Integrator.cs.meta │ │ ├── Jacobians.meta │ │ ├── Jacobians │ │ │ ├── AngularLimit1DJacobian.cs │ │ │ ├── AngularLimit1DJacobian.cs.meta │ │ │ ├── AngularLimit2DJacobian.cs │ │ │ ├── AngularLimit2DJacobian.cs.meta │ │ │ ├── AngularLimit3DJacobian.cs │ │ │ ├── AngularLimit3DJacobian.cs.meta │ │ │ ├── ContactJacobian.cs │ │ │ ├── ContactJacobian.cs.meta │ │ │ ├── ContactJacobianMemoryLayout.md │ │ │ ├── ContactJacobianMemoryLayout.md.meta │ │ │ ├── Jacobian.cs │ │ │ ├── Jacobian.cs.meta │ │ │ ├── LinearLimitJacobian.cs │ │ │ └── LinearLimitJacobian.cs.meta │ │ ├── Joint.meta │ │ ├── Joint │ │ │ ├── Physics_Joint.cs │ │ │ └── Physics_Joint.cs.meta │ │ ├── Material.meta │ │ ├── Material │ │ │ ├── Material.cs │ │ │ └── Material.cs.meta │ │ ├── Motion.meta │ │ ├── Motion │ │ │ ├── Motion.cs │ │ │ └── Motion.cs.meta │ │ ├── Simulation.meta │ │ ├── Simulation │ │ │ ├── Callbacks.cs │ │ │ ├── Callbacks.cs.meta │ │ │ ├── CollisionEvent.cs │ │ │ ├── CollisionEvent.cs.meta │ │ │ ├── IBodyPairsJob.cs │ │ │ ├── IBodyPairsJob.cs.meta │ │ │ ├── ICollisionEventsJob.cs │ │ │ ├── ICollisionEventsJob.cs.meta │ │ │ ├── IContactsJob.cs │ │ │ ├── IContactsJob.cs.meta │ │ │ ├── IJacobiansJob.cs │ │ │ ├── IJacobiansJob.cs.meta │ │ │ ├── ITriggerEventsJob.cs │ │ │ ├── ITriggerEventsJob.cs.meta │ │ │ ├── Narrowphase.cs │ │ │ ├── Narrowphase.cs.meta │ │ │ ├── Scheduler.cs │ │ │ ├── Scheduler.cs.meta │ │ │ ├── Simulation.cs │ │ │ ├── Simulation.cs.meta │ │ │ ├── TriggerEvent.cs │ │ │ └── TriggerEvent.cs.meta │ │ ├── Solver.meta │ │ ├── Solver │ │ │ ├── SimplexSolver.cs │ │ │ ├── SimplexSolver.cs.meta │ │ │ ├── Solver.cs │ │ │ └── Solver.cs.meta │ │ ├── World.meta │ │ └── World │ │ │ ├── DynamicsWorld.cs │ │ │ ├── DynamicsWorld.cs.meta │ │ │ ├── PhysicsWorld.cs │ │ │ └── PhysicsWorld.cs.meta │ ├── ECS.meta │ ├── ECS │ │ ├── Components.meta │ │ ├── Components │ │ │ ├── PhysicsComponents.cs │ │ │ └── PhysicsComponents.cs.meta │ │ ├── Systems.meta │ │ └── Systems │ │ │ ├── BuildPhysicsWorld.cs │ │ │ ├── BuildPhysicsWorld.cs.meta │ │ │ ├── EndFramePhysicsSystem.cs │ │ │ ├── EndFramePhysicsSystem.cs.meta │ │ │ ├── ExportPhysicsWorld.cs │ │ │ ├── ExportPhysicsWorld.cs.meta │ │ │ ├── StepPhysicsWorld.cs │ │ │ └── StepPhysicsWorld.cs.meta │ ├── Extensions.meta │ ├── Extensions │ │ ├── World.meta │ │ └── World │ │ │ ├── ComponentExtensions.cs │ │ │ ├── ComponentExtensions.cs.meta │ │ │ ├── PhysicsWorldExtensions.cs │ │ │ └── PhysicsWorldExtensions.cs.meta │ ├── Unity.Physics.asmdef │ └── Unity.Physics.asmdef.meta │ ├── UnityPhysicsMods.cs │ ├── UnityPhysicsMods.cs.meta │ ├── package.json │ └── package.json.meta ├── LICENSE.md └── README.md /AiNavInterop/AiCrowd.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | #include "NavigationMesh.hpp" 4 | 5 | class AiCrowd { 6 | private: 7 | int activeAgentCount = 0; 8 | dtNavMesh* m_navMesh = nullptr; 9 | dtNavMeshQuery* m_navQuery = nullptr; 10 | dtCrowd* crowd = nullptr; 11 | dtCrowdAgentParams CreateParams(DtAgentParams* agentParams); 12 | public: 13 | AiCrowd(); 14 | ~AiCrowd(); 15 | int Init(NavigationMesh * navmesh, int maxAgents, float maxRadius); 16 | int AddAgent(float3 position, DtAgentParams * agentParams); 17 | void RemoveAgent(int idx); 18 | void SetAgentParams(int idx, DtAgentParams* agentParams); 19 | void GetAgentParams(int idx, DtAgentParams* agentParams); 20 | int RequestMove(int idx, float3 position); 21 | int GetAgentCount(); 22 | void GetAgent(int idx, DtCrowdAgent* result); 23 | void GetActiveAgents(DtCrowdAgentsResult* result); 24 | void Update(const float dt); 25 | }; -------------------------------------------------------------------------------- /AiNavInterop/AiNav.sln: -------------------------------------------------------------------------------- 1 |  2 | Microsoft Visual Studio Solution File, Format Version 12.00 3 | # Visual Studio Version 16 4 | VisualStudioVersion = 16.0.29519.87 5 | MinimumVisualStudioVersion = 10.0.40219.1 6 | Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}") = "AiNav", "AiNav.vcxproj", "{FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}" 7 | EndProject 8 | Global 9 | GlobalSection(SolutionConfigurationPlatforms) = preSolution 10 | Debug|x64 = Debug|x64 11 | Debug|x86 = Debug|x86 12 | Release|x64 = Release|x64 13 | Release|x86 = Release|x86 14 | EndGlobalSection 15 | GlobalSection(ProjectConfigurationPlatforms) = postSolution 16 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Debug|x64.ActiveCfg = Debug|x64 17 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Debug|x64.Build.0 = Debug|x64 18 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Debug|x86.ActiveCfg = Debug|Win32 19 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Debug|x86.Build.0 = Debug|Win32 20 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Release|x64.ActiveCfg = Release|x64 21 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Release|x64.Build.0 = Release|x64 22 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Release|x86.ActiveCfg = Release|Win32 23 | {FE4A6EFA-0093-4059-9B3E-FD37EB2DE1DD}.Release|x86.Build.0 = Release|Win32 24 | EndGlobalSection 25 | GlobalSection(SolutionProperties) = preSolution 26 | HideSolutionNode = FALSE 27 | EndGlobalSection 28 | GlobalSection(ExtensibilityGlobals) = postSolution 29 | SolutionGuid = {519176CB-C8C9-4D8A-8C02-8587E32180BC} 30 | EndGlobalSection 31 | EndGlobal 32 | -------------------------------------------------------------------------------- /AiNavInterop/AiNav.vcxproj.user: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | false 5 | 6 | -------------------------------------------------------------------------------- /AiNavInterop/AiQuery.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | #include 4 | #include "NavigationMesh.hpp" 5 | 6 | class AiQuery { 7 | private: 8 | dtNavMesh* m_navMesh = nullptr; 9 | dtNavMeshQuery* m_navQuery = nullptr; 10 | int invalidated = 0; 11 | public: 12 | AiQuery(); 13 | ~AiQuery(); 14 | int Init(NavigationMesh* navmesh, int maxNodes); 15 | void FindStraightPath(NavMeshPathfindQuery query, NavMeshPathfindResult* result); 16 | int HasPath(NavMeshPathfindQuery query); 17 | void Raycast(NavMeshRaycastQuery query, NavMeshRaycastResult* result); 18 | int SamplePosition(float3 point, float3 extent, float3* result); 19 | int GetRandomPosition(float3* result); 20 | int GetLocation(float3 point, float3 extent, float3* result); 21 | int IsValid(); 22 | void Invalidate(); 23 | }; -------------------------------------------------------------------------------- /AiNavInterop/Detour/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | file(GLOB SOURCES Source/*.cpp) 2 | 3 | if(RECASTNAVIGATION_STATIC) 4 | add_library(Detour STATIC ${SOURCES}) 5 | else() 6 | add_library(Detour SHARED ${SOURCES}) 7 | endif() 8 | 9 | add_library(RecastNavigation::Detour ALIAS Detour) 10 | 11 | set(Detour_INCLUDE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/Include") 12 | 13 | target_include_directories(Detour PUBLIC 14 | "$" 15 | ) 16 | 17 | set_target_properties(Detour PROPERTIES 18 | SOVERSION ${SOVERSION} 19 | VERSION ${VERSION} 20 | ) 21 | 22 | install(TARGETS Detour 23 | ARCHIVE DESTINATION lib 24 | LIBRARY DESTINATION lib 25 | COMPONENT library 26 | ) 27 | 28 | file(GLOB INCLUDES Include/*.h) 29 | install(FILES ${INCLUDES} DESTINATION include) 30 | -------------------------------------------------------------------------------- /AiNavInterop/Detour/Include/DetourMath.h: -------------------------------------------------------------------------------- 1 | /** 2 | @defgroup detour Detour 3 | 4 | Members in this module are wrappers around the standard math library 5 | */ 6 | 7 | #ifndef DETOURMATH_H 8 | #define DETOURMATH_H 9 | 10 | #include 11 | // This include is required because libstdc++ has problems with isfinite 12 | // if cmath is included before math.h. 13 | #include 14 | 15 | inline float dtMathFabsf(float x) { return fabsf(x); } 16 | inline float dtMathSqrtf(float x) { return sqrtf(x); } 17 | inline float dtMathFloorf(float x) { return floorf(x); } 18 | inline float dtMathCeilf(float x) { return ceilf(x); } 19 | inline float dtMathCosf(float x) { return cosf(x); } 20 | inline float dtMathSinf(float x) { return sinf(x); } 21 | inline float dtMathAtan2f(float y, float x) { return atan2f(y, x); } 22 | inline bool dtMathIsfinite(float x) { return std::isfinite(x); } 23 | 24 | #endif 25 | -------------------------------------------------------------------------------- /AiNavInterop/Detour/Source/DetourAlloc.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Copyright (c) 2009-2010 Mikko Mononen memon@inside.org 3 | // 4 | // This software is provided 'as-is', without any express or implied 5 | // warranty. In no event will the authors be held liable for any damages 6 | // arising from the use of this software. 7 | // Permission is granted to anyone to use this software for any purpose, 8 | // including commercial applications, and to alter it and redistribute it 9 | // freely, subject to the following restrictions: 10 | // 1. The origin of this software must not be misrepresented; you must not 11 | // claim that you wrote the original software. If you use this software 12 | // in a product, an acknowledgment in the product documentation would be 13 | // appreciated but is not required. 14 | // 2. Altered source versions must be plainly marked as such, and must not be 15 | // misrepresented as being the original software. 16 | // 3. This notice may not be removed or altered from any source distribution. 17 | // 18 | 19 | #include 20 | #include "DetourAlloc.h" 21 | 22 | static void *dtAllocDefault(size_t size, dtAllocHint) 23 | { 24 | return malloc(size); 25 | } 26 | 27 | static void dtFreeDefault(void *ptr) 28 | { 29 | free(ptr); 30 | } 31 | 32 | static dtAllocFunc* sAllocFunc = dtAllocDefault; 33 | static dtFreeFunc* sFreeFunc = dtFreeDefault; 34 | 35 | void dtAllocSetCustom(dtAllocFunc *allocFunc, dtFreeFunc *freeFunc) 36 | { 37 | sAllocFunc = allocFunc ? allocFunc : dtAllocDefault; 38 | sFreeFunc = freeFunc ? freeFunc : dtFreeDefault; 39 | } 40 | 41 | void* dtAlloc(size_t size, dtAllocHint hint) 42 | { 43 | return sAllocFunc(size, hint); 44 | } 45 | 46 | void dtFree(void* ptr) 47 | { 48 | if (ptr) 49 | sFreeFunc(ptr); 50 | } 51 | -------------------------------------------------------------------------------- /AiNavInterop/Detour/Source/DetourAssert.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Copyright (c) 2009-2010 Mikko Mononen memon@inside.org 3 | // 4 | // This software is provided 'as-is', without any express or implied 5 | // warranty. In no event will the authors be held liable for any damages 6 | // arising from the use of this software. 7 | // Permission is granted to anyone to use this software for any purpose, 8 | // including commercial applications, and to alter it and redistribute it 9 | // freely, subject to the following restrictions: 10 | // 1. The origin of this software must not be misrepresented; you must not 11 | // claim that you wrote the original software. If you use this software 12 | // in a product, an acknowledgment in the product documentation would be 13 | // appreciated but is not required. 14 | // 2. Altered source versions must be plainly marked as such, and must not be 15 | // misrepresented as being the original software. 16 | // 3. This notice may not be removed or altered from any source distribution. 17 | // 18 | 19 | #include "DetourAssert.h" 20 | 21 | #ifndef NDEBUG 22 | 23 | static dtAssertFailFunc* sAssertFailFunc = 0; 24 | 25 | void dtAssertFailSetCustom(dtAssertFailFunc *assertFailFunc) 26 | { 27 | sAssertFailFunc = assertFailFunc; 28 | } 29 | 30 | dtAssertFailFunc* dtAssertFailGetCustom() 31 | { 32 | return sAssertFailFunc; 33 | } 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /AiNavInterop/DetourCrowd/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | file(GLOB SOURCES Source/*.cpp) 2 | 3 | if (RECASTNAVIGATION_STATIC) 4 | add_library(DetourCrowd STATIC ${SOURCES}) 5 | else () 6 | add_library(DetourCrowd SHARED ${SOURCES}) 7 | endif () 8 | 9 | add_library(RecastNavigation::DetourCrowd ALIAS DetourCrowd) 10 | 11 | set(DetourCrowd_INCLUDE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/Include") 12 | 13 | target_include_directories(DetourCrowd PUBLIC 14 | "$" 15 | ) 16 | 17 | target_link_libraries(DetourCrowd 18 | Detour 19 | ) 20 | 21 | set_target_properties(DetourCrowd PROPERTIES 22 | SOVERSION ${SOVERSION} 23 | VERSION ${VERSION} 24 | ) 25 | 26 | install(TARGETS DetourCrowd 27 | ARCHIVE DESTINATION lib 28 | LIBRARY DESTINATION lib 29 | COMPONENT library 30 | ) 31 | 32 | file(GLOB INCLUDES Include/*.h) 33 | install(FILES ${INCLUDES} DESTINATION include) 34 | -------------------------------------------------------------------------------- /AiNavInterop/DetourTileCache/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | file(GLOB SOURCES Source/*.cpp) 2 | 3 | if (RECASTNAVIGATION_STATIC) 4 | add_library(DetourTileCache STATIC ${SOURCES}) 5 | else () 6 | add_library(DetourTileCache SHARED ${SOURCES}) 7 | endif () 8 | 9 | add_library(RecastNavigation::DetourTileCache ALIAS DetourTileCache) 10 | 11 | set(DetourTileCache_INCLUDE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/Include") 12 | 13 | target_include_directories(DetourTileCache PUBLIC 14 | "$" 15 | ) 16 | 17 | target_link_libraries(DetourTileCache 18 | Detour 19 | ) 20 | 21 | set_target_properties(DetourTileCache PROPERTIES 22 | SOVERSION ${SOVERSION} 23 | VERSION ${VERSION} 24 | ) 25 | 26 | 27 | install(TARGETS DetourTileCache 28 | ARCHIVE DESTINATION lib 29 | LIBRARY DESTINATION lib 30 | COMPONENT library 31 | ) 32 | 33 | file(GLOB INCLUDES Include/*.h) 34 | install(FILES ${INCLUDES} DESTINATION include) 35 | -------------------------------------------------------------------------------- /AiNavInterop/Navigation.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | 4 | //#pragma pack(push, 4) 5 | 6 | struct int2 7 | { 8 | int x; 9 | int y; 10 | }; 11 | 12 | typedef struct float3 13 | { 14 | float x; 15 | float y; 16 | float z; 17 | } float3; 18 | 19 | typedef struct DtBoundingBox 20 | { 21 | float3 min; 22 | float3 max; 23 | } DtBoundingBox; 24 | 25 | struct DtBuildSettings 26 | { 27 | // Bounding box for the generated navigation mesh 28 | DtBoundingBox boundingBox; 29 | float cellHeight; 30 | float cellSize; 31 | int tileSize; 32 | int2 tilePosition; 33 | int regionMinArea; 34 | int regionMergeArea; 35 | float edgeMaxLen; 36 | float edgeMaxError; 37 | float detailSampleDistInput; 38 | float detailSampleMaxErrorInput; 39 | float agentHeight; 40 | float agentRadius; 41 | float agentMaxClimb; 42 | float agentMaxSlope; 43 | }; 44 | 45 | struct DtGeneratedData 46 | { 47 | bool success; 48 | int error = 0; 49 | float3* navmeshVertices = nullptr; 50 | int numNavmeshVertices = 0; 51 | uint8_t* navmeshData = nullptr; 52 | int navmeshDataLength = 0; 53 | }; 54 | 55 | 56 | struct DtCrowdAgent 57 | { 58 | int active; 59 | int partial; 60 | float desiredSpeed; 61 | float3 position; 62 | float3 velocity; 63 | }; 64 | 65 | struct DtCrowdAgentsResult 66 | { 67 | DtCrowdAgent* agents = nullptr; 68 | int agentCount = 0; 69 | }; 70 | 71 | struct DtAgentParams { 72 | float radius; ///< Agent radius. [Limit: >= 0] 73 | float height; ///< Agent height. [Limit: > 0] 74 | float maxAcceleration; ///< Maximum allowed acceleration. [Limit: >= 0] 75 | float maxSpeed; ///< Maximum allowed speed. [Limit: >= 0] 76 | float collisionQueryRange; 77 | float pathOptimizationRange; ///< The path visibility optimization range. [Limit: > 0] 78 | float separationWeight; 79 | int anticipateTurns; 80 | int optimizeVis; 81 | int optimizeTopo; 82 | int obstacleAvoidance; 83 | int crowdSeparation; 84 | int obstacleAvoidanceType; 85 | int queryFilterType; 86 | }; 87 | 88 | //#pragma pack(pop) 89 | -------------------------------------------------------------------------------- /AiNavInterop/NavigationBuilder.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include "Recast.h" 3 | #include "Navigation.hpp" 4 | #include 5 | 6 | class NavigationBuilder 7 | { 8 | rcHeightfield* m_solid = nullptr; 9 | uint8_t* m_triareas = nullptr; 10 | rcCompactHeightfield* m_chf = nullptr; 11 | rcContourSet* m_cset = nullptr; 12 | rcPolyMesh* m_pmesh = nullptr; 13 | rcPolyMeshDetail* m_dmesh = nullptr; 14 | DtBuildSettings m_buildSettings; 15 | rcContext* m_context; 16 | 17 | // Detour returned navigation mesh data 18 | // free with dtFree() 19 | uint8_t* m_navmeshData = nullptr; 20 | int m_navmeshDataLength = 0; 21 | 22 | DtGeneratedData m_result; 23 | public: 24 | NavigationBuilder(); 25 | ~NavigationBuilder(); 26 | void Cleanup(); 27 | DtGeneratedData* BuildNavmesh(float3* vertices, int numVertices, int* indices, int numIndices, uint8_t* areas); 28 | void SetSettings(DtBuildSettings buildSettings); 29 | 30 | private: 31 | int CreateDetourMesh(); 32 | }; -------------------------------------------------------------------------------- /AiNavInterop/NavigationMesh.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | #include 4 | #include "Navigation.hpp" 5 | #include 6 | 7 | using namespace std; 8 | 9 | //#pragma pack(push, 4) 10 | struct NavMeshPathfindQuery 11 | { 12 | float3 source; 13 | float3 target; 14 | float3 findNearestPolyExtent; 15 | int maxPathPoints; 16 | }; 17 | struct NavMeshPathfindResult 18 | { 19 | bool pathFound = false; 20 | float3* pathPoints = nullptr; 21 | int numPathPoints = 0; 22 | }; 23 | 24 | struct NavMeshRaycastQuery 25 | { 26 | float3 start; 27 | float3 end; 28 | float3 findNearestPolyExtent; 29 | int maxPathPoints; 30 | }; 31 | struct NavMeshRaycastResult 32 | { 33 | bool hit = false; 34 | float3 position; 35 | float3 normal; 36 | }; 37 | //#pragma pack(pop) 38 | 39 | class NavigationMesh 40 | { 41 | private: 42 | dtNavMesh* m_navMesh = nullptr; 43 | dtNavMeshQuery* m_navQuery = nullptr; 44 | std::unordered_set m_tileRefs; 45 | public: 46 | 47 | NavigationMesh(); 48 | ~NavigationMesh(); 49 | int Init(float cellTileSize); 50 | int LoadTile(uint8_t* navData, int navDataLength); 51 | int RemoveTile(int2 tileCoordinate); 52 | void FindPath(NavMeshPathfindQuery query, NavMeshPathfindResult* result); 53 | void Raycast(NavMeshRaycastQuery query, NavMeshRaycastResult* result); 54 | int SamplePosition(float3 point, float3 extent, float3* result); 55 | int GetRandomPosition(float3* result); 56 | dtNavMesh* GetNavmesh(); 57 | dtNavMeshQuery* GetNavmeshQuery(); 58 | int GetLocation(float3 point, float3 extent, float3* result); 59 | }; 60 | -------------------------------------------------------------------------------- /AiNavInterop/Recast/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | file(GLOB SOURCES Source/*.cpp) 2 | 3 | if (RECASTNAVIGATION_STATIC) 4 | add_library(Recast STATIC ${SOURCES}) 5 | else () 6 | add_library(Recast SHARED ${SOURCES}) 7 | endif () 8 | 9 | add_library(RecastNavigation::Recast ALIAS Recast) 10 | 11 | set(Recast_INCLUDE_DIR "${CMAKE_CURRENT_SOURCE_DIR}/Include") 12 | 13 | target_include_directories(Recast PUBLIC 14 | "$" 15 | ) 16 | 17 | set_target_properties(Recast PROPERTIES 18 | SOVERSION ${SOVERSION} 19 | VERSION ${VERSION} 20 | ) 21 | 22 | install(TARGETS Recast 23 | ARCHIVE DESTINATION lib 24 | LIBRARY DESTINATION lib 25 | COMPONENT library 26 | ) 27 | 28 | file(GLOB INCLUDES Include/*.h) 29 | install(FILES ${INCLUDES} DESTINATION include) 30 | -------------------------------------------------------------------------------- /AiNavInterop/Recast/Source/RecastAssert.cpp: -------------------------------------------------------------------------------- 1 | // 2 | // Copyright (c) 2009-2010 Mikko Mononen memon@inside.org 3 | // 4 | // This software is provided 'as-is', without any express or implied 5 | // warranty. In no event will the authors be held liable for any damages 6 | // arising from the use of this software. 7 | // Permission is granted to anyone to use this software for any purpose, 8 | // including commercial applications, and to alter it and redistribute it 9 | // freely, subject to the following restrictions: 10 | // 1. The origin of this software must not be misrepresented; you must not 11 | // claim that you wrote the original software. If you use this software 12 | // in a product, an acknowledgment in the product documentation would be 13 | // appreciated but is not required. 14 | // 2. Altered source versions must be plainly marked as such, and must not be 15 | // misrepresented as being the original software. 16 | // 3. This notice may not be removed or altered from any source distribution. 17 | // 18 | 19 | #include "RecastAssert.h" 20 | 21 | #ifndef NDEBUG 22 | 23 | static rcAssertFailFunc* sRecastAssertFailFunc = 0; 24 | 25 | void rcAssertFailSetCustom(rcAssertFailFunc *assertFailFunc) 26 | { 27 | sRecastAssertFailFunc = assertFailFunc; 28 | } 29 | 30 | rcAssertFailFunc* rcAssertFailGetCustom() 31 | { 32 | return sRecastAssertFailFunc; 33 | } 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /AiNavInterop/dllmain.cpp: -------------------------------------------------------------------------------- 1 | // dllmain.cpp : Defines the entry point for the DLL application. 2 | #include "pch.h" 3 | 4 | BOOL APIENTRY DllMain( HMODULE hModule, 5 | DWORD ul_reason_for_call, 6 | LPVOID lpReserved 7 | ) 8 | { 9 | switch (ul_reason_for_call) 10 | { 11 | case DLL_PROCESS_ATTACH: 12 | case DLL_THREAD_ATTACH: 13 | case DLL_THREAD_DETACH: 14 | case DLL_PROCESS_DETACH: 15 | break; 16 | } 17 | return TRUE; 18 | } 19 | 20 | -------------------------------------------------------------------------------- /AiNavInterop/framework.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #define WIN32_LEAN_AND_MEAN // Exclude rarely-used stuff from Windows headers 4 | // Windows Header Files 5 | #include 6 | -------------------------------------------------------------------------------- /AiNavInterop/pch.cpp: -------------------------------------------------------------------------------- 1 | // pch.cpp: source file corresponding to the pre-compiled header 2 | 3 | #include "pch.h" 4 | 5 | // When you are using pre-compiled headers, this source file is necessary for compilation to succeed. 6 | -------------------------------------------------------------------------------- /AiNavInterop/pch.h: -------------------------------------------------------------------------------- 1 | // pch.h: This is a precompiled header file. 2 | // Files listed below are compiled only once, improving build performance for future builds. 3 | // This also affects IntelliSense performance, including code completion and many code browsing features. 4 | // However, files listed here are ALL re-compiled if any one of them is updated between builds. 5 | // Do not add files here that you will be updating frequently as this negates the performance advantage. 6 | 7 | #ifndef PCH_H 8 | #define PCH_H 9 | 10 | // add headers that you want to pre-compile here 11 | #include "framework.h" 12 | 13 | #endif //PCH_H 14 | -------------------------------------------------------------------------------- /AiNavInterop/x64/Release/AiNav.log: -------------------------------------------------------------------------------- 1 |  -------------------------------------------------------------------------------- /Assets/AiNav/AiNavSurface.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 58f85f75ceccc934082cef3367ae3158 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: fd3a67949551390479ad4ee32dfd0d01 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/AgentPathBuffer.cs: -------------------------------------------------------------------------------- 1 | using Unity.Entities; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | 7 | [InternalBufferCapacity(16)] 8 | public struct AgentPathBuffer : IBufferElementData 9 | { 10 | public static implicit operator float3(AgentPathBuffer e) { return e.Value; } 11 | public static implicit operator AgentPathBuffer(float3 e) { return new AgentPathBuffer { Value = e }; } 12 | 13 | public float3 Value; 14 | } 15 | } 16 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/AgentPathBuffer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4dddd5aacd54861408f1917f0c919784 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/AgentPathData.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Entities; 3 | using Unity.Mathematics; 4 | 5 | namespace AiNav 6 | { 7 | [Serializable] 8 | public struct AgentPathData : IComponentData 9 | { 10 | public int PathLength; 11 | public int CurrentIndex; 12 | 13 | public bool UsingPath; 14 | public int LastQueryResult; 15 | public float3 CurrentWaypoint; 16 | public bool HasPath; 17 | public float DistanceToDestination; 18 | public float DistanceToWaypoint; 19 | } 20 | } 21 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/AgentPathData.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 74b8fc2316a25ce49aeeefb3be85a267 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ce0549ad9d2704e49b38ff69c33b9470 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/BoxFilterAuthoring.cs: -------------------------------------------------------------------------------- 1 | using Unity.Mathematics; 2 | using UnityEngine; 3 | 4 | namespace AiNav 5 | { 6 | public class BoxFilterAuthoring : MonoBehaviour 7 | { 8 | public int SurfaceId = 1; 9 | 10 | [SerializeField] 11 | private BoxCollider Collider; 12 | [SerializeField] 13 | private Collider TestPoint; 14 | 15 | public BoxFilter BoxFilter 16 | { 17 | get 18 | { 19 | BoxFilter filter = new BoxFilter(); 20 | Bounds bounds = Collider.bounds; 21 | filter.Bounds = new DtBoundingBox(bounds.min, bounds.max); 22 | 23 | WorldBoxFilter box = new WorldBoxFilter(); 24 | box.Size = Collider.size; 25 | box.Center = Collider.center; 26 | box.TRS = float4x4.TRS(transform.position, transform.rotation, transform.localScale); 27 | 28 | filter.WorldBoxFilter = box; 29 | return filter; 30 | } 31 | } 32 | 33 | 34 | } 35 | } 36 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/BoxFilterAuthoring.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 97fe5e247d21c484299a81211eca9c0a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/LayerAttribute.cs: -------------------------------------------------------------------------------- 1 |  2 | using UnityEngine; 3 | 4 | namespace AiNav 5 | { 6 | public class LayerAttribute : PropertyAttribute 7 | { 8 | // NOTHING - just oxygen. 9 | } 10 | } 11 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/LayerAttribute.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e083b440d262ddf4097dab9f46a4e904 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/MeshSourceAuthorBase.cs: -------------------------------------------------------------------------------- 1 | using Unity.Collections; 2 | using UnityEngine; 3 | 4 | namespace AiNav 5 | { 6 | public class MeshSourceAuthorBase : MonoBehaviour 7 | { 8 | public virtual void AppendSources(int surfaceId, NativeList nonShared, NativeList shared) 9 | { 10 | 11 | } 12 | } 13 | } 14 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/MeshSourceAuthorBase.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4f6b4b0dbec1df34297c3cef5c9b33f7 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/Authoring/SimpleMeshSourceAuthor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 648754a67c0d00d43b0f22cfa9e15176 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/BoxFilter.cs: -------------------------------------------------------------------------------- 1 | using Unity.Entities; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | public struct BoxFilter : IComponentData 7 | { 8 | public DtBoundingBox Bounds; 9 | public WorldBoxFilter WorldBoxFilter; 10 | public bool Active; 11 | } 12 | 13 | public struct WorldBoxFilter 14 | { 15 | public float3 Center; 16 | public float3 Size; 17 | public float4x4 TRS; 18 | 19 | 20 | public bool ContainsPoint(float3 point) 21 | { 22 | point = TRS.WorldToLocal(point) - Center; 23 | 24 | float halfX = (Size.x * 0.5f); 25 | float halfY = (Size.y * 0.5f); 26 | float halfZ = (Size.z * 0.5f); 27 | if (point.x < halfX && point.x > -halfX && point.y < halfY && point.y > -halfY && point.z < halfZ && point.z > -halfZ) 28 | { 29 | return true; 30 | } 31 | else 32 | { 33 | return false; 34 | } 35 | } 36 | } 37 | } 38 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/BoxFilter.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6114ba9170ec88741ae01f3f56b00a50 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/MeshSource.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d47fedec96e7d6d40acaed82c2327d42 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/NavAgent.cs: -------------------------------------------------------------------------------- 1 | using Unity.Entities; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | [System.Serializable] 7 | public struct NavAgent : IComponentData 8 | { 9 | public bool Active; 10 | public int CrowdIndex; 11 | public int UpdateParams; 12 | public DtAgentParams DtAgentParams; 13 | public DtCrowdAgent DtCrowdAgent; 14 | public float3 Destination; 15 | public bool SetDestination; 16 | public bool SetDestinationFailed; 17 | 18 | public bool ClosestRandomPointOnCircle(AiNavQuery query, ref Random random, float range, out float3 closest) 19 | { 20 | float2 current = new float2(DtCrowdAgent.Position.x, DtCrowdAgent.Position.z); 21 | float2 pos = RandomPointInCircle(current, range, ref random); 22 | float3 target = new float3(pos.x, DtCrowdAgent.Position.y, pos.y); 23 | float3 extent = new float3(range, range, range); 24 | return query.SamplePosition(target, extent, out closest); 25 | } 26 | 27 | public static float2 RandomPointInCircle(float2 center, float radius, ref Random rand) 28 | { 29 | float x = rand.NextFloat(center.x - radius, center.x + radius); 30 | float y = rand.NextFloat(center.y - radius, center.y + radius); 31 | return new float2(x, y); 32 | } 33 | } 34 | 35 | } 36 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/NavAgent.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f0156cd438945b044ac4048f546a2f80 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/NavAgentDebug.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct NavAgentDebug 7 | { 8 | public NavAgent NavAgent; 9 | public AgentPathData PathData; 10 | } 11 | } 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/NavAgentDebug.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 98acc8ac02609ff408797768954bfd99 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Components/PathHandler.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 671bf9b2e43318549a9fc063e6798b70 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: fc614c760b843b74d9b0fb08d3e069ea 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/AiNavSurfaceEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 03492ec5c79b66949b4c4b82c5ceff94 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/AiNavTests.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3f51db5cd348eb140aba393862c7d839 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/EcsWorldEditor.cs: -------------------------------------------------------------------------------- 1 | using Unity.Entities; 2 | using UnityEditor; 3 | using UnityEngine; 4 | 5 | namespace AiNav 6 | { 7 | [CustomEditor(typeof(EcsWorld))] 8 | public class EcsWorldEditor : Editor 9 | { 10 | public override void OnInspectorGUI() 11 | { 12 | DrawDefaultInspector(); 13 | 14 | if (!EditorApplication.isPlaying) 15 | { 16 | if (EcsWorld.EditorModeEnabled) 17 | { 18 | GUILayout.Label("Ecs is running"); 19 | 20 | if (GUILayout.Button("StopEditorSystems")) 21 | { 22 | EcsWorld.StopEditorSystems(); 23 | } 24 | } 25 | } 26 | 27 | } 28 | } 29 | } 30 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/EcsWorldEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 66303980b574bad49a9db2e05ef74680 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/LayerAttributeEditor.cs: -------------------------------------------------------------------------------- 1 | using UnityEditor; 2 | using UnityEngine; 3 | 4 | namespace AiNav 5 | { 6 | [CustomPropertyDrawer(typeof(LayerAttribute))] 7 | class LayerAttributeEditor : PropertyDrawer 8 | { 9 | 10 | public override void OnGUI(Rect position, SerializedProperty property, GUIContent label) 11 | { 12 | // One line of oxygen free code. 13 | property.intValue = EditorGUI.LayerField(position, label, property.intValue); 14 | } 15 | } 16 | } 17 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/LayerAttributeEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0b539da61f0a22a4597a15c9bacc7cc2 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/SharedMeshDbEditor.cs: -------------------------------------------------------------------------------- 1 | using UnityEditor; 2 | using UnityEngine; 3 | 4 | namespace AiNav 5 | { 6 | [CustomEditor(typeof(SharedMeshDb))] 7 | public class SharedMeshDbEditor : Editor 8 | { 9 | public override void OnInspectorGUI() 10 | { 11 | DrawDefaultInspector(); 12 | 13 | SharedMeshDb db = (SharedMeshDb)target; 14 | 15 | if (GUILayout.Button("Add Mesh")) 16 | { 17 | db.AddMesh(); 18 | } 19 | 20 | if (GUILayout.Button("Save")) 21 | { 22 | db.Save(); 23 | } 24 | 25 | if (GUILayout.Button("AddPrimitives")) 26 | { 27 | db.AddPrimitives(); 28 | } 29 | 30 | } 31 | } 32 | } 33 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/SharedMeshDbEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ce7bef3e920f16d45ba2991d2f69ea47 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/SimpleSourceAuthorEditor.cs: -------------------------------------------------------------------------------- 1 | using UnityEditor; 2 | using UnityEngine; 3 | 4 | namespace AiNav 5 | { 6 | [CustomEditor(typeof(SimpleMeshSourceAuthor))] 7 | public class SimpleSourceAuthorEditor : Editor 8 | { 9 | public override void OnInspectorGUI() 10 | { 11 | DrawDefaultInspector(); 12 | 13 | SimpleMeshSourceAuthor author = (SimpleMeshSourceAuthor)target; 14 | 15 | if (GUILayout.Button("Add To Surface")) 16 | { 17 | author.AddToSurface(); 18 | } 19 | 20 | if (author.Current.Id > 0 && GUILayout.Button("Remove from Surface")) 21 | { 22 | author.RemoveFromSurface(); 23 | } 24 | } 25 | } 26 | } -------------------------------------------------------------------------------- /Assets/AiNav/Editor/SimpleSourceAuthorEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c7d66e8da7e93b44d82e4fe13b088ff2 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Editor/Test/NavigationTests.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6dc511c5eeff92e4084d9e22e29cf7c5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/NativeBuildUtitls.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Collections; 3 | using Unity.Mathematics; 4 | 5 | namespace AiNav 6 | { 7 | public static class NativeBuildUtitls 8 | { 9 | public static NativeList GetOverlappingTiles(NavMeshBuildSettings settings, DtBoundingBox boundingBox) 10 | { 11 | NativeList ret = new NativeList(Allocator.Temp); 12 | float tcs = settings.TileSize * settings.CellSize; 13 | float2 start = boundingBox.min.xz / tcs; 14 | float2 end = boundingBox.max.xz / tcs; 15 | 16 | int2 startTile = new int2( 17 | (int)Math.Floor(start.x), 18 | (int)Math.Floor(start.y)); 19 | int2 endTile = new int2( 20 | (int)Math.Ceiling(end.x), 21 | (int)Math.Ceiling(end.y)); 22 | 23 | for (int y = startTile.y; y < endTile.y; y++) 24 | { 25 | for (int x = startTile.x; x < endTile.x; x++) 26 | { 27 | ret.Add(new int2(x, y)); 28 | } 29 | } 30 | return ret; 31 | } 32 | } 33 | } 34 | -------------------------------------------------------------------------------- /Assets/AiNav/NativeBuildUtitls.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 178ef86e2228d0b4c8b58fbad7bc08e0 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/NavAgentMotor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c383b97644d287c4d912ea5167a5a764 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/NavMeshNativeInputBuilder.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 16f3341ba41849f46bb6fb67ad83548e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 45d5f0f41132ced49a52b8b8b3393f34 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/AiNavSurface.prefab.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6dc7c326434aca149ad6c356c3e4e522 3 | PrefabImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/BoundsFilterMaterial.mat.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7731ceb609766be41bc504ac4a999137 3 | NativeFormatImporter: 4 | externalObjects: {} 5 | mainObjectFileID: 0 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/BoxFilter.prefab.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c9ab09d55be8d5b4f988f85030c84446 3 | PrefabImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/CapsuleSource.prefab.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a8ae666f3cf24194ea71e6f9ecbe4bf5 3 | PrefabImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/SimpleMeshSourceAuthor.prefab.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 25f04b9f3788e1a43ab33a84dc283127 3 | PrefabImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/agent.mat.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3368eac3a278bdc45bad0d04ce1f0786 3 | NativeFormatImporter: 4 | externalObjects: {} 5 | mainObjectFileID: 0 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/agent.prefab.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: fc5c40f6a424f324cbd0c80babcca0d9 3 | PrefabImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/AiNav/Prefabs/surface.mat.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 33fb81643ffd7da458b37dff1fd96ee2 3 | NativeFormatImporter: 4 | externalObjects: {} 5 | mainObjectFileID: 0 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Resources.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 01ce08e4635155245bcd3fa1a256f406 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Resources/SharedMeshDb.asset: -------------------------------------------------------------------------------- 1 | %YAML 1.1 2 | %TAG !u! tag:unity3d.com,2011: 3 | --- !u!114 &11400000 4 | MonoBehaviour: 5 | m_ObjectHideFlags: 0 6 | m_CorrespondingSourceObject: {fileID: 0} 7 | m_PrefabInstance: {fileID: 0} 8 | m_PrefabAsset: {fileID: 0} 9 | m_GameObject: {fileID: 0} 10 | m_Enabled: 1 11 | m_EditorHideFlags: 0 12 | m_Script: {fileID: 11500000, guid: 53842005d8205d04a91335bbad1ffc79, type: 3} 13 | m_Name: SharedMeshDb 14 | m_EditorClassIdentifier: 15 | Name: 16 | Mesh: {fileID: 0} 17 | Meshes: 18 | - Id: 2 19 | Name: Capsule 20 | Mesh: {fileID: 10208, guid: 0000000000000000e000000000000000, type: 0} 21 | - Id: 4 22 | Name: Cube 23 | Mesh: {fileID: 10202, guid: 0000000000000000e000000000000000, type: 0} 24 | - Id: 3 25 | Name: Cylinder 26 | Mesh: {fileID: 10206, guid: 0000000000000000e000000000000000, type: 0} 27 | - Id: 1 28 | Name: Sphere 29 | Mesh: {fileID: 10207, guid: 0000000000000000e000000000000000, type: 0} 30 | -------------------------------------------------------------------------------- /Assets/AiNav/Resources/SharedMeshDb.asset.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ef6cc577196d2b541a96fca559cf9608 3 | NativeFormatImporter: 4 | externalObjects: {} 5 | mainObjectFileID: 0 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/SharedMeshDb.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 53842005d8205d04a91335bbad1ffc79 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 86b8ca18ad298474690dd3efd22a71f6 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/AiNavSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9f78ddfc20055e144ae8945d1b8ae6fc 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/AiNavTestSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: de429b4123d127542bf06460edc1d8ed 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/CrowdController.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1d23c6b1d6c67ba4ba9be66318c5c9f4 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/CrowdControllerJobs.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c7498356e678fed48902566f1c0e2bd3 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/EcsWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3d0751aeea10586419340f96b4da2c93 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6cbc20cdb68e7e44da2d82b0cf500fb8 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors/ConvexHullGeometryCollector.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f4757b4896ac8094fbb49de6992b9ced 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors/GeometryFilter.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct GeometryFilter 7 | { 8 | public bool ApplyWaterFilter; 9 | public float WaterLevel; 10 | public float WaterSpan; 11 | 12 | public bool ApplyMinHeight; 13 | public float MinHeight; 14 | 15 | public bool FilterHeight(float height) 16 | { 17 | return (ApplyMinHeight && height < MinHeight); 18 | } 19 | 20 | public bool FilterWater(float height) 21 | { 22 | if (!ApplyWaterFilter) return false; 23 | float min = WaterLevel - WaterSpan; 24 | float max = WaterLevel + WaterSpan; 25 | return (height >= min && height <= max); 26 | } 27 | } 28 | } 29 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors/GeometryFilter.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8a81944e8852e4b4db38a1a4ea7f90e5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors/MeshGeometryCollector.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f75a1f63fff8d2c4e9e0ccda6617ffe0 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors/PrimitiveGeometryCollector.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 144361e1e440bf44190a13c10c693024 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/GeometryCollectors/TerrainGeometryCollector.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 34dc20b150e6537458bc5f04db7051d2 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/MeshSourceMap.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5373a1156fb8cdf43a425afbc0bb6950 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/NavMeshStoreSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a9f0429c5464a2c4d9f1fd2aa93852c6 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/SurfaceController.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d4f6fb4f3a75af340ab8bbc46d3ababd 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/SurfaceControllerConfig.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics; 2 | 3 | namespace AiNav 4 | { 5 | public struct SurfaceControllerConfig 6 | { 7 | public int SurfaceId; 8 | public NavMeshBuildSettings BuildSettings; 9 | public NavAgentSettings AgentSettings; 10 | public int BatchSize; 11 | public bool CrowdEnabled; 12 | public GeometryFilter GeometryFilter; 13 | public CollisionFilter IncludeMask; 14 | public bool IncludeUnityPhysicsGeometry; 15 | } 16 | } 17 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/SurfaceControllerConfig.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ef3c35e61d2a6004587ee0b151136873 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/SurfaceControllerJobs.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b5ca34943e877924b87408fcb3421e02 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Systems/SurfaceData.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e79ca0250aa56ba4094a812b3efbaddc 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Util.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: fda29997354c9e54b8f049e528c28b7b 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNav/Util/AiNavExtensions.cs: -------------------------------------------------------------------------------- 1 | using Unity.Entities.Serialization; 2 | using Unity.Mathematics; 3 | using UnityEngine; 4 | 5 | namespace AiNav 6 | { 7 | public static unsafe class AiNavExtensions 8 | { 9 | public static float3 WorldToLocal(this float4x4 transform, float3 point) 10 | { 11 | return math.transform(math.inverse(transform), point); 12 | } 13 | 14 | public static float3 LocalToWorld(this float4x4 transform, float3 point) 15 | { 16 | return math.transform(transform, point); 17 | } 18 | 19 | public static float3 WorldToLocal(this RigidTransform transform, float3 point) 20 | { 21 | return math.transform(math.inverse(transform), point); 22 | } 23 | 24 | public static float3 LocalToWorld(this RigidTransform transform, float3 point) 25 | { 26 | return math.transform(transform, point); 27 | } 28 | 29 | public static RigidTransform ToRigidTransform(this Transform transform) 30 | { 31 | return new RigidTransform(transform.rotation, transform.position); 32 | } 33 | 34 | public static int ReadInt(this BinaryReader reader) 35 | { 36 | int value; 37 | reader.ReadBytes(&value, sizeof(int)); 38 | return value; 39 | } 40 | 41 | public static void Write(this BinaryWriter writer, int value) 42 | { 43 | writer.WriteBytes(&value, sizeof(int)); 44 | } 45 | 46 | } 47 | } 48 | -------------------------------------------------------------------------------- /Assets/AiNav/Util/AiNavExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d28b5c86ef3f88a4a92a78779aaa4006 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNav/Util/UnityPhysicsHelper.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics; 2 | using UnityEngine; 3 | 4 | namespace AiNav.Util 5 | { 6 | public static class UnityPhysicsHelper 7 | { 8 | public static bool HasLayer(this CollisionFilter filter, int layer) 9 | { 10 | uint mask = 1u << layer; 11 | return (filter.BelongsTo & mask) == mask; 12 | } 13 | 14 | public static CollisionFilter LayerMaskToFilter(LayerMask mask) 15 | { 16 | CollisionFilter filter = new CollisionFilter() 17 | { 18 | BelongsTo = (uint)mask.value, 19 | CollidesWith = (uint)mask.value 20 | }; 21 | return filter; 22 | } 23 | 24 | 25 | 26 | } 27 | } 28 | -------------------------------------------------------------------------------- /Assets/AiNav/Util/UnityPhysicsHelper.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 96fff3989ee40634c86f3a55d8bef670 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/AiCrowd.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4633f1eb168e24d47baa556ba08f43f0 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/AiNavMesh.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 69a87d3fedd4c0d46b22aa23a5ecb78a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/AiNavQuery.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: afd7e3467271ffe4caceaea101698d48 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/AiNavWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ba8f02acad66d6b4581ec85aba2beaae 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 79cc5bbcb5b691a4c9d230f060bedfcc 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/AiNativeArray.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Collections.LowLevel.Unsafe; 3 | 4 | namespace AiNav.Collections 5 | { 6 | public unsafe struct AiNativeArray where T : unmanaged 7 | { 8 | public int Length => m_Data->Length; 9 | [NativeDisableUnsafePtrRestriction] 10 | private UnsafeArrayData* m_Data; 11 | 12 | public int SizeOf 13 | { 14 | get 15 | { 16 | return UnsafeCollectionUtility.SizeOf() * Length; 17 | } 18 | } 19 | 20 | public T this[int i] 21 | { 22 | get 23 | { 24 | return m_Data->ReadElement(i); 25 | } 26 | 27 | set 28 | { 29 | m_Data->WriteElement(i, value); 30 | } 31 | } 32 | 33 | public AiNativeArray(int length) 34 | { 35 | if (length <= 0) 36 | { 37 | throw new ArgumentException("Length must be > 0"); 38 | } 39 | 40 | m_Data = UnsafeArrayData.Create(UnsafeCollectionUtility.SizeOf(), length); 41 | } 42 | 43 | public void* GetUnsafePtr() 44 | { 45 | return m_Data->GetUnsafePtr(); 46 | } 47 | 48 | public void Dispose() 49 | { 50 | UnsafeArrayData.Destroy(m_Data); 51 | m_Data = null; 52 | } 53 | 54 | public AiNativeList ToNativeList() 55 | { 56 | var data = UnsafeListData.CreateFrom(this); 57 | AiNativeList list = new AiNativeList(data); 58 | Dispose(); 59 | return list; 60 | } 61 | 62 | } 63 | } 64 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/AiNativeArray.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 87da649de34854745b9c1f1b8952bdee 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/AiNativeList.cs: -------------------------------------------------------------------------------- 1 | using System.Runtime.InteropServices; 2 | using Unity.Collections.LowLevel.Unsafe; 3 | 4 | namespace AiNav.Collections 5 | { 6 | [StructLayout(LayoutKind.Sequential)] 7 | public unsafe struct AiNativeList where T : unmanaged 8 | { 9 | public int Capacity => m_ListData->Capacity; 10 | public int Length => m_ListData->Length; 11 | [NativeDisableUnsafePtrRestriction] 12 | private UnsafeListData* m_ListData; 13 | 14 | public T this[int i] 15 | { 16 | get 17 | { 18 | return m_ListData->ReadElement(i); 19 | } 20 | 21 | set 22 | { 23 | m_ListData->WriteElement(i, value); 24 | } 25 | } 26 | 27 | public AiNativeList(UnsafeListData* m_ListData) 28 | { 29 | this.m_ListData = m_ListData; 30 | } 31 | 32 | public AiNativeList(int initialCapacity) 33 | { 34 | m_ListData = UnsafeListData.Create(UnsafeCollectionUtility.SizeOf(), initialCapacity); 35 | } 36 | 37 | public void Clear() 38 | { 39 | m_ListData->Clear(); 40 | } 41 | 42 | public void Add(T value) 43 | { 44 | m_ListData->Add(value); 45 | } 46 | 47 | public void AddRange(AiNativeList list) 48 | { 49 | m_ListData->AddRange(list.m_ListData->Ptr, list.Length); 50 | } 51 | 52 | public void RemoveAtSwapBack(int index) 53 | { 54 | m_ListData->RemoveAtSwapBack(index); 55 | } 56 | 57 | public void* GetUnsafePtr() 58 | { 59 | return m_ListData->GetUnsafePtr(); 60 | } 61 | 62 | public void Dispose() 63 | { 64 | UnsafeListData.Destroy(m_ListData); 65 | } 66 | 67 | } 68 | } 69 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/AiNativeList.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 100a9ffe3ef1b5e4c9ddf0084a8af7d9 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/CollectionStore.cs: -------------------------------------------------------------------------------- 1 | using System.IO; 2 | 3 | namespace AiNav.Collections 4 | { 5 | public class CollectionStore 6 | { 7 | 8 | 9 | } 10 | } 11 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/CollectionStore.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: cb9edf5a9838aa141885c4366f78b26e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/MemoryCopy.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d6346f7a17043724ca1cd65e2cb98eba 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/UnsafeArrayData.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6def32cf8357ef24a95828af4428a124 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/UnsafeCollectionExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 2029c7035ee37d341973a3e46df997fc 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/UnsafeCollectionUtility.cs: -------------------------------------------------------------------------------- 1 | namespace AiNav.Collections 2 | { 3 | public static unsafe class UnsafeCollectionUtility 4 | { 5 | public static int SizeOf() where T : unmanaged 6 | { 7 | return sizeof(T); 8 | } 9 | 10 | public static int CeilPow2(int i) 11 | { 12 | i -= 1; 13 | i |= i >> 1; 14 | i |= i >> 2; 15 | i |= i >> 4; 16 | i |= i >> 8; 17 | i |= i >> 16; 18 | return i + 1; 19 | } 20 | 21 | public static T ReadArrayElement(void* ptr, int index) where T : unmanaged 22 | { 23 | T* array = (T*)ptr; 24 | return array[index]; 25 | } 26 | 27 | public static void WriteArrayElement(void* ptr, int index, T value) where T : unmanaged 28 | { 29 | T* array = (T*)ptr; 30 | array[index] = value; 31 | } 32 | 33 | 34 | 35 | 36 | } 37 | } 38 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/UnsafeCollectionUtility.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 82ce5d90deb5aaa41b1bab33347e21b4 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Collections/UnsafeListData.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: cbc6fb811cc7e8341bc47b9b761d8403 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavAgentSettings.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct NavAgentSettings 7 | { 8 | /// 9 | /// Height of the actor 10 | /// 11 | /// 12 | /// The height of the entities in this group. Entities can't enter areas with ceilings lower than this value. 13 | /// 14 | public float Height; 15 | 16 | /// 17 | /// Maximum vertical distance this agent can climb 18 | /// 19 | /// 20 | /// The maximum height that entities in this group can climb. 21 | /// 22 | public float MaxClimb; 23 | 24 | /// 25 | /// Maximum slope angle this agent can climb 26 | /// 27 | /// 28 | /// The maximum incline (in degrees) that entities in this group can climb. Entities can't go up or down slopes higher than this value. 29 | /// 30 | public float MaxSlope; 31 | 32 | /// 33 | /// Radius of the actor 34 | /// 35 | /// 36 | /// The larger this value, the larger the area of the navigation mesh entities use. Entities can't pass through gaps of less than twice the radius. 37 | /// 38 | public float Radius; 39 | 40 | public static NavAgentSettings Default() 41 | { 42 | return new NavAgentSettings 43 | { 44 | Height = 2.0f, 45 | MaxClimb = 0.4f, 46 | MaxSlope = 45f, 47 | Radius = 0.5f, 48 | }; 49 | } 50 | 51 | } 52 | } 53 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavAgentSettings.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0da7b8476fefef64c8d26b980214440e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuildInput.cs: -------------------------------------------------------------------------------- 1 | using Unity.Collections.LowLevel.Unsafe; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | public unsafe struct NavMeshBuildInput 7 | { 8 | public NavMeshTileBounds TileBounds; 9 | 10 | [NativeDisableUnsafePtrRestriction] 11 | public float3* Vertices; 12 | public int VerticesLength; 13 | 14 | [NativeDisableUnsafePtrRestriction] 15 | public int* Indices; 16 | public int IndicesLength; 17 | 18 | [NativeDisableUnsafePtrRestriction] 19 | public byte* Areas; 20 | public int AreasLength; 21 | } 22 | } 23 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuildInput.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: fa69457b0e085c54db8e43ef49b50c8e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuildResult.cs: -------------------------------------------------------------------------------- 1 | using System.Globalization; 2 | 3 | namespace AiNav 4 | { 5 | public struct NavMeshBuildResult 6 | { 7 | public int Result; 8 | public int TilesBuilt; 9 | public int VerticeCount; 10 | public int TriangleCount; 11 | 12 | public bool IsValidBuild 13 | { 14 | get 15 | { 16 | return (Result == 0 || Result == 110); 17 | } 18 | } 19 | 20 | public override string ToString() 21 | { 22 | return string.Format(CultureInfo.CurrentCulture, "Result:{0} TilesBuilt:{1} VerticeCount:{2} TriangleCount:{3}", Result, TilesBuilt, VerticeCount, TriangleCount); 23 | } 24 | } 25 | 26 | } 27 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuildResult.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ce4747a9d3feae9459d299994cd683c0 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuildSettings.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e759dea47d78d6646bc722470953dcdb 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuildUtils.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e61bc3a243cdcfb4c82b16ab7c8075ff 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuilder.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 2dba89fae142b674f903445b9126b633 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuilderSettings.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct NavMeshBuilderSettings 7 | { 8 | public int Id; 9 | public NavMeshBuildSettings BuildSettings; 10 | public NavAgentSettings AgentSettings; 11 | 12 | public NavMeshBuilderSettings(int id, NavMeshBuildSettings buildSettings, NavAgentSettings agentSettings) 13 | { 14 | Id = id; 15 | BuildSettings = buildSettings; 16 | AgentSettings = agentSettings; 17 | } 18 | } 19 | } 20 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshBuilderSettings.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4d00db2892f8e0d4297b7e8e14548bbc 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshInputBuilder.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e85bc3eff422eec42a631c382d05bb0d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshTestData.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c866cc68d0e9f5b42b68234c19f058e7 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshTile.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 08894dd2515e0fa49a46b38b0e795146 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshTileBounds.cs: -------------------------------------------------------------------------------- 1 | using Unity.Mathematics; 2 | 3 | namespace AiNav 4 | { 5 | public struct NavMeshTileBounds 6 | { 7 | public int2 Coord; 8 | public DtBoundingBox Bounds; 9 | 10 | public NavMeshTileBounds(int2 coord, DtBoundingBox bounds) 11 | { 12 | Coord = coord; 13 | Bounds = bounds; 14 | } 15 | } 16 | } 17 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavMeshTileBounds.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ef97805f30956864d9597d215a78aa7f 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavQuerySettings.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | [Serializable] 7 | public struct NavQuerySettings 8 | { 9 | /// 10 | /// The default settings that are used when querying navigation meshes 11 | /// 12 | public static readonly NavQuerySettings Default = new NavQuerySettings 13 | { 14 | FindNearestPolyExtent = new float3(2.0f, 4.0f, 2.0f), 15 | MaxPathPoints = 512, 16 | }; 17 | 18 | /// 19 | /// Used as the extend for the find nearest poly bounding box used when scanning for a polygon corresponding to the given starting/ending position. 20 | /// Making this bigger will allow you to find paths that allow the entity to start further away or higher from the navigation mesh bounds for example 21 | /// 22 | public float3 FindNearestPolyExtent; 23 | 24 | /// 25 | /// The maximum number of path points used internally and also the maximum number of output points 26 | /// 27 | public int MaxPathPoints; 28 | } 29 | } 30 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavQuerySettings.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3a653ca7f8e76794aa1493f5251bb91e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ff41f8c355124ff469e11dfeb7fd60fd 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtAgentParams.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1352ced6446025f41be81a80955a8c38 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtArea.cs: -------------------------------------------------------------------------------- 1 | namespace AiNav 2 | { 3 | public static class DtArea 4 | { 5 | public const byte NULL = 0; 6 | public const byte WALKABLE = 63; 7 | } 8 | } 9 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtArea.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8d1d737c83cc86c4da0ed6bc9e87b288 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtBoundingBox.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 840a6d18eefd82a4cbc6da6410e08f82 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtBuildSettings.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | [Serializable] 7 | public struct DtBuildSettings 8 | { 9 | public DtBoundingBox BoundingBox; 10 | public float CellHeight; 11 | public float CellSize; 12 | public int TileSize; 13 | public int2 TilePosition; 14 | public int RegionMinArea; 15 | public int RegionMergeArea; 16 | public float EdgeMaxLen; 17 | public float EdgeMaxError; 18 | public float DetailSampleDist; 19 | public float DetailSampleMaxError; 20 | public float AgentHeight; 21 | public float AgentRadius; 22 | public float AgentMaxClimb; 23 | public float AgentMaxSlope; 24 | } 25 | } 26 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtBuildSettings.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: cd877402c20740042986b9b323f59664 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtCrowdAgent.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Entities; 3 | using Unity.Mathematics; 4 | 5 | namespace AiNav 6 | { 7 | [Serializable] 8 | public struct DtCrowdAgent : IComponentData 9 | { 10 | public int Active; 11 | public int Partial; 12 | public float DesiredSpeed; 13 | public float3 Position; 14 | public float3 Velocity; 15 | } 16 | } 17 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtCrowdAgent.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3d09cb462eb56f7438b08fe693a496df 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtCrowdAgentsResult.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct DtCrowdAgentsResult 7 | { 8 | public IntPtr Agents; 9 | public int AgentCount; 10 | } 11 | } 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtCrowdAgentsResult.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b92f4c913d472f944802f57266423345 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtGeneratedData.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct DtGeneratedData 7 | { 8 | public bool Success; 9 | public int Error; 10 | public IntPtr NavmeshVertices; 11 | public int NumNavmeshVertices; 12 | public IntPtr NavmeshData; 13 | public int NavmeshDataLength; 14 | } 15 | } 16 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtGeneratedData.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b74e2de1b1753fd4ab3d17b6dad3819d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtPathFindQuery.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | [Serializable] 7 | public struct DtPathFindQuery 8 | { 9 | public float3 Source; 10 | public float3 Target; 11 | public float3 FindNearestPolyExtent; 12 | public int MaxPathPoints; 13 | } 14 | } 15 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtPathFindQuery.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6ed50f7cb0263b54e8e49f339752468b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtPathFindResult.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public struct DtPathFindResult 7 | { 8 | public bool PathFound; 9 | 10 | /// 11 | /// Should point to a preallocated array of 's matching the amount in 12 | /// 13 | public IntPtr PathPoints; 14 | 15 | public int NumPathPoints; 16 | } 17 | } 18 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtPathFindResult.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 38cd0b785df7fc54d871bb63490d9c2d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtPoly.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public unsafe struct DtPoly 7 | { 8 | public uint FirstLink; 9 | public fixed ushort Vertices[6]; 10 | public fixed ushort Neighbours[6]; 11 | public ushort Flags; 12 | public byte VertexCount; 13 | public byte AreaAndType; 14 | } 15 | } 16 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtPoly.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: eb749581cd0695b4b829273e0f1ea813 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtRaycastQuery.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | [Serializable] 7 | public struct DtRaycastQuery 8 | { 9 | public float3 Source; 10 | public float3 Target; 11 | public float3 FindNearestPolyExtent; 12 | public int MaxPathPoints; 13 | } 14 | } 15 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtRaycastQuery.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f221931108f5e32449ef969137b0e7a6 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtRaycastResult.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Mathematics; 3 | 4 | namespace AiNav 5 | { 6 | [Serializable] 7 | public struct DtRaycastResult 8 | { 9 | public bool Hit; 10 | public float3 Position; 11 | public float3 Normal; 12 | } 13 | } 14 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtRaycastResult.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 07fac44663bc5c7489db6e50dae8a919 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtTileHeader.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | 3 | namespace AiNav 4 | { 5 | [Serializable] 6 | public unsafe struct DtTileHeader 7 | { 8 | public int Magic; 9 | public int Version; 10 | public int X; 11 | public int Y; 12 | public int Layer; 13 | public uint UserId; 14 | public int PolyCount; 15 | public int VertCount; 16 | public int MaxLinkCount; 17 | public int DetailMeshCount; 18 | public int DetailVertCount; 19 | public int DetailTriCount; 20 | public int BvNodeCount; 21 | public int OffMeshConCount; 22 | public int OffMeshBase; 23 | public float WalkableHeight; 24 | public float WalkableRadius; 25 | public float WalkableClimb; 26 | public fixed float Bmin[3]; 27 | public fixed float Bmax[3]; 28 | public float BvQuantFactor; 29 | } 30 | } 31 | -------------------------------------------------------------------------------- /Assets/AiNavCore/NavTypes/DtTileHeader.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0f87f10223dc20b4dbd3fdfc13abd7c0 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Navigation.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c8c2e27452f8dd94ea9692fdf6d1c605 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Util.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3decdeb69badfe24f94730bb1cf81502 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Util/GameClock.cs: -------------------------------------------------------------------------------- 1 | namespace AiNav 2 | { 3 | public struct GameClock 4 | { 5 | public const float MainTickRate = 30f; 6 | public float TimeBetweenTicks; 7 | public float LastTick; 8 | 9 | public GameClock(float interval, bool asTicksPerSecond = true) 10 | { 11 | if (asTicksPerSecond) 12 | { 13 | TimeBetweenTicks = 1000f / interval / 1000f; 14 | } 15 | else 16 | { 17 | TimeBetweenTicks = interval; 18 | } 19 | 20 | LastTick = 0f; 21 | } 22 | 23 | public static bool NetworkTick(float time, float interval, ref float lastTick) 24 | { 25 | float timeBetweenTicks = 1000f / interval / 1000f; 26 | var since = time - lastTick; 27 | if (since >= timeBetweenTicks) 28 | { 29 | lastTick = time; 30 | return true; 31 | } 32 | else 33 | { 34 | return false; 35 | } 36 | } 37 | 38 | public static bool Tick(float time, float timeBetweenTicks, ref float lastTick) 39 | { 40 | var since = time - lastTick; 41 | if (since >= timeBetweenTicks) 42 | { 43 | lastTick = time; 44 | return true; 45 | } 46 | else 47 | { 48 | return false; 49 | } 50 | } 51 | 52 | public bool Tick(float time) 53 | { 54 | var since = time - LastTick; 55 | if (since >= TimeBetweenTicks) 56 | { 57 | LastTick = time; 58 | return true; 59 | } 60 | else 61 | { 62 | return false; 63 | } 64 | } 65 | 66 | } 67 | } 68 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Util/GameClock.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 10d7dfd89c5c4ed4681cb6fc4611646f 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Util/NavExtensions.cs: -------------------------------------------------------------------------------- 1 | using Unity.Mathematics; 2 | 3 | namespace AiNav 4 | { 5 | public static class NavExtensions 6 | { 7 | public const float Epsilon = 1.17549435E-38f; 8 | 9 | public static bool Approximately(float a, float b) 10 | { 11 | return math.abs(b - a) < math.max(0.000001f * math.max(math.abs(a), math.abs(b)), Epsilon * 8); 12 | } 13 | 14 | public static bool Approximately(this float3 self, float3 other) 15 | { 16 | return Approximately(self.x, other.x) && Approximately(self.y, other.y) && Approximately(self.z, other.z); 17 | } 18 | 19 | public static bool Approximately(this DtBoundingBox self, DtBoundingBox other) 20 | { 21 | return Approximately(self.min, other.min) && Approximately(self.max, other.max); 22 | } 23 | } 24 | } 25 | -------------------------------------------------------------------------------- /Assets/AiNavCore/Util/NavExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 89a401dd185182a4da54241918359a43 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/Plugins/x86_64.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4120b3a344cb663489d04bcc4d85cf6e 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/Plugins/x86_64/AiNav.dll: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/Plugins/x86_64/AiNav.dll -------------------------------------------------------------------------------- /Assets/Plugins/x86_64/AiNav.dll.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1324f37a69d47ec4d866962fc91916f8 3 | PluginImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | iconMap: {} 7 | executionOrder: {} 8 | defineConstraints: [] 9 | isPreloaded: 0 10 | isOverridable: 0 11 | isExplicitlyReferenced: 0 12 | validateReferences: 1 13 | platformData: 14 | - first: 15 | Any: 16 | second: 17 | enabled: 1 18 | settings: {} 19 | - first: 20 | Editor: Editor 21 | second: 22 | enabled: 0 23 | settings: 24 | CPU: x86_64 25 | DefaultValueInitialized: true 26 | - first: 27 | Standalone: Linux64 28 | second: 29 | enabled: 1 30 | settings: 31 | CPU: x86_64 32 | - first: 33 | Standalone: OSXUniversal 34 | second: 35 | enabled: 0 36 | settings: 37 | CPU: x86_64 38 | - first: 39 | Standalone: Win 40 | second: 41 | enabled: 0 42 | settings: 43 | CPU: None 44 | - first: 45 | Standalone: Win64 46 | second: 47 | enabled: 1 48 | settings: 49 | CPU: AnyCPU 50 | userData: 51 | assetBundleName: 52 | assetBundleVariant: 53 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/CHANGELOG.md.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 259e073a32ee4df42be6858276d2f51d 3 | TextScriptImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/glossary.md: -------------------------------------------------------------------------------- 1 | Glossary 2 | ========= 3 | 4 | | Term | Description | 5 | |--|---| 6 | |Inertia Tensor| Describes the mass distribtuion of a rigid body. In paricular it effects how the angular velocity of a body can change. See [Moment of inertia](https://en.wikipedia.org/wiki/Moment_of_inertia) | 7 | |Center of mass (COM) | Forces applied to the [center of mass](https://en.wikipedia.org/wiki/Center_of_mass) will push the body in the direction of the force without causing rotation 8 | |Convex shape| A convex shape or volume has the property that a line segment drawn between any two points inside the volume never leaves the volume. We exploit this property to accelerate the performance of collision detection and spatial queries. 9 | | Degree of Freedom (DOF) | A describtion of how a linear system is free to move. In rigid body dynamcis we usualy refer to the 6 degrees of freedom a body has when moving in free space. These are 3 linear and 3 angular degress of freedom. The correspond to the axes you specify when describing a constraint. | 10 | | Convex Radius (Bevel Radius) | To improve the performance and robustness of collision detection we allow contacts to be generated within a small tolerance of the surface of a convex shape. This tolerance is referred to as convex radius or bevel radius. | 11 | |Jacobian|Typically describes a constraint used during constraint solving. See [Jacobian](https://en.wikipedia.org/wiki/Jacobian_matrix_and_determinant)| 12 | 13 | 14 | [Back to Index](index.md) 15 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/BoxShape.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/BoxShape.png -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/Compunds.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/Compunds.gif -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/CompundsH.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/CompundsH.png -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/Convex_Hull_Teapot.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/Convex_Hull_Teapot.png -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/DynamicBody.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/DynamicBody.png -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/StaticBody.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/StaticBody.png -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/StepPhysics.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/StepPhysics.png -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/closest_points.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/closest_points.gif -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/closest_points_all_hits.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/closest_points_all_hits.gif -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/images/collider_cast_queries.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Documentation~/images/collider_cast_queries.gif -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/index.md: -------------------------------------------------------------------------------- 1 | Introduction to Unity Physics 2 | ====== 3 | 4 | Unity Physics is a deterministic rigid body dynamics system and spatial query system written from the ground up using the Unity data oriented tech stack. Unity Physics originates from a close collaboration between Unity and the Havok Physics team at Microsoft. 5 | 6 | ## About these documents 7 | 8 | These are very early stage documents which will be extended over time. Please read through the Design Philosophy and Getting Started at least, which should give you an good overview of how to use the physics system at a high level. As the code settles down we will add more explanation on how to modify the simulation and expand on how the algorithms work. The most up to date use of Unity Physics is the Samples for it in the main DOTs sample repository and they cover a wide range of use cases not yet covered in these documents, such as character controllers, ray cast driven cars, and examples of all the joints. 9 | 10 | ## Read 11 | 12 | * [Design Philosophy](design.md) 13 | * [Getting started](getting_started.md) 14 | * [Collision queries](collision_queries.md) 15 | * [Core components](core_components.md) 16 | * [Modifying simulation behaviour](simulation_modification.md) 17 | * [Glossary](glossary.md) 18 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/runtime_overview.md: -------------------------------------------------------------------------------- 1 | 2 | Please come back later, work in progress. 3 | 4 | [Back to Index](index.md) 5 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Documentation~/simulation_results.md: -------------------------------------------------------------------------------- 1 | 2 | Please come back later, work in progress. 3 | 4 | [Back to Index](index.md) 5 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/LICENSE.md: -------------------------------------------------------------------------------- 1 | Unity Physics copyright © 2019 Unity Technologies ApS 2 | 3 | Licensed under the Unity Companion License for Unity-dependent projects--see [Unity Companion License](http://www.unity3d.com/legal/licenses/Unity_Companion_License). 4 | 5 | Unless expressly provided otherwise, the Software under this license is made available strictly on an “AS IS” BASIS WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED. Please review the license for details on these and other terms and conditions. 6 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/LICENSE.md.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 22e65f34478919449b3105ce7bcafd7f 3 | TextScriptImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d756f2269480e3b4895796bafd6bcfbd 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/AssemblyInfo.cs: -------------------------------------------------------------------------------- 1 | using System.Runtime.CompilerServices; 2 | 3 | [assembly: InternalsVisibleTo("Unity.Physics.EditModeTests")] -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/AssemblyInfo.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7b3cc3eb9b3304aaabd9bef2198277a3 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editor.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 683bc849d791a4714930b4563e0b66cc 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ab526351563b84e9a82eed9f3e7b3f22 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/CustomPhysicsBodyTagNames Icon.psd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/CustomPhysicsBodyTagNames Icon.psd -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/CustomPhysicsMaterialTagNames Icon.psd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/CustomPhysicsMaterialTagNames Icon.psd -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/PhysicsCategoryNames Icon.psd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/PhysicsCategoryNames Icon.psd -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/PhysicsMaterialTemplate Icon.psd: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/gamemachine/ainav/d47134bfe548a43e05f2fc0f2add4d3b853ccb67/Assets/UnityPhysics/Unity.Physics.Editor/Editor/Resources/PhysicsMaterialTemplate Icon.psd -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/EditorTools.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: eafd2df9888a843d98dad6b614dda084 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/EditorTools/BeveledBoxBoundsHandle.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3d159761cbfd64ab4b45c185b806856c 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/EditorTools/BeveledCylinderBoundsHandle.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7a64b7883aec4411eb5718b49553d58a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a40c9f4dd335149c8aebb97c6fe09e12 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/BaseEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0459f91158f584084a9b3f9d3efe572a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/CustomPhysicsBodyTagNamesEditor.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics.Authoring; 2 | using UnityEditor; 3 | using UnityEditorInternal; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Editor 7 | { 8 | [CustomEditor(typeof(CustomPhysicsBodyTagNames))] 9 | [CanEditMultipleObjects] 10 | class CustomPhysicsBodyTagNamesEditor : BaseEditor 11 | { 12 | #pragma warning disable 649 13 | [AutoPopulate(ElementFormatString = "Custom Physics Body Tag {0}", Resizable = false, Reorderable = false)] 14 | ReorderableList m_TagNames; 15 | #pragma warning restore 649 16 | } 17 | } 18 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/CustomPhysicsBodyTagNamesEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7b821b5ae31ad42ea8d1fdbe7afc9a3a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/CustomPhysicsMaterialTagNamesEditor.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics.Authoring; 2 | using UnityEditor; 3 | using UnityEditorInternal; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Editor 7 | { 8 | [CustomEditor(typeof(CustomPhysicsMaterialTagNames))] 9 | [CanEditMultipleObjects] 10 | class CustomPhysicsMaterialTagNamesEditor : BaseEditor 11 | { 12 | #pragma warning disable 649 13 | [AutoPopulate(ElementFormatString = "Custom Physics Material Tag {0}", Resizable = false, Reorderable = false)] 14 | ReorderableList m_TagNames; 15 | #pragma warning restore 649 16 | } 17 | } 18 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/CustomPhysicsMaterialTagNamesEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 381742f9fa30c4306b9067a7e36f6cb1 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/PhysicsBodyAuthoringEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 174eb3fcbd301439589b61d0568ab6b5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/PhysicsCategoryNamesEditor.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics.Authoring; 2 | using UnityEditor; 3 | using UnityEditorInternal; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Editor 7 | { 8 | [CustomEditor(typeof(PhysicsCategoryNames))] 9 | [CanEditMultipleObjects] 10 | class PhysicsCategoryNamesEditor : BaseEditor 11 | { 12 | #pragma warning disable 649 13 | [AutoPopulate(ElementFormatString = "Category {0}", Resizable = false, Reorderable = false)] 14 | ReorderableList m_CategoryNames; 15 | #pragma warning restore 649 16 | } 17 | } 18 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/PhysicsCategoryNamesEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a26a407942e11406eb77bf271e041364 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Editors/PhysicsShapeAuthoringEditor.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6b059aae3b9b54e05acdf7b88a1b8447 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5906842964bca4d179d3cef1d1db2752 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/BaseDrawer.cs: -------------------------------------------------------------------------------- 1 | using UnityEditor; 2 | using UnityEngine; 3 | 4 | namespace Unity.Physics.Editor 5 | { 6 | abstract class BaseDrawer : PropertyDrawer 7 | { 8 | protected abstract bool IsCompatible(SerializedProperty property); 9 | 10 | public override float GetPropertyHeight(SerializedProperty property, GUIContent label) 11 | { 12 | return IsCompatible(property) 13 | ? EditorGUI.GetPropertyHeight(property) 14 | : EditorGUIUtility.singleLineHeight; 15 | } 16 | 17 | public override void OnGUI(Rect position, SerializedProperty property, GUIContent label) 18 | { 19 | if (IsCompatible(property)) 20 | DoGUI(position, property, label); 21 | else 22 | EditorGUIControls.DisplayCompatibilityWarning(position, label, ObjectNames.NicifyVariableName(GetType().Name)); 23 | } 24 | 25 | protected abstract void DoGUI(Rect position, SerializedProperty property, GUIContent label); 26 | } 27 | } 28 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/BaseDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 259c5757af5a441ddb6fce219e7ee22d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/EnumFlagsDrawer.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Physics.Authoring; 3 | using UnityEditor; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Editor 7 | { 8 | [CustomPropertyDrawer(typeof(EnumFlagsAttribute))] 9 | class EnumFlagsDrawer : BaseDrawer 10 | { 11 | protected override bool IsCompatible(SerializedProperty property) 12 | { 13 | return property.propertyType == SerializedPropertyType.Enum; 14 | } 15 | 16 | protected override void DoGUI(Rect position, SerializedProperty property, GUIContent label) 17 | { 18 | EditorGUI.BeginProperty(position, label, property); 19 | 20 | var value = property.longValue; 21 | EditorGUI.BeginChangeCheck(); 22 | value = Convert.ToInt64( 23 | EditorGUI.EnumFlagsField(position, label, (Enum)Enum.ToObject(fieldInfo.FieldType, value)) 24 | ); 25 | if (EditorGUI.EndChangeCheck()) 26 | property.longValue = value; 27 | 28 | EditorGUI.EndProperty(); 29 | } 30 | } 31 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/EnumFlagsDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: feb062e63d134472d97507fdf53a0a03 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/EulerAnglesDrawer.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics.Authoring; 2 | using UnityEditor; 3 | using UnityEngine; 4 | 5 | namespace Unity.Physics.Editor 6 | { 7 | [CustomPropertyDrawer(typeof(EulerAngles))] 8 | class EulerAnglesDrawer : BaseDrawer 9 | { 10 | protected override bool IsCompatible(SerializedProperty property) => true; 11 | 12 | public override float GetPropertyHeight(SerializedProperty property, GUIContent label) 13 | { 14 | var value = property.FindPropertyRelative(nameof(EulerAngles.Value)); 15 | return EditorGUI.GetPropertyHeight(value); 16 | } 17 | 18 | protected override void DoGUI(Rect position, SerializedProperty property, GUIContent label) 19 | { 20 | var value = property.FindPropertyRelative(nameof(EulerAngles.Value)); 21 | EditorGUI.PropertyField(position, value, label, true); 22 | } 23 | } 24 | } 25 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/EulerAnglesDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6685365a7ded846d6836b0f4f8c9ce36 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/ExpandChildrenDrawer.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics.Authoring; 2 | using UnityEditor; 3 | using UnityEngine; 4 | 5 | namespace Unity.Physics.Editor 6 | { 7 | [CustomPropertyDrawer(typeof(ExpandChildrenAttribute))] 8 | class ExpandChildrenDrawer : PropertyDrawer 9 | { 10 | public override float GetPropertyHeight(SerializedProperty property, GUIContent label) 11 | { 12 | property.isExpanded = true; 13 | return EditorGUI.GetPropertyHeight(property) 14 | - EditorGUIUtility.standardVerticalSpacing 15 | - EditorGUIUtility.singleLineHeight; 16 | } 17 | 18 | public override void OnGUI(Rect position, SerializedProperty property, GUIContent label) 19 | { 20 | var endProperty = property.GetEndProperty(); 21 | var childProperty = property.Copy(); 22 | childProperty.NextVisible(true); 23 | while (!SerializedProperty.EqualContents(childProperty, endProperty)) 24 | { 25 | position.height = EditorGUI.GetPropertyHeight(childProperty); 26 | OnChildPropertyGUI(position, childProperty); 27 | position.y += position.height + EditorGUIUtility.standardVerticalSpacing; 28 | childProperty.NextVisible(false); 29 | } 30 | } 31 | 32 | protected virtual void OnChildPropertyGUI(Rect position, SerializedProperty childProperty) 33 | { 34 | EditorGUI.PropertyField(position, childProperty, true); 35 | } 36 | } 37 | } 38 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/ExpandChildrenDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0f5af7bcfa14d4f7dbc94fc8b718a674 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/PhysicsMaterialCoefficientDrawer.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Physics.Authoring; 3 | using UnityEditor; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Editor 7 | { 8 | [CustomPropertyDrawer(typeof(PhysicsMaterialCoefficient))] 9 | class PhysicsMaterialCoefficientDrawer : BaseDrawer 10 | { 11 | static class Styles 12 | { 13 | public const float PopupWidth = 100f; 14 | } 15 | 16 | public override float GetPropertyHeight(SerializedProperty property, GUIContent label) => 17 | EditorGUIUtility.singleLineHeight; 18 | 19 | protected override bool IsCompatible(SerializedProperty property) => true; 20 | 21 | protected override void DoGUI(Rect position, SerializedProperty property, GUIContent label) 22 | { 23 | EditorGUI.BeginProperty(position, label, property); 24 | EditorGUI.PropertyField( 25 | new Rect(position) { xMax = position.xMax - Styles.PopupWidth }, 26 | property.FindPropertyRelative("Value"), 27 | label 28 | ); 29 | 30 | var indent = EditorGUI.indentLevel; 31 | EditorGUI.indentLevel = 0; 32 | EditorGUI.PropertyField( 33 | new Rect(position) { xMin = position.xMax - Styles.PopupWidth + EditorGUIUtility.standardVerticalSpacing }, 34 | property.FindPropertyRelative("CombineMode"), 35 | GUIContent.none 36 | ); 37 | EditorGUI.indentLevel = indent; 38 | EditorGUI.EndProperty(); 39 | } 40 | } 41 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/PhysicsMaterialCoefficientDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f6db3d3a916df49d1a0d65c3d08bfe8b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/PhysicsMaterialPropertiesDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ae8a5d9aeb3ea4f4babf68a9f13b35ec 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/SoftRangeDrawer.cs: -------------------------------------------------------------------------------- 1 | using Unity.Physics.Authoring; 2 | using UnityEditor; 3 | using UnityEngine; 4 | 5 | namespace Unity.Physics.Editor 6 | { 7 | [CustomPropertyDrawer(typeof(SoftRangeAttribute))] 8 | class SoftRangeDrawer : BaseDrawer 9 | { 10 | protected override bool IsCompatible(SerializedProperty property) 11 | { 12 | return property.propertyType == SerializedPropertyType.Float; 13 | } 14 | 15 | protected override void DoGUI(Rect position, SerializedProperty property, GUIContent label) 16 | { 17 | var attr = attribute as SoftRangeAttribute; 18 | EditorGUIControls.SoftSlider( 19 | position, label, property, attr.SliderMin, attr.SliderMax, attr.TextFieldMin, attr.TextFieldMax 20 | ); 21 | } 22 | } 23 | } 24 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/SoftRangeDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 66d1f8dbd2117405797f3d5878493cad 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/PropertyDrawers/TagsDrawer.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7da5b5fe0a1044383855fa6636355801 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Unity.Physics.Editor.asmdef: -------------------------------------------------------------------------------- 1 | { 2 | "name": "Unity.Physics.Editor", 3 | "references": [ 4 | "Unity.Burst", 5 | "Unity.Collections", 6 | "Unity.Entities", 7 | "Unity.Entities.Hybrid", 8 | "Unity.Mathematics", 9 | "Unity.Physics", 10 | "Unity.Physics.Hybrid", 11 | "Unity.Rendering.Hybrid", 12 | "Unity.Transforms", 13 | "Unity.Transforms.Hybrid" 14 | ], 15 | "optionalUnityReferences": [], 16 | "includePlatforms": [ 17 | "Editor" 18 | ], 19 | "excludePlatforms": [], 20 | "allowUnsafeCode": true, 21 | "overrideReferences": false, 22 | "precompiledReferences": [], 23 | "autoReferenced": true, 24 | "defineConstraints": [], 25 | "versionDefines": [] 26 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Unity.Physics.Editor.asmdef.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3438610b0a83016488db5062ec247a8d 3 | AssemblyDefinitionImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Utilities.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a04730b2070d44cd1a3133a8e230ea92 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Utilities/EditorGUIControls.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: abf92f81058974f0982c3044a98a9714 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Utilities/ManipulatorUtility.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using Unity.Mathematics; 3 | using UnityEngine; 4 | 5 | namespace Unity.Physics.Editor 6 | { 7 | enum MatrixState 8 | { 9 | UniformScale, 10 | NonUniformScale, 11 | ZeroScale, 12 | NotValidTRS 13 | } 14 | 15 | static class ManipulatorUtility 16 | { 17 | public static MatrixState GetMatrixState(ref float4x4 localToWorld) 18 | { 19 | if ( 20 | localToWorld.c0.w != 0f 21 | || localToWorld.c1.w != 0f 22 | || localToWorld.c2.w != 0f 23 | || localToWorld.c3.w != 1f 24 | ) 25 | return MatrixState.NotValidTRS; 26 | 27 | var m = new float3x3(localToWorld.c0.xyz, localToWorld.c1.xyz, localToWorld.c2.xyz); 28 | var lossyScale = new float3(math.length(m.c0.xyz), math.length(m.c1.xyz), math.length(m.c2.xyz)); 29 | if (math.determinant(m) < 0f) 30 | lossyScale.x *= -1f; 31 | if (math.lengthsq(lossyScale) == 0f) 32 | return MatrixState.ZeroScale; 33 | return math.abs(math.cmax(lossyScale)) - math.abs(math.cmin(lossyScale)) > 0.000001f 34 | ? MatrixState.NonUniformScale 35 | : MatrixState.UniformScale; 36 | } 37 | } 38 | } 39 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Utilities/ManipulatorUtility.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e7f1e24965b5e4bdca131f81969355bf 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Utilities/SceneViewUtility.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8aae5a02b6a294bd2a5c150759f2069b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Editor/Utilities/StatusMessageUtility.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c7772707c1b94ae295e3c02212d90095 3 | timeCreated: 1548100553 -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b0ac81b0cc8fb4bcaade4b098324ddd7 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/AssemblyInfo.cs: -------------------------------------------------------------------------------- 1 | using System.Runtime.CompilerServices; 2 | 3 | [assembly: InternalsVisibleTo("Unity.Physics.Editor")] 4 | [assembly: InternalsVisibleTo("Unity.Physics.EditModeTests")] 5 | [assembly: InternalsVisibleTo("Unity.Physics.PlayModeTests")] -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/AssemblyInfo.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 03c38d1c6355841b1aeed1a2b3cb81dd 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 536d9b526ab0f4734b47b8c78c155daf 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/CustomPhysicsBodyTagNames.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Linq; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Authoring 7 | { 8 | [CreateAssetMenu(menuName = "DOTS/Physics/Custom Physics Body Tag Names", fileName = "Custom Physics Body Tag Names")] 9 | public sealed class CustomPhysicsBodyTagNames : ScriptableObject, ITagNames 10 | { 11 | CustomPhysicsBodyTagNames() { } 12 | 13 | public IReadOnlyList TagNames => m_TagNames; 14 | [SerializeField] 15 | string[] m_TagNames = Enumerable.Range(0, 8).Select(i => string.Empty).ToArray(); 16 | 17 | void OnValidate() 18 | { 19 | if (m_TagNames.Length != 8) 20 | Array.Resize(ref m_TagNames, 8); 21 | } 22 | } 23 | } 24 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/CustomPhysicsBodyTagNames.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 88efd917f005949179616107eb6085f3 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {fileID: 2800000, guid: 55405dd19d77f49ec8577b3a1141b42b, type: 3} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/CustomPhysicsMaterialTagNames.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Linq; 4 | using UnityEngine; 5 | using UnityEngine.Serialization; 6 | 7 | namespace Unity.Physics.Authoring 8 | { 9 | interface ITagNames 10 | { 11 | IReadOnlyList TagNames { get; } 12 | } 13 | 14 | [CreateAssetMenu(menuName = "DOTS/Physics/Custom Physics Material Tag Names", fileName = "Custom Material Tag Names")] 15 | public sealed partial class CustomPhysicsMaterialTagNames : ScriptableObject, ITagNames 16 | { 17 | CustomPhysicsMaterialTagNames() { } 18 | 19 | public IReadOnlyList TagNames => m_TagNames; 20 | [SerializeField] 21 | [FormerlySerializedAs("m_FlagNames")] 22 | string[] m_TagNames = Enumerable.Range(0, 8).Select(i => string.Empty).ToArray(); 23 | 24 | void OnValidate() 25 | { 26 | if (m_TagNames.Length != 8) 27 | Array.Resize(ref m_TagNames, 8); 28 | } 29 | } 30 | } 31 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/CustomPhysicsMaterialTagNames.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7c8956dd10f66427faa4a4067c5dd97d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {fileID: 2800000, guid: 7c7a0159cb0d5433b90c970978f6cf5c, type: 3} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/PhysicsCategoryNames.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using System.Collections.Generic; 3 | using System.Linq; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Authoring 7 | { 8 | [CreateAssetMenu(menuName = "DOTS/Physics/Physics Category Names", fileName = "Physics Category Names")] 9 | public sealed class PhysicsCategoryNames : ScriptableObject, ITagNames 10 | { 11 | PhysicsCategoryNames() { } 12 | 13 | IReadOnlyList ITagNames.TagNames => CategoryNames; 14 | public IReadOnlyList CategoryNames => m_CategoryNames; 15 | [SerializeField] 16 | string[] m_CategoryNames = Enumerable.Range(0, 32).Select(i => string.Empty).ToArray(); 17 | 18 | void OnValidate() 19 | { 20 | if (m_CategoryNames.Length != 32) 21 | Array.Resize(ref m_CategoryNames, 32); 22 | } 23 | } 24 | } 25 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/PhysicsCategoryNames.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: cea4b49c4d6784a3291bea84d8086c8e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {fileID: 2800000, guid: 269c31d3570d84742a0d8739b06d5a18, type: 3} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/PhysicsMaterialTemplate.cs: -------------------------------------------------------------------------------- 1 | using System; 2 | using UnityEngine; 3 | 4 | namespace Unity.Physics.Authoring 5 | { 6 | [CreateAssetMenu(menuName = "DOTS/Physics/Physics Material Template")] 7 | public sealed partial class PhysicsMaterialTemplate : ScriptableObject, IPhysicsMaterialProperties 8 | { 9 | PhysicsMaterialTemplate() { } 10 | 11 | public bool IsTrigger { get => m_Value.IsTrigger; set => m_Value.IsTrigger = value; } 12 | 13 | public PhysicsMaterialCoefficient Friction { get => m_Value.Friction; set => m_Value.Friction = value; } 14 | public PhysicsMaterialCoefficient Restitution { get => m_Value.Restitution; set => m_Value.Restitution = value; } 15 | 16 | public PhysicsCategoryTags BelongsTo { get => m_Value.BelongsTo; set => m_Value.BelongsTo = value; } 17 | 18 | public PhysicsCategoryTags CollidesWith { get => m_Value.CollidesWith; set => m_Value.CollidesWith = value; } 19 | 20 | public bool RaisesCollisionEvents 21 | { 22 | get => m_Value.RaisesCollisionEvents; 23 | set => m_Value.RaisesCollisionEvents = value; 24 | } 25 | 26 | public CustomPhysicsMaterialTags CustomTags { get => m_Value.CustomTags; set => m_Value.CustomTags = value; } 27 | 28 | [SerializeField] 29 | PhysicsMaterialProperties m_Value = new PhysicsMaterialProperties(false); 30 | 31 | void OnValidate() => PhysicsMaterialProperties.OnValidate(ref m_Value, false); 32 | } 33 | } 34 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Assets/PhysicsMaterialTemplate.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 79f877434772c463192af154345455c9 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {fileID: 2800000, guid: dea88969a14a54552b290b80692e0785, type: 3} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Components.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0d77a02ce9849480b9c0ecbc455073d2 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Components/PhysicsBodyAuthoring.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ccea9ea98e38942e0b0938c27ed1903e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Components/PhysicsDebugDisplayAuthoring.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: bb54ea4f67dc17342bcd49954c53502d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Components/PhysicsShapeAuthoring.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b275e5f92732148048d7b77e264ac30e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Components/PhysicsStepAuthoring.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4d30974bf68d61043b1572197db94cdc 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: dca549f9b288d45d392f556b8bd2ac01 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/BaseShapeConversionSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4a56c3660f8ff41798691d34fb7630f3 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/ConversionExtensions.cs: -------------------------------------------------------------------------------- 1 | using Unity.Entities; 2 | using Unity.Mathematics; 3 | using Unity.Transforms; 4 | using UnityEngine; 5 | 6 | namespace Unity.Physics.Authoring 7 | { 8 | static class ConversionExtensions 9 | { 10 | internal static void AddOrSetComponent(this EntityManager manager, Entity entity, T value) 11 | where T : struct, IComponentData 12 | { 13 | if (!manager.HasComponent(entity)) 14 | manager.AddComponentData(entity, value); 15 | else if (!TypeManager.IsZeroSized(TypeManager.GetTypeIndex())) 16 | manager.SetComponentData(entity, value); 17 | } 18 | 19 | internal static void RemoveParentAndSetWorldTranslationAndRotation(this EntityManager manager, Entity entity, Transform worldTransform) 20 | { 21 | manager.RemoveComponent(entity); 22 | manager.RemoveComponent(entity); 23 | manager.AddOrSetComponent(entity, new Translation { Value = worldTransform.position }); 24 | manager.AddOrSetComponent(entity, new Rotation { Value = worldTransform.rotation }); 25 | if (math.lengthsq((float3)worldTransform.lossyScale - new float3(1f)) > 0f) 26 | { 27 | // bake in composite scale 28 | var compositeScale = math.mul( 29 | math.inverse(float4x4.TRS(worldTransform.position, worldTransform.rotation, 1f)), 30 | worldTransform.localToWorldMatrix 31 | ); 32 | manager.AddOrSetComponent(entity, new CompositeScale { Value = compositeScale }); 33 | } 34 | // TODO: revisit whether or not NonUniformScale/Scale should be preserved along with ParentScaleInverse instead 35 | manager.RemoveComponent(entity); 36 | manager.RemoveComponent(entity); 37 | } 38 | } 39 | } 40 | 41 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/ConversionExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5e1cb9623bd494b5bb4bc812da88c7a7 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/LegacyColliderConversionSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0a60928f473384760b8b9ece4d81a8af 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/LegacyRigidbodyConversionSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e1f8d968837784bd28087085e97040f9 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/PhysicsBodyConversionSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 04450748c0c43499bbae25b99d736c76 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Conversion/PhysicsShapeConversionSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: acd55f5f1097e43ce8eb22700a265fe6 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Data.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 32b93acb4de214bdbaf6e45c9efd5979 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Data/CustomPhysicsBodyTags.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 02fcddea751f04e248cd86cff1d8bbd7 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Data/CustomPhysicsMaterialTags.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 05cffa1394b6f481ca7e686dfc6404b9 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Data/PhysicsCategoryTags.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: eddb92a6422c54928b2fb196e49c81d6 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Data/PhysicsMaterialProperties.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c1e08ac6ebe62466ea40565d8591ae9e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Deprecated.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6a45bdd781a2044948bfd7633f6f4b02 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/PropertyAttributes.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8636ccd2301bb41d896662e81681697e 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/PropertyAttributes/PropertyAttributes.cs: -------------------------------------------------------------------------------- 1 | using UnityEngine; 2 | 3 | namespace Unity.Physics.Authoring 4 | { 5 | sealed class EnumFlagsAttribute : PropertyAttribute {} 6 | sealed class ExpandChildrenAttribute : PropertyAttribute {} 7 | sealed class SoftRangeAttribute : PropertyAttribute 8 | { 9 | public readonly float SliderMin; 10 | public readonly float SliderMax; 11 | public float TextFieldMin { get; set; } 12 | public float TextFieldMax { get; set; } 13 | 14 | public SoftRangeAttribute(float min, float max) 15 | { 16 | SliderMin = TextFieldMin = min; 17 | SliderMax = TextFieldMax = max; 18 | } 19 | } 20 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/PropertyAttributes/PropertyAttributes.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d0db1130e6fc44abea606b6aefc06d82 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Unity.Physics.Hybrid.asmdef: -------------------------------------------------------------------------------- 1 | { 2 | "name": "Unity.Physics.Hybrid", 3 | "references": [ 4 | "Unity.Burst", 5 | "Unity.Collections", 6 | "Unity.Entities", 7 | "Unity.Entities.Hybrid", 8 | "Unity.Mathematics", 9 | "Unity.Physics", 10 | "Unity.Scenes.Hybrid", 11 | "Unity.Transforms" 12 | ], 13 | "optionalUnityReferences": [], 14 | "includePlatforms": [], 15 | "excludePlatforms": [], 16 | "allowUnsafeCode": true, 17 | "overrideReferences": false, 18 | "precompiledReferences": [], 19 | "autoReferenced": true, 20 | "defineConstraints": [], 21 | "versionDefines": [] 22 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Unity.Physics.Hybrid.asmdef.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e00140a815de944528348782854abe39 3 | AssemblyDefinitionImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 97b3e5c1bb3194eb496a256796e4b428 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/ConvexHullGenerationParametersExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 604da30f59bed4d458c29f4c359d7f1c 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3b38fbd742f0e6b45bfcb2562c4c736a 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DebugStream.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5bbe9c6c1adee0b40bb4a382595b2994 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayBroadphaseSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 70e89a22f5bb2544a85f3d8aad4ceead 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayColliderBoundingVolumeSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4af8c92c2fe59bb4a8e4345ac0eb2a8c 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayCollidersSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c4a80566cda492d448fef3998e5422d5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayCollisionEventsSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: deb7cde93d0c3c241a183811d83b89ac 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayContactsSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: da12b23e95dd67a4c9b9f475c52713c5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayJointsSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1e5519c0d7e56104f97392ab7aec2f17 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayMassPropertiesSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5d8c8225a9bb32748b1f69645f6284c5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DebugDisplay/DisplayTriggerEventsSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9a598846d29b2c54981e4a1fed75cc31 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/DrawingUtility.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a0e5dbdd622ec4bacb50dcea88ad86ff 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.Hybrid/Utilities/PhysicsShapeExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f4fc8685ca8bc4f45970ed1527afa7a5 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9e791559801dc2f4a9e9bb8a46108f7a 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/AOTHint.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d6db7e52f60fc42669dc821242584c9f 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/AssemblyInfo.cs: -------------------------------------------------------------------------------- 1 | using System.Runtime.CompilerServices; 2 | 3 | [assembly: InternalsVisibleTo("Unity.Physics.Editor")] 4 | [assembly: InternalsVisibleTo("Unity.Physics.Hybrid")] 5 | [assembly: InternalsVisibleTo("Unity.Physics.PlayModeTests")] 6 | [assembly: InternalsVisibleTo("Havok.Physics")] 7 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/AssemblyInfo.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9c385b5fbd362444bbd618a13566348f 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: cd322267fa2826e409316c89d05b8387 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 29bc5e9d0c9987647a6932bddc3a6db0 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers/BlobArray.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 49d0dc3a3bc127147b3420421377e499 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers/BlockStream.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c85764b393ecf0b4a8648fc31266fd21 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers/ElementPool.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5187615741f91bd4b80ca2007f9bc579 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers/NativeListTemp.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6c106f77a62b241e7ad89ad37044defe 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers/UnsafeEx.cs: -------------------------------------------------------------------------------- 1 | using Unity.Collections.LowLevel.Unsafe; 2 | 3 | namespace Unity.Physics 4 | { 5 | internal static class UnsafeEx 6 | { 7 | internal unsafe static int CalculateOffset(ref T value, ref U baseValue) 8 | where T : struct 9 | where U : struct 10 | { 11 | return (int) ((byte*) UnsafeUtility.AddressOf(ref value) - (byte*) UnsafeUtility.AddressOf(ref baseValue)); 12 | } 13 | 14 | internal unsafe static int CalculateOffset(void* value, ref T baseValue) 15 | where T : struct 16 | { 17 | return (int) ((byte*) value - (byte*)UnsafeUtility.AddressOf(ref baseValue)); 18 | } 19 | } 20 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Containers/UnsafeEx.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6c7fe0f69b4864606908ee4a47baa83b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Jobs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ea3f41c5b39b2464aa0932d5cf85adfa 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Jobs/IJobParallelForDeferExtensionsPhysics.cs: -------------------------------------------------------------------------------- 1 | using Unity.Collections; 2 | using Unity.Collections.LowLevel.Unsafe; 3 | 4 | namespace Unity.Jobs 5 | { 6 | internal static class IJobParallelForDeferExtensionsPhysics 7 | { 8 | unsafe public static JobHandle ScheduleUnsafeIndex0(this T jobData, NativeArray forEachCount, int innerloopBatchCount, JobHandle dependsOn = new JobHandle()) 9 | where T : struct, IJobParallelForDefer 10 | { 11 | return IJobParallelForDeferExtensions.Schedule(jobData, (int*)NativeArrayUnsafeUtility.GetUnsafeBufferPointerWithoutChecks(forEachCount), innerloopBatchCount, dependsOn); 12 | } 13 | } 14 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Jobs/IJobParallelForDeferExtensionsPhysics.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 179a16a546d724e26bacd57ff77d3ff2 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9c6f4b21fb3059b40afab58fe2bb229b 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math/Aabb.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9208347103400a44ea72e5751c586b5b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math/FourTransposedAabbs.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 0dad76fe03d740b41af1e74b728f3a29 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math/FourTransposedPoints.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d877f2d6b4313ce4eb845c29b2c31854 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math/Math.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 33a80ac9dac48424fa0c83610894c5d9 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math/Physics_Transform.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c068a7f887800b6439bdfadebeaf5370 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Base/Math/Plane.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8eacc3e3090b56d4e946e9ed8a91cd96 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 90afa0e9b4d1a8942a560d58ff9ca1a9 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5b5d25f928a3a0345862d29b2fd5267a 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/CompoundCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 022919aecaeb0814ca98f7be88471f8d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/ConvexCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e26fa93df59e9204193fa06106f41a50 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/CylinderCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: ce7d3a97fe8af400fbfd020418a33b6e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/Physics_BoxCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 590f28f9b75ed8b49a21ffde288bc964 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/Physics_CapsuleCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f519d9beb59076e4586312e6003761b7 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/Physics_Collider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 9352fc7b395c33348bbc0ba7168c141b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/Physics_MeshCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 85fcd7cb4600caf479471441afd9e328 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/Physics_SphereCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 2387c719c7b0ce14b98f8299ce776499 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/Physics_TerrainCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d38972ad213478d42982f0abd915140c 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Colliders/PolygonCollider.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 89076eda5a01bef48af3cade362f455b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Filter.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b108c05cd8d763248ab6d782c289e0b0 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Filter/CollisionFilter.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f7ac5aa207b29ff47815e5ba3c81cc04 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d1708614f77857b4b9d2e1c9cc0c599f 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry/BoundingVolumeHierarchy.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1c4f1bd7578251443bf35dbf8dadc021 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry/BoundingVolumeHierarchyBuilder.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: dabe461abef50cb47a33cb29a4e01f8b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry/ConvexHull.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d99169bd34b3b3044bc330f8bd6666b6 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry/ConvexHullBuilder.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: bef4505d9d53cf144b284b839a755640 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry/Mesh.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d32c929c965478641b2f367080c60872 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Geometry/MeshBuilder.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8ae9aaedb8c908048b860130036ccb16 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b3ed586dd01c9f044b17d18c46942354 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/Collector.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4bcb5862f42a8d744be66aced5cd05f4 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/Collidable.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b3620834b66d9f046925e0d6a275b8c2 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/ColliderCast.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1d24d042594cff64299a5ef3681e304a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/ConvexConvexDistance.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 55cb3c5abf2aca04680b44c0db1bb91f 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/ConvexConvexManifold.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 2885c4bd4a7b7c84792883bae410ae3b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/Distance.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5a84c8eace8256047b5d285f712fee6b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/Manifold.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7af89d6754d0f5a4eaf4dc05dfd11c49 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/Overlap.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 32c964965c6520341a464e63284a6514 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/Queries/Raycast.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 926cb3d162207f649bd8ae9326fe6f8e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/RigidBody.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d8f9a1bb6c3efc647af89ad4aa86d3f4 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/RigidBody/RigidBody.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 2399ddd9d733dbc48bfd114f8c1779f4 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/World.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 4592463c2e408b74f9aedc284dd9c037 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/World/Broadphase.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 290f7d3360f57104bb02d3e7b56f9a30 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Collision/World/CollisionWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 67ee297e4011cb44abd9059ed2790b6a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Deprecated.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 499a4fbfa532c47ce88941996bb3f3dd 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a73b940bb36d7d74a843a6da6b74ab1d 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Integrator.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 3cc0cca878c14374496004736b408eee 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Integrator/Integrator.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6b6541aa033c9c649afef26fb467e3eb 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f9d102141c6347c4faad2054fb4bbe3e 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/AngularLimit1DJacobian.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a34e365e99ef51f4d93fa95efbb69854 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/AngularLimit2DJacobian.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a0e5ac4c1f05c904aa3a2aefda712342 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/AngularLimit3DJacobian.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: f3a650279a219ff48afd0f45ac019834 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/ContactJacobian.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e841cafb297d7264b96b8666fcf50b55 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/ContactJacobianMemoryLayout.md.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 49d4596482a51304aa5667cdb92739b2 3 | TextScriptImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/Jacobian.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 892ccbfa9987bf146824f83a1a61c99e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Jacobians/LinearLimitJacobian.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 77f86213ff6ec294c81256924cb80962 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Joint.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 817adfd99fec7e24da9c0b5d202f9ce5 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Joint/Physics_Joint.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a82ae0efcfd30bb448a0cb00b56c6d5c 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Material.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 6c211415bce8b5c4c85ddd4105d3e108 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Material/Material.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7582e9a4ecc6ccf47aa57dea13c0a77b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Motion.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 519d32bb505b2404d88c9b179ece1867 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Motion/Motion.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: c7b267e845e91994baf4187f9b164356 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 767d058def2cc8342a09fcbd047953b3 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/Callbacks.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 51189c121a7b38c41b73d4af759b6112 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/CollisionEvent.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7c67c7ab7d270b444ada82bad13229e0 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/IBodyPairsJob.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 5c5bc18b30f3fa54bbe2e1e6deb2bf70 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/ICollisionEventsJob.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 651d88e20aa180843a79a25652c2c0e3 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/IContactsJob.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 13af4a6c6b897f344b77885b8e70760f 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/IJacobiansJob.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a073d4fc854a6fc4fba3df264bf988db 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/ITriggerEventsJob.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1cc22b36eac902f4d85e76eab88d6676 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/Narrowphase.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7b554e745bb005b4a9207ac29e7ca457 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/Scheduler.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7d662241278573340a75d854ddbb6a34 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/Simulation.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 7c8ffabd78945a642a104fc69e47632a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Simulation/TriggerEvent.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b8c1254b3cb27cc43913ee90e61176bc 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Solver.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 69562b715cf0a5d429c6ac27988868a2 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Solver/SimplexSolver.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a69c4121605d86c4ca4399973a021c05 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/Solver/Solver.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: a9a01ed1e821673408422b7dbafe07db 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/World.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: b0addde1f67b55f4bbf082edb61471b8 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/World/DynamicsWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 32d62e05bbda8c349a4ce193cf204bf9 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Dynamics/World/PhysicsWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 13a1abaf4e91aa9499d8d47c6ef6d036 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e8a3010b2dc8ed1419e46a540a0f5885 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Components.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 2253b9138ed1902489400cde00ac0ddc 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Components/PhysicsComponents.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 67edda1429582534b86e23ec5d8a45e1 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Systems.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d7b6e50205875cf4ebcd255989782277 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Systems/BuildPhysicsWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: d6b780b01ab1d8e4284cd4a6864aa69d 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Systems/EndFramePhysicsSystem.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 369a2c039808333439a2d533242edc61 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Systems/ExportPhysicsWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: fa4059b3a77bf49439090e1f91c00a4a 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/ECS/Systems/StepPhysicsWorld.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 8e4907e965e300a4cb878ad3f28eea25 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Extensions.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 63fbef8049effb54782de0fa93a42b2d 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Extensions/World.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: e7e857ea0f222db4fa22ef9b9b0a29c7 3 | folderAsset: yes 4 | DefaultImporter: 5 | externalObjects: {} 6 | userData: 7 | assetBundleName: 8 | assetBundleVariant: 9 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Extensions/World/ComponentExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 97c7f410dbf04ed49874c1a38df8286e 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Extensions/World/PhysicsWorldExtensions.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 52fef0fd9effe5e4a8a11931342d2a4b 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Unity.Physics.asmdef: -------------------------------------------------------------------------------- 1 | { 2 | "name": "Unity.Physics", 3 | "references": [ 4 | "Unity.Burst", 5 | "Unity.Collections", 6 | "Unity.Entities", 7 | "Unity.Mathematics", 8 | "Unity.Transforms", 9 | "Unity.Jobs" 10 | ], 11 | "optionalUnityReferences": [], 12 | "includePlatforms": [], 13 | "excludePlatforms": [], 14 | "allowUnsafeCode": true, 15 | "overrideReferences": false, 16 | "precompiledReferences": [], 17 | "autoReferenced": true, 18 | "defineConstraints": [], 19 | "versionDefines": [ 20 | { 21 | "name": "com.havok.physics", 22 | "expression": "0.0.0", 23 | "define": "HAVOK_PHYSICS_EXISTS" 24 | }, 25 | { 26 | "name": "com.unity.entities", 27 | "expression": "0.2.0-preview", 28 | "define": "UNITY_ENTITIES_0_2_0_OR_NEWER" 29 | } 30 | ] 31 | } -------------------------------------------------------------------------------- /Assets/UnityPhysics/Unity.Physics/Unity.Physics.asmdef.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 63afb046c8423dd448ae7aba042ea63d 3 | AssemblyDefinitionImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/UnityPhysicsMods.cs.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 1d02d7997fd0b994bbbdf1339de8eeb8 3 | MonoImporter: 4 | externalObjects: {} 5 | serializedVersion: 2 6 | defaultReferences: [] 7 | executionOrder: 0 8 | icon: {instanceID: 0} 9 | userData: 10 | assetBundleName: 11 | assetBundleVariant: 12 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "displayName": "Unity Physics", 3 | "category": "Unity", 4 | "description": "Unity's C# stateless physics library. This package is still in experimental phase.", 5 | "dependencies": { 6 | "com.unity.burst": "1.1.2", 7 | "com.unity.entities": "0.1.1-preview", 8 | "com.unity.test-framework.performance": "1.0.9-preview" 9 | }, 10 | "keywords": [ 11 | "unity", 12 | "physics" 13 | ], 14 | "name": "com.unity.physics", 15 | "unity": "2019.1", 16 | "unityRelease": "10f1", 17 | "version": "0.2.4-preview", 18 | "repository": { 19 | "type": "git", 20 | "url": "git@github.com:Unity-Technologies/Unity.Physics.git", 21 | "revision": "ce0179b7dc93da3591848c0a5eec740d5b394f95" 22 | } 23 | } 24 | -------------------------------------------------------------------------------- /Assets/UnityPhysics/package.json.meta: -------------------------------------------------------------------------------- 1 | fileFormatVersion: 2 2 | guid: 952190cfedfe3ac4abb4da4b2b94aec4 3 | TextScriptImporter: 4 | externalObjects: {} 5 | userData: 6 | assetBundleName: 7 | assetBundleVariant: 8 | -------------------------------------------------------------------------------- /LICENSE.md: -------------------------------------------------------------------------------- 1 | Unity Companion License 2 | 3 | 4 | AiNav borrowed a good chunk of code from Xenko although it's been heavily modified for the most part. That was under the MIT license. Recast is the Zlib license. AiNativeArray/AiNativeList borrow heavily from Unity's container design. 5 | --------------------------------------------------------------------------------