├── .gitignore ├── .gitmodules ├── GMVPhy ├── GMVPhy.vcxproj ├── GMVPhy.vcxproj.filters ├── MiscFuncs.cpp ├── MiscFuncs.h ├── PhysCollision.cpp ├── PhysCollision.h ├── PhysConstraint.cpp ├── PhysConstraint.h ├── PhysEnv.cpp ├── PhysEnv.h ├── PhysObj.cpp ├── PhysObj.h ├── PhysSoftBody.cpp ├── PhysSoftBody.h ├── PhysVehicle.cpp ├── PhysVehicle.h ├── main.cpp └── premake4.lua ├── LICENSE ├── README.md ├── build.sh ├── bullet ├── license.txt ├── make │ └── Makefile ├── msvc │ ├── BulletCollision │ │ ├── BulletCollision.vcxproj │ │ └── BulletCollision.vcxproj.filters │ ├── BulletDynamics │ │ ├── BulletDynamics.vcxproj │ │ └── BulletDynamics.vcxproj.filters │ ├── BulletMultiThreaded │ │ ├── BulletMultiThreaded.vcxproj │ │ ├── BulletMultiThreaded.vcxproj.filters │ │ ├── ThreadPool.cpp │ │ └── ThreadPool.h │ ├── BulletSoftBody │ │ ├── BulletSoftBody.vcxproj │ │ └── BulletSoftBody.vcxproj.filters │ └── LinearMath │ │ ├── LinearMath.vcxproj │ │ └── LinearMath.vcxproj.filters ├── proj │ ├── premake4 │ └── premake4.lua └── src │ ├── Bullet-C-Api.h │ ├── BulletCollision │ ├── BroadphaseCollision │ │ ├── btAxisSweep3.cpp │ │ ├── btAxisSweep3.h │ │ ├── btBroadphaseInterface.h │ │ ├── btBroadphaseProxy.cpp │ │ ├── btBroadphaseProxy.h │ │ ├── btCollisionAlgorithm.cpp │ │ ├── btCollisionAlgorithm.h │ │ ├── btDbvt.cpp │ │ ├── btDbvt.h │ │ ├── btDbvtBroadphase.cpp │ │ ├── btDbvtBroadphase.h │ │ ├── btDispatcher.cpp │ │ ├── btDispatcher.h │ │ ├── btMultiSapBroadphase.cpp │ │ ├── btMultiSapBroadphase.h │ │ ├── btOverlappingPairCache.cpp │ │ ├── btOverlappingPairCache.h │ │ ├── btOverlappingPairCallback.h │ │ ├── btQuantizedBvh.cpp │ │ ├── btQuantizedBvh.h │ │ ├── btSimpleBroadphase.cpp │ │ └── btSimpleBroadphase.h │ ├── CollisionDispatch │ │ ├── SphereTriangleDetector.cpp │ │ ├── SphereTriangleDetector.h │ │ ├── btActivatingCollisionAlgorithm.cpp │ │ ├── btActivatingCollisionAlgorithm.h │ │ ├── btBox2dBox2dCollisionAlgorithm.cpp │ │ ├── btBox2dBox2dCollisionAlgorithm.h │ │ ├── btBoxBoxCollisionAlgorithm.cpp │ │ ├── btBoxBoxCollisionAlgorithm.h │ │ ├── btBoxBoxDetector.cpp │ │ ├── btBoxBoxDetector.h │ │ ├── btCollisionConfiguration.h │ │ ├── btCollisionCreateFunc.h │ │ ├── btCollisionDispatcher.cpp │ │ ├── btCollisionDispatcher.h │ │ ├── btCollisionObject.cpp │ │ ├── btCollisionObject.h │ │ ├── btCollisionObjectWrapper.h │ │ ├── btCollisionWorld.cpp │ │ ├── btCollisionWorld.h │ │ ├── btCompoundCollisionAlgorithm.cpp │ │ ├── btCompoundCollisionAlgorithm.h │ │ ├── btCompoundCompoundCollisionAlgorithm.cpp │ │ ├── btCompoundCompoundCollisionAlgorithm.h │ │ ├── btConvex2dConvex2dAlgorithm.cpp │ │ ├── btConvex2dConvex2dAlgorithm.h │ │ ├── btConvexConcaveCollisionAlgorithm.cpp │ │ ├── btConvexConcaveCollisionAlgorithm.h │ │ ├── btConvexConvexAlgorithm.cpp │ │ ├── btConvexConvexAlgorithm.h │ │ ├── btConvexPlaneCollisionAlgorithm.cpp │ │ ├── btConvexPlaneCollisionAlgorithm.h │ │ ├── btDefaultCollisionConfiguration.cpp │ │ ├── btDefaultCollisionConfiguration.h │ │ ├── btEmptyCollisionAlgorithm.cpp │ │ ├── btEmptyCollisionAlgorithm.h │ │ ├── btGhostObject.cpp │ │ ├── btGhostObject.h │ │ ├── btHashedSimplePairCache.cpp │ │ ├── btHashedSimplePairCache.h │ │ ├── btInternalEdgeUtility.cpp │ │ ├── btInternalEdgeUtility.h │ │ ├── btManifoldResult.cpp │ │ ├── btManifoldResult.h │ │ ├── btSimulationIslandManager.cpp │ │ ├── btSimulationIslandManager.h │ │ ├── btSphereBoxCollisionAlgorithm.cpp │ │ ├── btSphereBoxCollisionAlgorithm.h │ │ ├── btSphereSphereCollisionAlgorithm.cpp │ │ ├── btSphereSphereCollisionAlgorithm.h │ │ ├── btSphereTriangleCollisionAlgorithm.cpp │ │ ├── btSphereTriangleCollisionAlgorithm.h │ │ ├── btUnionFind.cpp │ │ └── btUnionFind.h │ ├── CollisionShapes │ │ ├── btBox2dShape.cpp │ │ ├── btBox2dShape.h │ │ ├── btBoxShape.cpp │ │ ├── btBoxShape.h │ │ ├── btBvhTriangleMeshShape.cpp │ │ ├── btBvhTriangleMeshShape.h │ │ ├── btCapsuleShape.cpp │ │ ├── btCapsuleShape.h │ │ ├── btCollisionMargin.h │ │ ├── btCollisionShape.cpp │ │ ├── btCollisionShape.h │ │ ├── btCompoundShape.cpp │ │ ├── btCompoundShape.h │ │ ├── btConcaveShape.cpp │ │ ├── btConcaveShape.h │ │ ├── btConeShape.cpp │ │ ├── btConeShape.h │ │ ├── btConvex2dShape.cpp │ │ ├── btConvex2dShape.h │ │ ├── btConvexHullShape.cpp │ │ ├── btConvexHullShape.h │ │ ├── btConvexInternalShape.cpp │ │ ├── btConvexInternalShape.h │ │ ├── btConvexPointCloudShape.cpp │ │ ├── btConvexPointCloudShape.h │ │ ├── btConvexPolyhedron.cpp │ │ ├── btConvexPolyhedron.h │ │ ├── btConvexShape.cpp │ │ ├── btConvexShape.h │ │ ├── btConvexTriangleMeshShape.cpp │ │ ├── btConvexTriangleMeshShape.h │ │ ├── btCylinderShape.cpp │ │ ├── btCylinderShape.h │ │ ├── btEmptyShape.cpp │ │ ├── btEmptyShape.h │ │ ├── btHeightfieldTerrainShape.cpp │ │ ├── btHeightfieldTerrainShape.h │ │ ├── btMaterial.h │ │ ├── btMinkowskiSumShape.cpp │ │ ├── btMinkowskiSumShape.h │ │ ├── btMultiSphereShape.cpp │ │ ├── btMultiSphereShape.h │ │ ├── btMultimaterialTriangleMeshShape.cpp │ │ ├── btMultimaterialTriangleMeshShape.h │ │ ├── btOptimizedBvh.cpp │ │ ├── btOptimizedBvh.h │ │ ├── btPolyhedralConvexShape.cpp │ │ ├── btPolyhedralConvexShape.h │ │ ├── btScaledBvhTriangleMeshShape.cpp │ │ ├── btScaledBvhTriangleMeshShape.h │ │ ├── btShapeHull.cpp │ │ ├── btShapeHull.h │ │ ├── btSphereShape.cpp │ │ ├── btSphereShape.h │ │ ├── btStaticPlaneShape.cpp │ │ ├── btStaticPlaneShape.h │ │ ├── btStridingMeshInterface.cpp │ │ ├── btStridingMeshInterface.h │ │ ├── btTetrahedronShape.cpp │ │ ├── btTetrahedronShape.h │ │ ├── btTriangleBuffer.cpp │ │ ├── btTriangleBuffer.h │ │ ├── btTriangleCallback.cpp │ │ ├── btTriangleCallback.h │ │ ├── btTriangleIndexVertexArray.cpp │ │ ├── btTriangleIndexVertexArray.h │ │ ├── btTriangleIndexVertexMaterialArray.cpp │ │ ├── btTriangleIndexVertexMaterialArray.h │ │ ├── btTriangleInfoMap.h │ │ ├── btTriangleMesh.cpp │ │ ├── btTriangleMesh.h │ │ ├── btTriangleMeshShape.cpp │ │ ├── btTriangleMeshShape.h │ │ ├── btTriangleShape.h │ │ ├── btUniformScalingShape.cpp │ │ └── btUniformScalingShape.h │ ├── Gimpact │ │ ├── btBoxCollision.h │ │ ├── btClipPolygon.h │ │ ├── btCompoundFromGimpact.h │ │ ├── btContactProcessing.cpp │ │ ├── btContactProcessing.h │ │ ├── btGImpactBvh.cpp │ │ ├── btGImpactBvh.h │ │ ├── btGImpactCollisionAlgorithm.cpp │ │ ├── btGImpactCollisionAlgorithm.h │ │ ├── btGImpactMassUtil.h │ │ ├── btGImpactQuantizedBvh.cpp │ │ ├── btGImpactQuantizedBvh.h │ │ ├── btGImpactShape.cpp │ │ ├── btGImpactShape.h │ │ ├── btGenericPoolAllocator.cpp │ │ ├── btGenericPoolAllocator.h │ │ ├── btGeometryOperations.h │ │ ├── btQuantization.h │ │ ├── btTriangleShapeEx.cpp │ │ ├── btTriangleShapeEx.h │ │ ├── gim_array.h │ │ ├── gim_basic_geometry_operations.h │ │ ├── gim_bitset.h │ │ ├── gim_box_collision.h │ │ ├── gim_box_set.cpp │ │ ├── gim_box_set.h │ │ ├── gim_clip_polygon.h │ │ ├── gim_contact.cpp │ │ ├── gim_contact.h │ │ ├── gim_geom_types.h │ │ ├── gim_geometry.h │ │ ├── gim_hash_table.h │ │ ├── gim_linear_math.h │ │ ├── gim_math.h │ │ ├── gim_memory.cpp │ │ ├── gim_memory.h │ │ ├── gim_radixsort.h │ │ ├── gim_tri_collision.cpp │ │ └── gim_tri_collision.h │ ├── NarrowPhaseCollision │ │ ├── btContinuousConvexCollision.cpp │ │ ├── btContinuousConvexCollision.h │ │ ├── btConvexCast.cpp │ │ ├── btConvexCast.h │ │ ├── btConvexPenetrationDepthSolver.h │ │ ├── btDiscreteCollisionDetectorInterface.h │ │ ├── btGjkConvexCast.cpp │ │ ├── btGjkConvexCast.h │ │ ├── btGjkEpa2.cpp │ │ ├── btGjkEpa2.h │ │ ├── btGjkEpaPenetrationDepthSolver.cpp │ │ ├── btGjkEpaPenetrationDepthSolver.h │ │ ├── btGjkPairDetector.cpp │ │ ├── btGjkPairDetector.h │ │ ├── btManifoldPoint.h │ │ ├── btMinkowskiPenetrationDepthSolver.cpp │ │ ├── btMinkowskiPenetrationDepthSolver.h │ │ ├── btPersistentManifold.cpp │ │ ├── btPersistentManifold.h │ │ ├── btPointCollector.h │ │ ├── btPolyhedralContactClipping.cpp │ │ ├── btPolyhedralContactClipping.h │ │ ├── btRaycastCallback.cpp │ │ ├── btRaycastCallback.h │ │ ├── btSimplexSolverInterface.h │ │ ├── btSubSimplexConvexCast.cpp │ │ ├── btSubSimplexConvexCast.h │ │ ├── btVoronoiSimplexSolver.cpp │ │ └── btVoronoiSimplexSolver.h │ └── premake4.lua │ ├── BulletDynamics │ ├── Character │ │ ├── btCharacterControllerInterface.h │ │ ├── btKinematicCharacterController.cpp │ │ └── btKinematicCharacterController.h │ ├── ConstraintSolver │ │ ├── btConeTwistConstraint.cpp │ │ ├── btConeTwistConstraint.h │ │ ├── btConstraintSolver.h │ │ ├── btContactConstraint.cpp │ │ ├── btContactConstraint.h │ │ ├── btContactSolverInfo.h │ │ ├── btFixedConstraint.cpp │ │ ├── btFixedConstraint.h │ │ ├── btGearConstraint.cpp │ │ ├── btGearConstraint.h │ │ ├── btGeneric6DofConstraint.cpp │ │ ├── btGeneric6DofConstraint.h │ │ ├── btGeneric6DofSpringConstraint.cpp │ │ ├── btGeneric6DofSpringConstraint.h │ │ ├── btHinge2Constraint.cpp │ │ ├── btHinge2Constraint.h │ │ ├── btHingeConstraint.cpp │ │ ├── btHingeConstraint.h │ │ ├── btJacobianEntry.h │ │ ├── btNNCGConstraintSolver.cpp │ │ ├── btNNCGConstraintSolver.h │ │ ├── btPoint2PointConstraint.cpp │ │ ├── btPoint2PointConstraint.h │ │ ├── btSequentialImpulseConstraintSolver.cpp │ │ ├── btSequentialImpulseConstraintSolver.h │ │ ├── btSliderConstraint.cpp │ │ ├── btSliderConstraint.h │ │ ├── btSolve2LinearConstraint.cpp │ │ ├── btSolve2LinearConstraint.h │ │ ├── btSolverBody.h │ │ ├── btSolverConstraint.h │ │ ├── btTypedConstraint.cpp │ │ ├── btTypedConstraint.h │ │ ├── btUniversalConstraint.cpp │ │ └── btUniversalConstraint.h │ ├── Dynamics │ │ ├── Bullet-C-API.cpp │ │ ├── btActionInterface.h │ │ ├── btDiscreteDynamicsWorld.cpp │ │ ├── btDiscreteDynamicsWorld.h │ │ ├── btDynamicsWorld.h │ │ ├── btRigidBody.cpp │ │ ├── btRigidBody.h │ │ ├── btSimpleDynamicsWorld.cpp │ │ └── btSimpleDynamicsWorld.h │ ├── Featherstone │ │ ├── btMultiBody.cpp │ │ ├── btMultiBody.h │ │ ├── btMultiBodyConstraint.cpp │ │ ├── btMultiBodyConstraint.h │ │ ├── btMultiBodyConstraintSolver.cpp │ │ ├── btMultiBodyConstraintSolver.h │ │ ├── btMultiBodyDynamicsWorld.cpp │ │ ├── btMultiBodyDynamicsWorld.h │ │ ├── btMultiBodyJointLimitConstraint.cpp │ │ ├── btMultiBodyJointLimitConstraint.h │ │ ├── btMultiBodyJointMotor.cpp │ │ ├── btMultiBodyJointMotor.h │ │ ├── btMultiBodyLink.h │ │ ├── btMultiBodyLinkCollider.h │ │ ├── btMultiBodyPoint2Point.cpp │ │ ├── btMultiBodyPoint2Point.h │ │ └── btMultiBodySolverConstraint.h │ ├── MLCPSolvers │ │ ├── btDantzigLCP.cpp │ │ ├── btDantzigLCP.h │ │ ├── btDantzigSolver.h │ │ ├── btLemkeAlgorithm.cpp │ │ ├── btLemkeAlgorithm.h │ │ ├── btLemkeSolver.h │ │ ├── btMLCPSolver.cpp │ │ ├── btMLCPSolver.h │ │ ├── btMLCPSolverInterface.h │ │ ├── btPATHSolver.h │ │ └── btSolveProjectedGaussSeidel.h │ ├── Vehicle │ │ ├── btRaycastVehicle.cpp │ │ ├── btRaycastVehicle.h │ │ ├── btVehicleRaycaster.h │ │ ├── btWheelInfo.cpp │ │ ├── btWheelInfo.h │ │ ├── btWheeledVehicle.cpp │ │ └── btWheeledVehicle.h │ └── premake4.lua │ ├── BulletMultiThreaded │ ├── GpuSoftBodySolvers │ │ ├── DX11 │ │ │ ├── HLSL │ │ │ │ ├── ApplyForces.hlsl │ │ │ │ ├── ComputeBounds.hlsl │ │ │ │ ├── Integrate.hlsl │ │ │ │ ├── OutputToVertexArray.hlsl │ │ │ │ ├── PrepareLinks.hlsl │ │ │ │ ├── SolvePositions.hlsl │ │ │ │ ├── SolvePositionsSIMDBatched.hlsl │ │ │ │ ├── UpdateConstants.hlsl │ │ │ │ ├── UpdateNodes.hlsl │ │ │ │ ├── UpdateNormals.hlsl │ │ │ │ ├── UpdatePositions.hlsl │ │ │ │ ├── UpdatePositionsFromVelocities.hlsl │ │ │ │ ├── VSolveLinks.hlsl │ │ │ │ ├── solveCollisionsAndUpdateVelocities.hlsl │ │ │ │ └── solveCollisionsAndUpdateVelocitiesSIMDBatched.hlsl │ │ │ ├── btSoftBodySolverBuffer_DX11.h │ │ │ ├── btSoftBodySolverLinkData_DX11.h │ │ │ ├── btSoftBodySolverLinkData_DX11SIMDAware.h │ │ │ ├── btSoftBodySolverTriangleData_DX11.h │ │ │ ├── btSoftBodySolverVertexBuffer_DX11.h │ │ │ ├── btSoftBodySolverVertexData_DX11.h │ │ │ ├── btSoftBodySolver_DX11.cpp │ │ │ ├── btSoftBodySolver_DX11.h │ │ │ ├── btSoftBodySolver_DX11SIMDAware.cpp │ │ │ └── btSoftBodySolver_DX11SIMDAware.h │ │ ├── OpenCL │ │ │ ├── MiniCL │ │ │ │ └── MiniCLTaskWrap.cpp │ │ │ ├── OpenCLC10 │ │ │ │ ├── ApplyForces.cl │ │ │ │ ├── ComputeBounds.cl │ │ │ │ ├── Integrate.cl │ │ │ │ ├── OutputToVertexArray.cl │ │ │ │ ├── PrepareLinks.cl │ │ │ │ ├── SolveCollisionsAndUpdateVelocities.cl │ │ │ │ ├── SolveCollisionsAndUpdateVelocitiesSIMDBatched.cl │ │ │ │ ├── SolvePositions.cl │ │ │ │ ├── SolvePositionsSIMDBatched.cl │ │ │ │ ├── UpdateConstants.cl │ │ │ │ ├── UpdateFixedVertexPositions.cl │ │ │ │ ├── UpdateNodes.cl │ │ │ │ ├── UpdateNormals.cl │ │ │ │ ├── UpdatePositions.cl │ │ │ │ ├── UpdatePositionsFromVelocities.cl │ │ │ │ └── VSolveLinks.cl │ │ │ ├── btSoftBodySolverBuffer_OpenCL.h │ │ │ ├── btSoftBodySolverLinkData_OpenCL.h │ │ │ ├── btSoftBodySolverLinkData_OpenCLSIMDAware.h │ │ │ ├── btSoftBodySolverOutputCLtoGL.cpp │ │ │ ├── btSoftBodySolverOutputCLtoGL.h │ │ │ ├── btSoftBodySolverTriangleData_OpenCL.h │ │ │ ├── btSoftBodySolverVertexBuffer_OpenGL.h │ │ │ ├── btSoftBodySolverVertexData_OpenCL.h │ │ │ ├── btSoftBodySolver_OpenCL.cpp │ │ │ ├── btSoftBodySolver_OpenCL.h │ │ │ ├── btSoftBodySolver_OpenCLSIMDAware.cpp │ │ │ └── btSoftBodySolver_OpenCLSIMDAware.h │ │ └── Shared │ │ │ └── btSoftBodySolverData.h │ ├── HeapManager.h │ ├── PlatformDefinitions.h │ ├── PosixThreading.cpp │ ├── PpuAddressSpace.h │ ├── TrbDynBody.h │ ├── TrbStateVec.h │ ├── Win32Threading.cpp │ ├── btGpu3DGridBroadphase.cpp │ ├── btGpu3DGridBroadphase.h │ ├── btGpu3DGridBroadphaseSharedCode.h │ ├── btGpu3DGridBroadphaseSharedDefs.h │ ├── btGpu3DGridBroadphaseSharedTypes.h │ ├── btGpuDefines.h │ ├── btGpuUtilsSharedCode.h │ ├── btGpuUtilsSharedDefs.h │ ├── btParallelCollisionDispatcher.cpp │ ├── btParallelCollisionDispatcher.h │ ├── btParallelConstraintSolver.cpp │ ├── btParallelConstraintSolver.h │ ├── btThreadPool.cpp │ ├── btThreadPool.h │ ├── btThreading.h │ ├── premake4.lua │ └── vectormath2bullet.h │ ├── BulletSoftBody │ ├── btDefaultSoftBodySolver.cpp │ ├── btDefaultSoftBodySolver.h │ ├── btSoftBody.cpp │ ├── btSoftBody.h │ ├── btSoftBodyConcaveCollisionAlgorithm.cpp │ ├── btSoftBodyConcaveCollisionAlgorithm.h │ ├── btSoftBodyData.h │ ├── btSoftBodyHelpers.cpp │ ├── btSoftBodyHelpers.h │ ├── btSoftBodyInternals.h │ ├── btSoftBodyRigidBodyCollisionConfiguration.cpp │ ├── btSoftBodyRigidBodyCollisionConfiguration.h │ ├── btSoftBodySolverVertexBuffer.h │ ├── btSoftBodySolvers.h │ ├── btSoftRigidCollisionAlgorithm.cpp │ ├── btSoftRigidCollisionAlgorithm.h │ ├── btSoftRigidDynamicsWorld.cpp │ ├── btSoftRigidDynamicsWorld.h │ ├── btSoftSoftCollisionAlgorithm.cpp │ ├── btSoftSoftCollisionAlgorithm.h │ ├── btSparseSDF.h │ └── premake4.lua │ ├── LinearMath │ ├── btAabbUtil2.h │ ├── btAlignedAllocator.cpp │ ├── btAlignedAllocator.h │ ├── btAlignedObjectArray.h │ ├── btConvexHull.cpp │ ├── btConvexHull.h │ ├── btConvexHullComputer.cpp │ ├── btConvexHullComputer.h │ ├── btDebug.cpp │ ├── btDebug.h │ ├── btDefaultMotionState.h │ ├── btDefines.h │ ├── btGeometryUtil.cpp │ ├── btGeometryUtil.h │ ├── btGrahamScan2dConvexHull.h │ ├── btHashMap.h │ ├── btIDebugDraw.h │ ├── btList.h │ ├── btMatrix3x3.h │ ├── btMatrixX.h │ ├── btMinMax.h │ ├── btMotionState.h │ ├── btPolarDecomposition.cpp │ ├── btPolarDecomposition.h │ ├── btPoolAllocator.h │ ├── btQuadWord.h │ ├── btQuaternion.h │ ├── btQuickprof.cpp │ ├── btQuickprof.h │ ├── btRandom.h │ ├── btScalar.h │ ├── btSerializer.cpp │ ├── btSerializer.h │ ├── btStackAlloc.h │ ├── btTransform.h │ ├── btTransformUtil.h │ ├── btVector3.cpp │ ├── btVector3.h │ └── premake4.lua │ ├── Makefile.am │ ├── MiniCL │ ├── MiniCL.cpp │ ├── MiniCLTask │ │ ├── MiniCLTask.cpp │ │ └── MiniCLTask.h │ ├── MiniCLTaskScheduler.cpp │ ├── MiniCLTaskScheduler.h │ ├── cl.h │ ├── cl_MiniCL_Defs.h │ ├── cl_gl.h │ └── cl_platform.h │ ├── btBulletCollisionCommon.h │ ├── btBulletDynamicsCommon.h │ ├── premake4.lua │ └── vectormath │ ├── neon │ ├── boolInVec.h │ ├── floatInVec.h │ ├── mat_aos.h │ ├── quat_aos.h │ ├── vec_aos.h │ └── vectormath_aos.h │ ├── scalar │ ├── boolInVec.h │ ├── floatInVec.h │ ├── mat_aos.h │ ├── quat_aos.h │ ├── vec_aos.h │ └── vectormath_aos.h │ ├── sse │ ├── boolInVec.h │ ├── floatInVec.h │ ├── mat_aos.h │ ├── quat_aos.h │ ├── vec_aos.h │ ├── vecidx_aos.h │ └── vectormath_aos.h │ └── vmInclude.h ├── include ├── vphysics │ ├── constraintsV32.h │ ├── softbodyV32.h │ └── vehiclesV32.h └── vphysics_interfaceV32.h ├── proj ├── gmake.sh ├── options.lua ├── premake4 ├── premake4.exe ├── premake4.lua ├── readme.txt └── vs2010.bat ├── src ├── DebugDrawer.cpp ├── DebugDrawer.h ├── IController.h ├── Makefile ├── Physics.cpp ├── Physics.h ├── Physics_Collision.cpp ├── Physics_Collision.h ├── Physics_CollisionSet.cpp ├── Physics_CollisionSet.h ├── Physics_Constraint.cpp ├── Physics_Constraint.h ├── Physics_DragController.cpp ├── Physics_DragController.h ├── Physics_Environment.cpp ├── Physics_Environment.h ├── Physics_FluidController.cpp ├── Physics_FluidController.h ├── Physics_FrictionSnapshot.cpp ├── Physics_FrictionSnapshot.h ├── Physics_KeyParser.cpp ├── Physics_KeyParser.h ├── Physics_MotionController.cpp ├── Physics_MotionController.h ├── Physics_Object.cpp ├── Physics_Object.h ├── Physics_ObjectPairHash.cpp ├── Physics_ObjectPairHash.h ├── Physics_PlayerController.cpp ├── Physics_PlayerController.h ├── Physics_ShadowController.cpp ├── Physics_ShadowController.h ├── Physics_SoftBody.cpp ├── Physics_SoftBody.h ├── Physics_SurfaceProps.cpp ├── Physics_SurfaceProps.h ├── Physics_VehicleAirboat.cpp ├── Physics_VehicleAirboat.h ├── Physics_VehicleController.cpp ├── Physics_VehicleController.h ├── Physics_VehicleControllerCustom.cpp ├── Physics_VehicleControllerCustom.h ├── StdAfx.cpp ├── StdAfx.h ├── convert.h ├── miscmath.cpp ├── miscmath.h ├── phydata.h ├── premake4.lua ├── resource.h └── vphysics.rc ├── vphysics.sln ├── vphysics.vcxproj └── vphysics.vcxproj.filters /.gitignore: -------------------------------------------------------------------------------- 1 | *.ipch 2 | *.ncb 3 | *.sdf 4 | *.opensdf 5 | *.suo 6 | *.user 7 | *.exe 8 | *.dll 9 | *.exp 10 | *.ilk 11 | *.lib 12 | *.pdb 13 | *.aps 14 | *.o 15 | *.d 16 | 17 | *.cproject 18 | *.project 19 | 20 | /build 21 | /ipch 22 | proj/gmake 23 | proj/vs2010 -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "qhull"] 2 | path = thirdparty/qhull 3 | url = https://github.com/manctl/qhull.git 4 | [submodule "sourcesdk"] 5 | path = thirdparty/sourcesdk 6 | url = https://github.com/ValveSoftware/source-sdk-2013.git 7 | [submodule "thirdparty/gmmodulebase"] 8 | path = thirdparty/gmmodulebase 9 | url = https://github.com/garrynewman/gmod-module-base.git 10 | -------------------------------------------------------------------------------- /GMVPhy/GMVPhy.vcxproj.filters: -------------------------------------------------------------------------------- 1 |  2 | 3 | 4 | 5 | {4FC737F1-C7A5-4376-A066-2A32D752A2FF} 6 | cpp;c;cc;cxx;def;odl;idl;hpj;bat;asm;asmx 7 | 8 | 9 | {93995380-89BD-4b04-88EB-625FBE52EBFB} 10 | h;hpp;hxx;hm;inl;inc;xsd 11 | 12 | 13 | 14 | 15 | Source Files 16 | 17 | 18 | Source Files 19 | 20 | 21 | Source Files 22 | 23 | 24 | Source Files 25 | 26 | 27 | Source Files 28 | 29 | 30 | Source Files 31 | 32 | 33 | Source Files 34 | 35 | 36 | Source Files 37 | 38 | 39 | 40 | 41 | Header Files 42 | 43 | 44 | Header Files 45 | 46 | 47 | Header Files 48 | 49 | 50 | Header Files 51 | 52 | 53 | Header Files 54 | 55 | 56 | Header Files 57 | 58 | 59 | Header Files 60 | 61 | 62 | -------------------------------------------------------------------------------- /GMVPhy/MiscFuncs.h: -------------------------------------------------------------------------------- 1 | #ifndef MISCFUNCS_H 2 | #define MISCFUNCS_H 3 | 4 | class IPhysicsEnvironment32; 5 | class IPhysicsObject32; 6 | class IPhysicsObject; 7 | class IPhysicsSoftBody; 8 | class IPhysicsVehicleController; 9 | class CPhysCollide; 10 | class CPhysConvex; 11 | class Vector; 12 | class QAngle; 13 | struct lua_State; 14 | 15 | #include 16 | 17 | // These should probably be in a stdafx.h or something 18 | namespace CustomTypes { 19 | enum { 20 | TYPE_PHYSCOLLIDE = GarrysMod::Lua::Type::COUNT + 1, 21 | TYPE_PHYSCONVEX, 22 | 23 | TYPE_PHYSENV, 24 | TYPE_PHYSSOFTBODY, 25 | TYPE_PHYSUSERCONSTRAINT, 26 | TYPE_PHYSVEHICLECONTROLLER, 27 | 28 | COUNT, 29 | }; 30 | } 31 | 32 | IPhysicsEnvironment32 *Get_PhysEnv(lua_State *state, int stackPos); 33 | void Push_PhysEnv(lua_State *state, IPhysicsEnvironment32 *pEnv); 34 | 35 | IPhysicsObject32 *Get_PhysObj(lua_State *state, int stackPos); 36 | void Push_PhysObj(lua_State *state, IPhysicsObject *pObj); 37 | 38 | IPhysicsVehicleController *Get_PhysVehicleController(lua_State *state, int stackPos); 39 | void Push_PhysVehicleController(lua_State *state, IPhysicsVehicleController *pController); 40 | 41 | Vector *Get_Vector(lua_State *state, int stackPos); 42 | void Push_Vector(lua_State *state, const Vector &vec); 43 | 44 | QAngle *Get_Angle(lua_State *state, int stackPos); 45 | void Push_Angle(lua_State *state, const QAngle &ang); 46 | 47 | IPhysicsSoftBody *Get_SoftBody(lua_State *state, int stackPos); 48 | void Push_SoftBody(lua_State *state, IPhysicsSoftBody *softBody); 49 | 50 | CPhysCollide *Get_PhysCollide(lua_State *state, int stackPos); 51 | void Push_PhysCollide(lua_State *state, const CPhysCollide *collide); 52 | 53 | CPhysConvex *Get_PhysConvex(lua_State *state, int stackPos); 54 | void Push_PhysConvex(lua_State *state, const CPhysConvex *convex); 55 | 56 | #endif // MISCFUNCS_H -------------------------------------------------------------------------------- /GMVPhy/PhysCollision.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSCOLLISION_H 2 | #define PHYSCOLLISION_H 3 | 4 | struct lua_State; 5 | 6 | int Init_PhysCollision(lua_State *state); 7 | 8 | #endif // PHYSCOLLISION_H -------------------------------------------------------------------------------- /GMVPhy/PhysConstraint.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSCONSTRAINT_H 2 | #define PHYSCONSTRAINT_H 3 | 4 | struct lua_State; 5 | 6 | int Init_PhysConstraint(lua_State *L); 7 | 8 | #endif // PHYSCONSTRAINT_H -------------------------------------------------------------------------------- /GMVPhy/PhysEnv.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSENV_H 2 | #define PHYSENV_H 3 | 4 | struct lua_State; 5 | 6 | int Init_PhysEnv(lua_State *state); 7 | 8 | #endif // PHYSENV_H -------------------------------------------------------------------------------- /GMVPhy/PhysObj.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSOBJ_H 2 | #define PHYSOBJ_H 3 | 4 | struct lua_State; 5 | 6 | int Init_PhysObj(lua_State *L); 7 | 8 | #endif // PHYSOBJ_H -------------------------------------------------------------------------------- /GMVPhy/PhysSoftBody.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSSOFTBODY_H 2 | #define PHYSSOFTBODY_H 3 | 4 | struct lua_State; 5 | 6 | int Init_PhysSoftBody(lua_State *L); 7 | 8 | #endif // PHYSSOFTBODY_H -------------------------------------------------------------------------------- /GMVPhy/PhysVehicle.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSVEHICLE_H 2 | #define PHYSVEHICLE_H 3 | 4 | struct lua_State; 5 | 6 | int Init_PhysVehicle(lua_State *state); 7 | 8 | #endif // PHYSVEHICLE_H -------------------------------------------------------------------------------- /GMVPhy/main.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include "../include/vphysics_interfaceV32.h" 4 | 5 | #include "PhysObj.h" 6 | #include "PhysCollision.h" 7 | #include "PhysConstraint.h" 8 | #include "PhysEnv.h" 9 | #include "PhysSoftBody.h" 10 | #include "PhysVehicle.h" 11 | 12 | // memdbgon must be the last include file in a .cpp file!!! 13 | #include "tier0/memdbgon.h" 14 | 15 | using namespace GarrysMod::Lua; 16 | 17 | #define LINIT_CHECKRET(fn, state) { if ((fn)(state) != 0) { Warning("lua vphysics init: %s failed\n", #fn); return 1; } } 18 | 19 | IPhysics32 *g_pPhysics = NULL; 20 | IPhysicsSurfaceProps *g_pSurfProps = NULL; 21 | 22 | int lPhysStats(lua_State *state) { 23 | for (int i = 0; i < g_pPhysics->GetActiveEnvironmentCount(); i++) { 24 | IPhysicsEnvironment *pEnv = g_pPhysics->GetActiveEnvironmentByIndex(i); 25 | if (!pEnv) 26 | break; 27 | 28 | Msg("Environment %d active\n", i); 29 | Msg("\t%d active objects\n", pEnv->GetActiveObjectCount()); 30 | } 31 | 32 | return 0; 33 | } 34 | 35 | GMOD_MODULE_OPEN() { 36 | CreateInterfaceFn physFactory = Sys_GetFactory("vphysics"); 37 | if (physFactory) { 38 | g_pPhysics = (IPhysics32 *)physFactory("VPhysics032", NULL); // This specific interface is defined in the newer vphysics 39 | g_pSurfProps = (IPhysicsSurfaceProps *)physFactory(VPHYSICS_SURFACEPROPS_INTERFACE_VERSION, NULL); 40 | } 41 | 42 | // Check if the interface was created (if it wasn't, we're not running the newer vphysics) 43 | if (!g_pPhysics) { 44 | Warning("VPhysics lua init failed (vphysics module is too old!)"); 45 | return 1; 46 | } 47 | 48 | #ifdef _DEBUG 49 | if (g_pPhysics) { 50 | Msg("Found physics interface!\n"); 51 | } 52 | #endif 53 | 54 | // Let's setup our table of functions 55 | LUA->PushSpecial(GarrysMod::Lua::SPECIAL_GLOB); 56 | LUA->CreateTable(); 57 | LUA->PushCFunction(lPhysStats); LUA->SetField(-2, "printstats"); 58 | LUA->SetField(-2, "vphysics"); 59 | LUA->Pop(); 60 | 61 | LINIT_CHECKRET(Init_PhysObj, state); 62 | LINIT_CHECKRET(Init_PhysCollision, state); 63 | LINIT_CHECKRET(Init_PhysConstraint, state); 64 | LINIT_CHECKRET(Init_PhysEnv, state); 65 | LINIT_CHECKRET(Init_PhysSoftBody, state); 66 | LINIT_CHECKRET(Init_PhysVehicle, state); 67 | 68 | return 0; 69 | } 70 | 71 | GMOD_MODULE_CLOSE() { 72 | return 0; 73 | } -------------------------------------------------------------------------------- /GMVPhy/premake4.lua: -------------------------------------------------------------------------------- 1 | project "GMVPhy" 2 | 3 | language "C++" 4 | 5 | kind "SharedLib" 6 | 7 | -- Visual studio specific copy command 8 | configuration { "windows", "vs*" } 9 | if GEN_POSTBUILDCOMMANDS then 10 | postbuildcommands { 11 | 'if defined VPHYSICS_GAME_PATH (\n' 12 | .. ' if exist "%VPHYSICS_GAME_PATH%\garrysmod" (\n' 13 | .. ' if exist "%VPHYSICS_GAME_PATH%\garrysmod\lua\bin\$(TargetFileName)" (\n' 14 | .. ' attrib -r "%VPHYSICS_GAME_PATH%\garrysmod\lua\bin\$(TargetFileName)"\n' 15 | .. ' del "%VPHYSICS_GAME_PATH%\garrysmod\lua\bin\$(TargetFileName)"\n' 16 | .. ' )\n' 17 | .. ' \n' 18 | .. ' copy "$(TargetPath)" "%VPHYSICS_GAME_PATH%\garrysmod\lua\bin\$(TargetFileName)"\n' 19 | .. ' )\n' 20 | .. ')\n' 21 | } 22 | end 23 | 24 | linkoptions { "/NODEFAULTLIB:\"LIBCMT\"" } 25 | 26 | -- Part of a ridiculous hack to get source sdk to build 27 | configuration { "linux", "gmake" } 28 | buildoptions { "-w", "-fpermissive" } 29 | defines { "sprintf_s=snprintf", "strcmpi=strcasecmp", "_alloca=alloca", "stricmp=strcasecmp", "_stricmp=strcasecmp", "strcpy_s=strncpy", "_strnicmp=strncasecmp", "strnicmp=strncasecmp", "_snprintf=snprintf", "_vsnprintf=vsnprintf", "_alloca=alloca", "strcmpi=strcasecmp", "NDEBUG", "NO_MALLOC_OVERRIDE" } 30 | 31 | configuration {} 32 | 33 | defines {"GMMODULE"} 34 | 35 | if _PREMAKE_VERSION == "4.4" then 36 | vpaths { 37 | ["Header Files"] = "**.h", 38 | ["Source Files"] = "**.cpp", 39 | ["Resource Files"] = {"**.rc", "resource.h"}, 40 | } 41 | end 42 | 43 | includedirs { 44 | SDK_DIR, 45 | SDK_DIR .. "/public", 46 | SDK_DIR .. "/public/tier0", 47 | SDK_DIR .. "/public/tier1", 48 | GM_MODULEBASE, 49 | } 50 | 51 | files { 52 | "**.cpp", 53 | "**.h" 54 | } -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | The following license covers all vphysics code, which is every file and directory 2 | except for files and directories under bullet/* and thirdparty/* 3 | 4 | ------------------------------------------------------------------------------ 5 | DO WHAT THE FUCK YOU WANT TO PUBLIC LICENSE 6 | Version 2, December 2004 7 | 8 | Copyright (C) 2004 Sam Hocevar 9 | 10 | Everyone is permitted to copy and distribute verbatim or modified 11 | copies of this license document, and changing it is allowed as long 12 | as the name is changed. 13 | 14 | DO WHAT THE FUCK YOU WANT TO PUBLIC LICENSE 15 | TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION 16 | 17 | 0. You just DO WHAT THE FUCK YOU WANT TO. 18 | ------------------------------------------------------------------------------ 19 | 20 | Third party libraries are covered by their respective licenses. -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | Gmod-vphysics 2 | ============= 3 | 4 | Replacement vphysics module for the source engine (formerly just garry's mod) 5 | 6 | ## Users 7 | #### Download 8 | You can download vphysics [here](http://peniscorp.com/vphysics/) (courtesy of Gran PC) 9 | #### Installation 10 | 1. Copy vphysics.dll to the engine bin directory (parent folder is the one that contains hl2.exe, e.g. \/garrysmod/bin) 11 | 2. Run the game. 12 | 13 | You may have to repeat these steps if the game updates! 14 | 15 | ## Developers 16 | #### Libraries Required 17 | * Absolutely nothing! Everything needed included in ./thirdparty 18 | 19 | #### Git Submodules 20 | This library uses git submodules. In order to set those up, after cloning the repository, issue these commands: 21 | 22 | ``` 23 | git submodule init 24 | 25 | # And to update submodules: 26 | git submodule update 27 | ``` 28 | 29 | Alternatively, you can also clone the repository with the --recursive switch, as so: 30 | ``` 31 | git clone --recursive 32 | ``` 33 | 34 | Submodules will need to be compiled separately from vphysics if required (atleast until a script is setup) 35 | 36 | #### Windows Setup 37 | * Visual studio 2012 projects provided 38 | * - You must configure the library paths manually (sorry!) 39 | * Optionally, premake scripts are provided in the proj folder 40 | 41 | #### Linux Setup 42 | * You need to have the game you're building for installed, as vphysics needs to dynamically link to some modules. Configure the path in ./src/Makefile 43 | * You can use the build.sh provided in the root directory to compile vphysics. Optional arguments are -numthreads \ and -clean (make clean before make) 44 | 45 | #### Automatic Copying 46 | On Windows, you can set the environmental variable "VPHYSICS_GAME_PATH" to the directory that contains hl2.exe and vphysics will automatically be copied over. 47 | 48 | #### Pull Requests 49 | Please make the code in your pull requests look neat, and have the commits be granular (handle one thing at a time). They will only be pulled if they're in the same coding style as the surrounding code (don't make your code stand out!) 50 | -------------------------------------------------------------------------------- /build.sh: -------------------------------------------------------------------------------- 1 | #!/bin/sh 2 | 3 | # Settings 4 | WORKING_DIR=$(pwd) 5 | BULLET_PROJ_DIR=$WORKING_DIR/bullet/proj 6 | 7 | init() { 8 | NUM_THREADS="1" 9 | CLEAN="" 10 | CONFIG="release" 11 | 12 | while test $# -gt 0; do 13 | case "$1" in 14 | "-numthreads") 15 | NUM_THREADS="$2" 16 | shift ;; 17 | "-clean") 18 | CLEAN="yes" 19 | ;; 20 | "-config") 21 | CONFIG="$2" 22 | shift ;; 23 | esac 24 | shift # Shifts command line arguments var or something whatever 25 | done 26 | } 27 | 28 | usage() { 29 | echo "Usage: $0 " 30 | exit 1 31 | } 32 | 33 | build_bullet() { 34 | if test -n $BULLET_PROJ_DIR; then 35 | cd "$BULLET_PROJ_DIR" 36 | ./premake4 gmake 37 | cd gmake 38 | 39 | if test -n "$CLEAN"; then 40 | make clean 41 | fi 42 | 43 | make -j$NUM_THREADS "config=$CONFIG" 44 | fi 45 | } 46 | 47 | build_vphysics() { 48 | cd "$WORKING_DIR/src" 49 | 50 | if test -n "$CLEAN"; then 51 | make clean 52 | fi 53 | 54 | make -j$NUM_THREADS "CONFIGURATION=$CONFIG" 55 | } 56 | 57 | init $* 58 | 59 | build_bullet 60 | build_vphysics 61 | 62 | cd "$WORKING_DIR" 63 | -------------------------------------------------------------------------------- /bullet/license.txt: -------------------------------------------------------------------------------- 1 | Apparently we're supposed to mark our bullet distribution as altered, so I am doing that here. -------------------------------------------------------------------------------- /bullet/msvc/BulletMultiThreaded/ThreadPool.cpp: -------------------------------------------------------------------------------- 1 | #include "ThreadPool.h" -------------------------------------------------------------------------------- /bullet/msvc/BulletMultiThreaded/ThreadPool.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_THREADPOOL_H 2 | #define BT_THREADPOOL_H 3 | 4 | #include "Threading.h" 5 | 6 | class btIThreadTask { 7 | public: 8 | virtual void run() = 0; 9 | }; 10 | 11 | class btThreadPool { 12 | public: 13 | btThreadPool(int numThreads); 14 | 15 | private: 16 | btIThread *m_pThreads; 17 | int m_numThreads; 18 | }; 19 | 20 | #endif // BT_THREADPOOL_H -------------------------------------------------------------------------------- /bullet/proj/premake4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/bullet/proj/premake4 -------------------------------------------------------------------------------- /bullet/proj/premake4.lua: -------------------------------------------------------------------------------- 1 | solution "bullet" 2 | 3 | if _ACTION == "vs2010" or _ACTION == "vs2008" then 4 | -- Enable multi-processor compilation 5 | buildoptions { "/MP" } 6 | end 7 | 8 | act = "" 9 | 10 | if _ACTION then 11 | act = _ACTION 12 | end 13 | 14 | --[[--------------------------------- 15 | -- Main configuration properities 16 | -----------------------------------]] 17 | configurations { "Release", "Debug" } 18 | 19 | configuration "Release" 20 | defines { "RELEASE=1", "NDEBUG=1", "_RELEASE=1" } 21 | if os.is( "linux" ) then 22 | defines { "_LINUX=1", "__linux__=1", "LINUX=1" } 23 | end 24 | 25 | -- TODO: When supported, add NoIncrementalLink flag 26 | flags { "OptimizeSpeed", "EnableSSE", "StaticRuntime", "NoMinimalRebuild", "FloatFast" } 27 | targetdir( "../../build/lib/" .. os.get() .. "/release" ) 28 | 29 | configuration "Debug" 30 | defines { "_DEBUG=1" } 31 | if os.is("linux") then 32 | defines { "_LINUX=1", "__linux__=1", "LINUX=1" } 33 | end 34 | 35 | flags { "Symbols", "StaticRuntime", "NoMinimalRebuild", "FloatFast" } 36 | targetdir("../../build/lib/" .. os.get() .. "/debug") 37 | 38 | configuration {} 39 | 40 | -- Only support 32 bit builds 41 | configuration { "linux", "gmake" } 42 | buildoptions { "-fPIC", "-m32", "-msse2" } 43 | linkoptions { "-m32", "-msse2" } 44 | 45 | configuration { "linux", "gmake", "Debug" } 46 | buildoptions { "-ggdb" } 47 | linkoptions { "-ggdb" } 48 | 49 | configuration {} 50 | 51 | -- Set generated project location 52 | location( "./" .. act ) 53 | 54 | --[[-------------- 55 | -- Projects 56 | ----------------]] 57 | include "../src" 58 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp: -------------------------------------------------------------------------------- 1 | 2 | //Bullet Continuous Collision Detection and Physics Library 3 | //Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | 6 | // 7 | // btAxisSweep3 8 | // 9 | // Copyright (c) 2006 Simon Hobbs 10 | // 11 | // This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. 12 | // 13 | // Permission is granted to anyone to use this software for any purpose, including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 14 | // 15 | // 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 16 | // 17 | // 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 18 | // 19 | // 3. This notice may not be removed or altered from any source distribution. 20 | #include "btAxisSweep3.h" 21 | 22 | 23 | btAxisSweep3::btAxisSweep3(const btVector3& worldAabbMin, const btVector3& worldAabbMax, unsigned short int maxHandles, btOverlappingPairCache* pairCache, bool disableRaycastAccelerator) 24 | :btAxisSweep3Internal(worldAabbMin, worldAabbMax,0xfffe,0xffff, maxHandles, pairCache, disableRaycastAccelerator) 25 | { 26 | // 1 handle is reserved as sentinel 27 | btAssert(maxHandles > 1 && maxHandles < 32767); 28 | 29 | } 30 | 31 | 32 | bt32BitAxisSweep3::bt32BitAxisSweep3(const btVector3& worldAabbMin, const btVector3& worldAabbMax, unsigned int maxHandles, btOverlappingPairCache* pairCache, bool disableRaycastAccelerator) 33 | :btAxisSweep3Internal(worldAabbMin, worldAabbMax,0xfffffffe,0x7fffffff, maxHandles, pairCache, disableRaycastAccelerator) 34 | { 35 | // 1 handle is reserved as sentinel 36 | btAssert(maxHandles > 1 && maxHandles < 2147483647); 37 | } 38 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btBroadphaseProxy.h" 17 | 18 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btCollisionAlgorithm.h" 17 | #include "btDispatcher.h" 18 | 19 | btCollisionAlgorithm::btCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci) 20 | { 21 | m_dispatcher = ci.m_dispatcher1; 22 | } 23 | 24 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btDispatcher.h" 17 | 18 | btDispatcher::~btDispatcher() 19 | { 20 | 21 | } 22 | 23 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | Bullet Continuous Collision Detection and Physics Library 4 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 5 | 6 | This software is provided 'as-is', without any express or implied warranty. 7 | In no event will the authors be held liable for any damages arising from the use of this software. 8 | Permission is granted to anyone to use this software for any purpose, 9 | including commercial applications, and to alter it and redistribute it freely, 10 | subject to the following restrictions: 11 | 12 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 13 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 14 | 3. This notice may not be removed or altered from any source distribution. 15 | */ 16 | 17 | #ifndef OVERLAPPING_PAIR_CALLBACK_H 18 | #define OVERLAPPING_PAIR_CALLBACK_H 19 | 20 | class btDispatcher; 21 | struct btBroadphasePair; 22 | 23 | ///The btOverlappingPairCallback class is an additional optional broadphase user callback for adding/removing overlapping pairs, similar interface to btOverlappingPairCache. 24 | class btOverlappingPairCallback 25 | { 26 | public: 27 | virtual ~btOverlappingPairCallback() 28 | { 29 | 30 | } 31 | 32 | virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1) = 0; 33 | 34 | virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0, btBroadphaseProxy* proxy1, btDispatcher* dispatcher) = 0; 35 | 36 | virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy0, btDispatcher* dispatcher) = 0; 37 | 38 | }; 39 | 40 | #endif //OVERLAPPING_PAIR_CALLBACK_H 41 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SPHERE_TRIANGLE_DETECTOR_H 17 | #define BT_SPHERE_TRIANGLE_DETECTOR_H 18 | 19 | #include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" 20 | 21 | 22 | 23 | class btSphereShape; 24 | class btTriangleShape; 25 | 26 | 27 | 28 | /// sphere-triangle to match the btDiscreteCollisionDetectorInterface 29 | struct SphereTriangleDetector : public btDiscreteCollisionDetectorInterface 30 | { 31 | virtual void getClosestPoints(const ClosestPointInput& input, Result& output, class btIDebugDraw* debugDraw, bool swapResults=false); 32 | 33 | SphereTriangleDetector(btSphereShape* sphere, btTriangleShape* triangle, btScalar contactBreakingThreshold); 34 | 35 | virtual ~SphereTriangleDetector() {}; 36 | 37 | bool collide(const btVector3& sphereCenter, btVector3 &point, btVector3& resultNormal, btScalar& depth, btScalar &timeOfImpact, btScalar contactBreakingThreshold); 38 | 39 | private: 40 | 41 | 42 | bool pointInTriangle(const btVector3 vertices[], const btVector3 &normal, btVector3 *p ); 43 | bool facecontains(const btVector3 &p, const btVector3* vertices, btVector3& normal); 44 | 45 | btSphereShape* m_sphere; 46 | btTriangleShape* m_triangle; 47 | btScalar m_contactBreakingThreshold; 48 | 49 | }; 50 | #endif //BT_SPHERE_TRIANGLE_DETECTOR_H 51 | 52 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btActivatingCollisionAlgorithm.h" 17 | #include "btCollisionDispatcher.h" 18 | #include "btCollisionObject.h" 19 | 20 | btActivatingCollisionAlgorithm::btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci) 21 | :btCollisionAlgorithm(ci) 22 | //, 23 | //m_colObj0(0), 24 | //m_colObj1(0) 25 | { 26 | } 27 | btActivatingCollisionAlgorithm::btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper*, const btCollisionObjectWrapper* ) 28 | :btCollisionAlgorithm(ci) 29 | //, 30 | //m_colObj0(0), 31 | //m_colObj1(0) 32 | { 33 | // if (ci.m_dispatcher1->needsCollision(colObj0, colObj1)) 34 | // { 35 | // m_colObj0 = colObj0; 36 | // m_colObj1 = colObj1; 37 | // 38 | // m_colObj0->activate(); 39 | // m_colObj1->activate(); 40 | // } 41 | } 42 | 43 | btActivatingCollisionAlgorithm::~btActivatingCollisionAlgorithm() 44 | { 45 | // m_colObj0->activate(); 46 | // m_colObj1->activate(); 47 | } 48 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef __BT_ACTIVATING_COLLISION_ALGORITHM_H 17 | #define __BT_ACTIVATING_COLLISION_ALGORITHM_H 18 | 19 | #include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h" 20 | 21 | ///This class is not enabled yet (work-in-progress) to more aggressively activate objects. 22 | class btActivatingCollisionAlgorithm : public btCollisionAlgorithm 23 | { 24 | // btCollisionObject* m_colObj0; 25 | // btCollisionObject* m_colObj1; 26 | 27 | public: 28 | 29 | btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci); 30 | 31 | btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap); 32 | 33 | virtual ~btActivatingCollisionAlgorithm(); 34 | 35 | }; 36 | #endif //__BT_ACTIVATING_COLLISION_ALGORITHM_H 37 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Box-Box collision detection re-distributed under the ZLib license with permission from Russell L. Smith 3 | * Original version is from Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. 4 | * All rights reserved. Email: russ@q12.org Web: www.q12.org 5 | 6 | Bullet Continuous Collision Detection and Physics Library 7 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 8 | 9 | This software is provided 'as-is', without any express or implied warranty. 10 | In no event will the authors be held liable for any damages arising from the use of this software. 11 | Permission is granted to anyone to use this software for any purpose, 12 | including commercial applications, and to alter it and redistribute it freely, 13 | subject to the following restrictions: 14 | 15 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 16 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 17 | 3. This notice may not be removed or altered from any source distribution. 18 | */ 19 | #ifndef BT_BOX_BOX_DETECTOR_H 20 | #define BT_BOX_BOX_DETECTOR_H 21 | 22 | 23 | class btBoxShape; 24 | #include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" 25 | 26 | 27 | /// btBoxBoxDetector wraps the ODE box-box collision detector 28 | /// re-distributed under the Zlib license with permission from Russell L. Smith 29 | struct btBoxBoxDetector : public btDiscreteCollisionDetectorInterface 30 | { 31 | const btBoxShape* m_box1; 32 | const btBoxShape* m_box2; 33 | 34 | public: 35 | 36 | btBoxBoxDetector(const btBoxShape* box1, const btBoxShape* box2); 37 | 38 | virtual ~btBoxBoxDetector() {}; 39 | 40 | virtual void getClosestPoints(const ClosestPointInput& input, Result& output, class btIDebugDraw* debugDraw, bool swapResults=false); 41 | 42 | }; 43 | 44 | #endif //BT_BOX_BOX_DETECTOR_H 45 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_COLLISION_CONFIGURATION 17 | #define BT_COLLISION_CONFIGURATION 18 | 19 | struct btCollisionAlgorithmCreateFunc; 20 | 21 | class btStackAlloc; 22 | class btPoolAllocator; 23 | 24 | ///btCollisionConfiguration allows to configure Bullet collision detection 25 | ///stack allocator size, default collision algorithms and persistent manifold pool size 26 | ///@todo: describe the meaning 27 | class btCollisionConfiguration 28 | { 29 | 30 | public: 31 | 32 | virtual ~btCollisionConfiguration() 33 | { 34 | } 35 | 36 | ///memory pools 37 | virtual btPoolAllocator* getPersistentManifoldPool() = 0; 38 | 39 | virtual btPoolAllocator* getCollisionAlgorithmPool() = 0; 40 | 41 | virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0, int proxyType1) =0; 42 | 43 | }; 44 | 45 | #endif //BT_COLLISION_CONFIGURATION 46 | 47 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_COLLISION_CREATE_FUNC 17 | #define BT_COLLISION_CREATE_FUNC 18 | 19 | #include "LinearMath/btAlignedObjectArray.h" 20 | class btCollisionAlgorithm; 21 | class btCollisionObject; 22 | struct btCollisionObjectWrapper; 23 | struct btCollisionAlgorithmConstructionInfo; 24 | 25 | ///Used by the btCollisionDispatcher to register and create instances for btCollisionAlgorithm 26 | struct btCollisionAlgorithmCreateFunc 27 | { 28 | bool m_swapped; 29 | 30 | btCollisionAlgorithmCreateFunc() 31 | :m_swapped(false) 32 | { 33 | } 34 | virtual ~btCollisionAlgorithmCreateFunc(){}; 35 | 36 | virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo&, const btCollisionObjectWrapper* body0Wrap, const btCollisionObjectWrapper* body1Wrap) 37 | { 38 | 39 | (void)body0Wrap; 40 | (void)body1Wrap; 41 | return 0; 42 | } 43 | }; 44 | #endif //BT_COLLISION_CREATE_FUNC 45 | 46 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_COLLISION_OBJECT_WRAPPER_H 2 | #define BT_COLLISION_OBJECT_WRAPPER_H 3 | 4 | ///btCollisionObjectWrapperis an internal data structure. 5 | ///Most users can ignore this and use btCollisionObject and btCollisionShape instead 6 | class btCollisionShape; 7 | class btCollisionObject; 8 | class btTransform; 9 | #include "LinearMath/btScalar.h" // for SIMD_FORCE_INLINE definition 10 | 11 | #define BT_DECLARE_STACK_ONLY_OBJECT \ 12 | private: \ 13 | void* operator new(size_t size); \ 14 | void operator delete(void*); 15 | 16 | struct btCollisionObjectWrapper; 17 | struct btCollisionObjectWrapper 18 | { 19 | BT_DECLARE_STACK_ONLY_OBJECT 20 | 21 | private: 22 | btCollisionObjectWrapper(const btCollisionObjectWrapper&); // not implemented. Not allowed. 23 | btCollisionObjectWrapper* operator=(const btCollisionObjectWrapper&); 24 | 25 | public: 26 | const btCollisionObjectWrapper* m_parent; 27 | const btCollisionShape* m_shape; 28 | const btCollisionObject* m_collisionObject; 29 | const btTransform& m_worldTransform; 30 | int m_partId; 31 | int m_index; 32 | 33 | btCollisionObjectWrapper(const btCollisionObjectWrapper* parent, const btCollisionShape* shape, const btCollisionObject* collisionObject, const btTransform& worldTransform, int partId, int index) 34 | : m_parent(parent), m_shape(shape), m_collisionObject(collisionObject), m_worldTransform(worldTransform), 35 | m_partId(partId), m_index(index) 36 | {} 37 | 38 | SIMD_FORCE_INLINE const btTransform& getWorldTransform() const { return m_worldTransform; } 39 | SIMD_FORCE_INLINE const btCollisionObject* getCollisionObject() const { return m_collisionObject; } 40 | SIMD_FORCE_INLINE const btCollisionShape* getCollisionShape() const { return m_shape; } 41 | }; 42 | 43 | #endif //BT_COLLISION_OBJECT_WRAPPER_H 44 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btEmptyCollisionAlgorithm.h" 17 | 18 | 19 | 20 | btEmptyAlgorithm::btEmptyAlgorithm(const btCollisionAlgorithmConstructionInfo& ci) 21 | : btCollisionAlgorithm(ci) 22 | { 23 | } 24 | 25 | void btEmptyAlgorithm::processCollision (const btCollisionObjectWrapper*, const btCollisionObjectWrapper*, const btDispatcherInfo&, btManifoldResult* ) 26 | { 27 | } 28 | 29 | btScalar btEmptyAlgorithm::calculateTimeOfImpact(btCollisionObject*, btCollisionObject*, const btDispatcherInfo&, btManifoldResult* ) 30 | { 31 | return btScalar(1.); 32 | } 33 | 34 | 35 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef BT_INTERNAL_EDGE_UTILITY_H 3 | #define BT_INTERNAL_EDGE_UTILITY_H 4 | 5 | #include "LinearMath/btHashMap.h" 6 | #include "LinearMath/btVector3.h" 7 | 8 | #include "BulletCollision/CollisionShapes/btTriangleInfoMap.h" 9 | 10 | ///The btInternalEdgeUtility helps to avoid or reduce artifacts due to wrong collision normals caused by internal edges. 11 | ///See also http://code.google.com/p/bullet/issues/detail?id=27 12 | 13 | class btBvhTriangleMeshShape; 14 | class btCollisionObject; 15 | struct btCollisionObjectWrapper; 16 | class btManifoldPoint; 17 | class btIDebugDraw; 18 | 19 | 20 | 21 | enum btInternalEdgeAdjustFlags 22 | { 23 | BT_TRIANGLE_CONVEX_BACKFACE_MODE = 1, 24 | BT_TRIANGLE_CONCAVE_DOUBLE_SIDED = 2, //double sided options are experimental, single sided is recommended 25 | BT_TRIANGLE_CONVEX_DOUBLE_SIDED = 4 26 | }; 27 | 28 | 29 | ///Call btGenerateInternalEdgeInfo to create triangle info, store in the shape 'userInfo' 30 | void btGenerateInternalEdgeInfo (btBvhTriangleMeshShape *trimeshShape, btTriangleInfoMap* triangleInfoMap); 31 | 32 | 33 | ///Call the btFixMeshNormal to adjust the collision normal, using the triangle info map (generated using btGenerateInternalEdgeInfo) 34 | ///If this info map is missing, or the triangle is not store in this map, nothing will be done 35 | void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWrapper* trimeshColObj0Wrap, const btCollisionObjectWrapper* otherColObj1Wrap, int partId0, int index0, int normalAdjustFlags = 0, btIDebugDraw *drawer = NULL); 36 | 37 | 38 | #endif //BT_INTERNAL_EDGE_UTILITY_H 39 | 40 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btUnionFind.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btUnionFind.h" 17 | 18 | 19 | 20 | btUnionFind::~btUnionFind() 21 | { 22 | Free(); 23 | 24 | } 25 | 26 | btUnionFind::btUnionFind() 27 | { 28 | 29 | } 30 | 31 | void btUnionFind::allocate(int N) 32 | { 33 | m_elements.resize(N); 34 | } 35 | void btUnionFind::Free() 36 | { 37 | m_elements.clear(); 38 | } 39 | 40 | 41 | void btUnionFind::reset(int N) 42 | { 43 | allocate(N); 44 | 45 | for (int i = 0; i < N; i++) 46 | { 47 | m_elements[i].m_id = i; m_elements[i].m_sz = 1; 48 | } 49 | } 50 | 51 | 52 | class btUnionFindElementSortPredicate 53 | { 54 | public: 55 | 56 | bool operator() ( const btElement& lhs, const btElement& rhs ) const 57 | { 58 | return lhs.m_id < rhs.m_id; 59 | } 60 | }; 61 | 62 | ///this is a special operation, destroying the content of btUnionFind. 63 | ///it sorts the elements, based on island id, in order to make it easy to iterate over islands 64 | void btUnionFind::sortIslands() 65 | { 66 | 67 | //first store the original body index, and islandId 68 | int numElements = m_elements.size(); 69 | 70 | for (int i=0;i m_indices; 32 | // btAlignedObjectArray m_connectedFaces; 33 | btScalar m_plane[4]; 34 | }; 35 | 36 | 37 | ATTRIBUTE_ALIGNED16(class) btConvexPolyhedron 38 | { 39 | public: 40 | 41 | BT_DECLARE_ALIGNED_ALLOCATOR(); 42 | 43 | btConvexPolyhedron(); 44 | virtual ~btConvexPolyhedron(); 45 | 46 | btAlignedObjectArray m_vertices; 47 | btAlignedObjectArray m_faces; 48 | btAlignedObjectArray m_uniqueEdges; 49 | 50 | btVector3 m_localCenter; 51 | btVector3 m_extents; 52 | btScalar m_radius; 53 | btVector3 mC; 54 | btVector3 mE; 55 | 56 | void initialize(); 57 | bool testContainment() const; 58 | 59 | void project(const btTransform& trans, const btVector3& dir, btScalar& minProj, btScalar& maxProj, btVector3& witnesPtMin, btVector3& witnesPtMax) const; 60 | }; 61 | 62 | 63 | #endif //_BT_POLYHEDRAL_FEATURES_H 64 | 65 | 66 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btEmptyShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btEmptyShape.h" 17 | 18 | 19 | #include "btCollisionShape.h" 20 | 21 | 22 | btEmptyShape::btEmptyShape() : btConcaveShape () 23 | { 24 | m_shapeType = EMPTY_SHAPE_PROXYTYPE; 25 | } 26 | 27 | 28 | btEmptyShape::~btEmptyShape() 29 | { 30 | } 31 | 32 | 33 | ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version 34 | void btEmptyShape::getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const 35 | { 36 | btVector3 margin(getMargin(), getMargin(), getMargin()); 37 | 38 | aabbMin = t.getOrigin() - margin; 39 | 40 | aabbMax = t.getOrigin() + margin; 41 | 42 | } 43 | 44 | void btEmptyShape::calculateLocalInertia(btScalar, btVector3& ) const 45 | { 46 | btAssert(0); 47 | } 48 | 49 | 50 | 51 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btEmptyShape.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_EMPTY_SHAPE_H 17 | #define BT_EMPTY_SHAPE_H 18 | 19 | #include "btConcaveShape.h" 20 | 21 | #include "LinearMath/btVector3.h" 22 | #include "LinearMath/btTransform.h" 23 | #include "LinearMath/btMatrix3x3.h" 24 | #include "btCollisionMargin.h" 25 | 26 | 27 | 28 | 29 | /// The btEmptyShape is a collision shape without actual collision detection shape, so most users should ignore this class. 30 | /// It can be replaced by another shape during runtime, but the inertia tensor should be recomputed. 31 | ATTRIBUTE_ALIGNED16(class) btEmptyShape : public btConcaveShape 32 | { 33 | public: 34 | BT_DECLARE_ALIGNED_ALLOCATOR(); 35 | 36 | btEmptyShape(); 37 | 38 | virtual ~btEmptyShape(); 39 | 40 | 41 | ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version 42 | void getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const; 43 | 44 | 45 | virtual void setLocalScaling(const btVector3& scaling) 46 | { 47 | m_localScaling = scaling; 48 | } 49 | virtual const btVector3& getLocalScaling() const 50 | { 51 | return m_localScaling; 52 | } 53 | 54 | virtual void calculateLocalInertia(btScalar mass, btVector3& inertia) const; 55 | 56 | virtual const char* getName()const 57 | { 58 | return "Empty"; 59 | } 60 | 61 | virtual void processAllTriangles(btTriangleCallback*, const btVector3&, const btVector3& ) const 62 | { 63 | } 64 | 65 | protected: 66 | btVector3 m_localScaling; 67 | 68 | }; 69 | 70 | 71 | 72 | #endif //BT_EMPTY_SHAPE_H 73 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMaterial.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | /// This file was created by Alex Silverman 17 | 18 | #ifndef BT_MATERIAL_H 19 | #define BT_MATERIAL_H 20 | 21 | // Material class to be used by btMultimaterialTriangleMeshShape to store triangle properties 22 | class btMaterial 23 | { 24 | // public members so that materials can change due to world events 25 | public: 26 | btScalar m_friction; 27 | btScalar m_restitution; 28 | int pad[2]; 29 | 30 | btMaterial(){} 31 | btMaterial(btScalar fric, btScalar rest) { m_friction = fric; m_restitution = rest; } 32 | }; 33 | 34 | #endif // BT_MATERIAL_H 35 | 36 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #include "btMinkowskiSumShape.h" 18 | 19 | 20 | btMinkowskiSumShape::btMinkowskiSumShape(const btConvexShape* shapeA, const btConvexShape* shapeB) 21 | : btConvexInternalShape (), 22 | m_shapeA(shapeA), 23 | m_shapeB(shapeB) 24 | { 25 | m_shapeType = MINKOWSKI_DIFFERENCE_SHAPE_PROXYTYPE; 26 | m_transA.setIdentity(); 27 | m_transB.setIdentity(); 28 | } 29 | 30 | btVector3 btMinkowskiSumShape::localGetSupportingVertexWithoutMargin(const btVector3& vec)const 31 | { 32 | btVector3 supVertexA = m_transA(m_shapeA->localGetSupportingVertexWithoutMargin(vec*m_transA.getBasis())); 33 | btVector3 supVertexB = m_transB(m_shapeB->localGetSupportingVertexWithoutMargin(-vec*m_transB.getBasis())); 34 | return supVertexA - supVertexB; 35 | } 36 | 37 | void btMinkowskiSumShape::batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors, btVector3* supportVerticesOut, int numVectors) const 38 | { 39 | ///@todo: could make recursive use of batching. probably this shape is not used frequently. 40 | for (int i=0;igetMargin() + m_shapeB->getMargin(); 52 | } 53 | 54 | 55 | void btMinkowskiSumShape::calculateLocalInertia(btScalar mass, btVector3& inertia) const 56 | { 57 | (void)mass; 58 | btAssert(0); 59 | inertia.setValue(0,0,0); 60 | } 61 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | /// This file was created by Alex Silverman 17 | 18 | #include "BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h" 19 | #include "BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.h" 20 | //#include "BulletCollision/CollisionShapes/btOptimizedBvh.h" 21 | 22 | 23 | ///Obtains the material for a specific triangle 24 | const btMaterial * btMultimaterialTriangleMeshShape::getMaterialProperties(int partID, int triIndex) 25 | { 26 | const unsigned char * materialBase = 0; 27 | int numMaterials; 28 | PHY_ScalarType materialType; 29 | int materialStride; 30 | const unsigned char * triangleMaterialBase = 0; 31 | int numTriangles; 32 | int triangleMaterialStride; 33 | PHY_ScalarType triangleType; 34 | 35 | ((btTriangleIndexVertexMaterialArray*)m_meshInterface)->getLockedReadOnlyMaterialBase(&materialBase, numMaterials, materialType, materialStride, 36 | &triangleMaterialBase, numTriangles, triangleMaterialStride, triangleType, partID); 37 | 38 | // return the pointer to the place with the friction for the triangle 39 | // TODO: This depends on whether it's a moving mesh or not 40 | // BUG IN GIMPACT 41 | //return (btScalar*)(&materialBase[triangleMaterialBase[(triIndex-1) * triangleMaterialStride] * materialStride]); 42 | int * matInd = (int *)(&(triangleMaterialBase[(triIndex * triangleMaterialStride)])); 43 | btMaterial *matVal = (btMaterial *)(&(materialBase[*matInd * materialStride])); 44 | return (matVal); 45 | } 46 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btShapeHull.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | ///btShapeHull implemented by John McCutchan. 17 | 18 | #ifndef BT_SHAPE_HULL_H 19 | #define BT_SHAPE_HULL_H 20 | 21 | #include "LinearMath/btAlignedObjectArray.h" 22 | #include "BulletCollision/CollisionShapes/btConvexShape.h" 23 | 24 | 25 | ///The btShapeHull class takes a btConvexShape, builds a simplified convex hull using btConvexHull and provides triangle indices and vertices. 26 | ///It can be useful for to simplify a complex convex object and for visualization of a non-polyhedral convex object. 27 | ///It approximates the convex hull using the supporting vertex of 42 directions. 28 | ATTRIBUTE_ALIGNED16(class) btShapeHull 29 | { 30 | protected: 31 | 32 | btAlignedObjectArray m_vertices; 33 | btAlignedObjectArray m_indices; 34 | unsigned int m_numIndices; 35 | const btConvexShape* m_shape; 36 | 37 | static btVector3* getUnitSpherePoints(); 38 | 39 | public: 40 | BT_DECLARE_ALIGNED_ALLOCATOR(); 41 | 42 | btShapeHull (const btConvexShape* shape); 43 | ~btShapeHull (); 44 | 45 | bool buildHull (btScalar margin); 46 | 47 | int numTriangles () const; 48 | int numVertices () const; 49 | int numIndices () const; 50 | 51 | const btVector3* getVertexPointer() const 52 | { 53 | return &m_vertices[0]; 54 | } 55 | const unsigned int* getIndexPointer() const 56 | { 57 | return &m_indices[0]; 58 | } 59 | }; 60 | 61 | #endif //BT_SHAPE_HULL_H 62 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleBuffer.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btTriangleBuffer.h" 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | void btTriangleBuffer::processTriangle(btVector3* triangle, int partId, int triangleIndex) 25 | { 26 | btTriangle tri; 27 | tri.m_vertex0 = triangle[0]; 28 | tri.m_vertex1 = triangle[1]; 29 | tri.m_vertex2 = triangle[2]; 30 | tri.m_partId = partId; 31 | tri.m_triangleIndex = triangleIndex; 32 | 33 | m_triangleBuffer.push_back(tri); 34 | } 35 | 36 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleBuffer.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_TRIANGLE_BUFFER_H 17 | #define BT_TRIANGLE_BUFFER_H 18 | 19 | #include "btTriangleCallback.h" 20 | #include "LinearMath/btAlignedObjectArray.h" 21 | 22 | struct btTriangle 23 | { 24 | btVector3 m_vertex0; 25 | btVector3 m_vertex1; 26 | btVector3 m_vertex2; 27 | int m_partId; 28 | int m_triangleIndex; 29 | }; 30 | 31 | ///The btTriangleBuffer callback can be useful to collect and store overlapping triangles between AABB and concave objects that support 'processAllTriangles' 32 | ///Example usage of this class: 33 | /// btTriangleBuffer triBuf; 34 | /// concaveShape->processAllTriangles(&triBuf, aabbMin, aabbMax); 35 | /// for (int i=0;i m_triangleBuffer; 44 | 45 | public: 46 | 47 | 48 | virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex); 49 | 50 | int getNumTriangles() const 51 | { 52 | return int(m_triangleBuffer.size()); 53 | } 54 | 55 | const btTriangle& getTriangle(int index) const 56 | { 57 | return m_triangleBuffer[index]; 58 | } 59 | 60 | void clearBuffer() 61 | { 62 | m_triangleBuffer.clear(); 63 | } 64 | 65 | }; 66 | 67 | 68 | #endif //BT_TRIANGLE_BUFFER_H 69 | 70 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleCallback.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btTriangleCallback.h" 17 | 18 | btTriangleCallback::~btTriangleCallback() 19 | { 20 | 21 | } 22 | 23 | 24 | btInternalTriangleIndexCallback::~btInternalTriangleIndexCallback() 25 | { 26 | 27 | } 28 | 29 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleCallback.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_TRIANGLE_CALLBACK_H 17 | #define BT_TRIANGLE_CALLBACK_H 18 | 19 | #include "LinearMath/btVector3.h" 20 | 21 | 22 | ///The btTriangleCallback provides a callback for each overlapping triangle when calling processAllTriangles. 23 | ///This callback is called by processAllTriangles for all btConcaveShape derived class, such as btBvhTriangleMeshShape, btStaticPlaneShape and btHeightfieldTerrainShape. 24 | class btTriangleCallback 25 | { 26 | public: 27 | 28 | virtual ~btTriangleCallback(); 29 | virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) = 0; 30 | }; 31 | 32 | class btInternalTriangleIndexCallback 33 | { 34 | public: 35 | 36 | virtual ~btInternalTriangleIndexCallback(); 37 | virtual void internalProcessTriangleIndex(btVector3* triangle, int partId, int triangleIndex) = 0; 38 | }; 39 | 40 | 41 | 42 | #endif //BT_TRIANGLE_CALLBACK_H 43 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/bullet/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactMassUtil.h: -------------------------------------------------------------------------------- 1 | /*! \file btGImpactMassUtil.h 2 | \author Francisco Leon Najera 3 | */ 4 | /* 5 | This source file is part of GIMPACT Library. 6 | 7 | For the latest info, see http://gimpact.sourceforge.net/ 8 | 9 | Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371. 10 | email: projectileman@yahoo.com 11 | 12 | 13 | This software is provided 'as-is', without any express or implied warranty. 14 | In no event will the authors be held liable for any damages arising from the use of this software. 15 | Permission is granted to anyone to use this software for any purpose, 16 | including commercial applications, and to alter it and redistribute it freely, 17 | subject to the following restrictions: 18 | 19 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 20 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 21 | 3. This notice may not be removed or altered from any source distribution. 22 | */ 23 | 24 | 25 | #ifndef GIMPACT_MASS_UTIL_H 26 | #define GIMPACT_MASS_UTIL_H 27 | 28 | #include "LinearMath/btTransform.h" 29 | 30 | 31 | 32 | SIMD_FORCE_INLINE btVector3 gim_inertia_add_transformed( 33 | const btVector3 & source_inertia, const btVector3 & added_inertia, const btTransform & transform) 34 | { 35 | btMatrix3x3 rotatedTensor = transform.getBasis().scaled(added_inertia) * transform.getBasis().transpose(); 36 | 37 | btScalar x2 = transform.getOrigin()[0]; 38 | x2*= x2; 39 | btScalar y2 = transform.getOrigin()[1]; 40 | y2*= y2; 41 | btScalar z2 = transform.getOrigin()[2]; 42 | z2*= z2; 43 | 44 | btScalar ix = rotatedTensor[0][0]*(y2+z2); 45 | btScalar iy = rotatedTensor[1][1]*(x2+z2); 46 | btScalar iz = rotatedTensor[2][2]*(x2+y2); 47 | 48 | return btVector3(source_inertia[0]+ix, source_inertia[1]+iy, source_inertia[2] + iz); 49 | } 50 | 51 | SIMD_FORCE_INLINE btVector3 gim_get_point_inertia(const btVector3 & point, btScalar mass) 52 | { 53 | btScalar x2 = point[0]*point[0]; 54 | btScalar y2 = point[1]*point[1]; 55 | btScalar z2 = point[2]*point[2]; 56 | return btVector3(mass*(y2+z2), mass*(x2+z2), mass*(x2+y2)); 57 | } 58 | 59 | 60 | #endif //GIMPACT_MESH_SHAPE_H 61 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/bullet/src/BulletCollision/Gimpact/btGImpactShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_geometry.h: -------------------------------------------------------------------------------- 1 | #ifndef GIM_GEOMETRY_H_INCLUDED 2 | #define GIM_GEOMETRY_H_INCLUDED 3 | 4 | /*! \file gim_geometry.h 5 | \author Francisco Leon Najera 6 | */ 7 | /* 8 | ----------------------------------------------------------------------------- 9 | This source file is part of GIMPACT Library. 10 | 11 | For the latest info, see http://gimpact.sourceforge.net/ 12 | 13 | Copyright (c) 2006 Francisco Leon Najera. C.C. 80087371. 14 | email: projectileman@yahoo.com 15 | 16 | This library is free software; you can redistribute it and/or 17 | modify it under the terms of EITHER: 18 | (1) The GNU Lesser General Public License as published by the Free 19 | Software Foundation; either version 2.1 of the License, or (at 20 | your option) any later version. The text of the GNU Lesser 21 | General Public License is included with this library in the 22 | file GIMPACT-LICENSE-LGPL.TXT. 23 | (2) The BSD-style license that is included with this library in 24 | the file GIMPACT-LICENSE-BSD.TXT. 25 | (3) The zlib/libpng license that is included with this library in 26 | the file GIMPACT-LICENSE-ZLIB.TXT. 27 | 28 | This library is distributed in the hope that it will be useful, 29 | but WITHOUT ANY WARRANTY; without even the implied warranty of 30 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files 31 | GIMPACT-LICENSE-LGPL.TXT, GIMPACT-LICENSE-ZLIB.TXT and GIMPACT-LICENSE-BSD.TXT for more details. 32 | 33 | ----------------------------------------------------------------------------- 34 | */ 35 | 36 | ///Additional Headers for Collision 37 | #include "gim_basic_geometry_operations.h" 38 | #include "gim_clip_polygon.h" 39 | #include "gim_box_collision.h" 40 | #include "gim_tri_collision.h" 41 | 42 | #endif // GIM_VECTOR_H_INCLUDED 43 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btConvexCast.h" 17 | 18 | btConvexCast::~btConvexCast() 19 | { 20 | } 21 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #ifndef BT_CONVEX_PENETRATION_DEPTH_H 18 | #define BT_CONVEX_PENETRATION_DEPTH_H 19 | 20 | class btStackAlloc; 21 | class btVector3; 22 | #include "btSimplexSolverInterface.h" 23 | class btConvexShape; 24 | class btTransform; 25 | 26 | ///ConvexPenetrationDepthSolver provides an interface for penetration depth calculation. 27 | class btConvexPenetrationDepthSolver 28 | { 29 | public: 30 | 31 | virtual ~btConvexPenetrationDepthSolver() {}; 32 | virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 33 | const btConvexShape* convexA, const btConvexShape* convexB, 34 | const btTransform& transA, const btTransform& transB, 35 | btVector3& v, btVector3& pa, btVector3& pb, 36 | class btIDebugDraw* debugDraw, btStackAlloc* stackAlloc 37 | ) = 0; 38 | 39 | 40 | }; 41 | #endif //BT_CONVEX_PENETRATION_DEPTH_H 42 | 43 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | 18 | #ifndef BT_GJK_CONVEX_CAST_H 19 | #define BT_GJK_CONVEX_CAST_H 20 | 21 | #include "BulletCollision/CollisionShapes/btCollisionMargin.h" 22 | 23 | #include "LinearMath/btVector3.h" 24 | #include "btConvexCast.h" 25 | class btConvexShape; 26 | class btMinkowskiSumShape; 27 | #include "btSimplexSolverInterface.h" 28 | 29 | ///GjkConvexCast performs a raycast on a convex object using support mapping. 30 | class btGjkConvexCast : public btConvexCast 31 | { 32 | btSimplexSolverInterface* m_simplexSolver; 33 | const btConvexShape* m_convexA; 34 | const btConvexShape* m_convexB; 35 | 36 | public: 37 | 38 | btGjkConvexCast(const btConvexShape* convexA, const btConvexShape* convexB, btSimplexSolverInterface* simplexSolver); 39 | 40 | /// cast a convex against another convex object 41 | virtual bool calcTimeOfImpact( 42 | const btTransform& fromA, 43 | const btTransform& toA, 44 | const btTransform& fromB, 45 | const btTransform& toB, 46 | CastResult& result); 47 | 48 | }; 49 | 50 | #endif //BT_GJK_CONVEX_CAST_H 51 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | EPA Copyright (c) Ricardo Padrela 2006 6 | 7 | This software is provided 'as-is', without any express or implied warranty. 8 | In no event will the authors be held liable for any damages arising from the use of this software. 9 | Permission is granted to anyone to use this software for any purpose, 10 | including commercial applications, and to alter it and redistribute it freely, 11 | subject to the following restrictions: 12 | 13 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 14 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 15 | 3. This notice may not be removed or altered from any source distribution. 16 | */ 17 | #ifndef BT_GJP_EPA_PENETRATION_DEPTH_H 18 | #define BT_GJP_EPA_PENETRATION_DEPTH_H 19 | 20 | #include "btConvexPenetrationDepthSolver.h" 21 | 22 | ///EpaPenetrationDepthSolver uses the Expanding Polytope Algorithm to 23 | ///calculate the penetration depth between two convex shapes. 24 | // DrChat: CHANGE btConvexConvexAlgorithm.cpp:194 IF YOU ADD ANY CLASS MEMBERS 25 | class btGjkEpaPenetrationDepthSolver : public btConvexPenetrationDepthSolver 26 | { 27 | public : 28 | 29 | btGjkEpaPenetrationDepthSolver() 30 | { 31 | } 32 | 33 | bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 34 | const btConvexShape* pConvexA, const btConvexShape* pConvexB, 35 | const btTransform& transformA, const btTransform& transformB, 36 | btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB, 37 | class btIDebugDraw* debugDraw, btStackAlloc* stackAlloc ); 38 | 39 | private : 40 | 41 | }; 42 | 43 | #endif // BT_GJP_EPA_PENETRATION_DEPTH_H 44 | 45 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 17 | #define BT_MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 18 | 19 | #include "btConvexPenetrationDepthSolver.h" 20 | 21 | ///MinkowskiPenetrationDepthSolver implements bruteforce penetration depth estimation. 22 | ///Implementation is based on sampling the depth using support mapping, and using GJK step to get the witness points. 23 | // DrChat: CHANGE btConvexConvexAlgorithm.cpp:194 IF YOU ADD ANY CLASS MEMBERS 24 | class btMinkowskiPenetrationDepthSolver : public btConvexPenetrationDepthSolver 25 | { 26 | protected: 27 | 28 | static btVector3* getPenetrationDirections(); 29 | 30 | public: 31 | 32 | virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 33 | const btConvexShape* convexA, const btConvexShape* convexB, 34 | const btTransform& transA, const btTransform& transB, 35 | btVector3& v, btVector3& pa, btVector3& pb, 36 | class btIDebugDraw* debugDraw, btStackAlloc* stackAlloc 37 | ); 38 | }; 39 | 40 | #endif //BT_MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 41 | 42 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_POINT_COLLECTOR_H 17 | #define BT_POINT_COLLECTOR_H 18 | 19 | #include "btDiscreteCollisionDetectorInterface.h" 20 | 21 | 22 | 23 | struct btPointCollector : public btDiscreteCollisionDetectorInterface::Result 24 | { 25 | 26 | 27 | btVector3 m_normalOnBInWorld; 28 | btVector3 m_pointInWorld; 29 | btScalar m_distance;//negative means penetration 30 | 31 | bool m_hasResult; 32 | 33 | btPointCollector () 34 | : m_distance(btScalar(BT_LARGE_FLOAT)), m_hasResult(false) 35 | { 36 | } 37 | 38 | virtual void setShapeIdentifiersA(int partId0, int index0) 39 | { 40 | (void)partId0; 41 | (void)index0; 42 | 43 | } 44 | virtual void setShapeIdentifiersB(int partId1, int index1) 45 | { 46 | (void)partId1; 47 | (void)index1; 48 | } 49 | 50 | virtual void addContactPoint(const btVector3& normalOnBInWorld, const btVector3& pointInWorld, btScalar depth) 51 | { 52 | if (depth< m_distance) 53 | { 54 | m_hasResult = true; 55 | m_normalOnBInWorld = normalOnBInWorld; 56 | m_pointInWorld = pointInWorld; 57 | //negative means penetration 58 | m_distance = depth; 59 | } 60 | } 61 | }; 62 | 63 | #endif //BT_POINT_COLLECTOR_H 64 | 65 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | 18 | #ifndef BT_SIMPLEX_SOLVER_INTERFACE_H 19 | #define BT_SIMPLEX_SOLVER_INTERFACE_H 20 | 21 | #include "LinearMath/btVector3.h" 22 | 23 | #define NO_VIRTUAL_INTERFACE 1 24 | #ifdef NO_VIRTUAL_INTERFACE 25 | #include "btVoronoiSimplexSolver.h" 26 | #define btSimplexSolverInterface btVoronoiSimplexSolver 27 | #else 28 | 29 | /// btSimplexSolverInterface can incrementally calculate distance between origin and up to 4 vertices 30 | /// Used by GJK or Linear Casting. Can be implemented by the Johnson-algorithm or alternative approaches based on 31 | /// voronoi regions or barycentric coordinates 32 | class btSimplexSolverInterface 33 | { 34 | public: 35 | virtual ~btSimplexSolverInterface() {}; 36 | 37 | virtual void reset() = 0; 38 | 39 | virtual void addVertex(const btVector3& w, const btVector3& p, const btVector3& q) = 0; 40 | 41 | virtual bool closest(btVector3& v) = 0; 42 | 43 | virtual btScalar maxVertex() = 0; 44 | 45 | virtual bool fullSimplex() const = 0; 46 | 47 | virtual int getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const = 0; 48 | 49 | virtual bool inSimplex(const btVector3& w) = 0; 50 | 51 | virtual void backup_closest(btVector3& v) = 0; 52 | 53 | virtual bool emptySimplex() const = 0; 54 | 55 | virtual void compute_points(btVector3& p1, btVector3& p2) = 0; 56 | 57 | virtual int numVertices() const =0; 58 | 59 | 60 | }; 61 | #endif 62 | #endif //BT_SIMPLEX_SOLVER_INTERFACE_H 63 | 64 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #ifndef BT_SUBSIMPLEX_CONVEX_CAST_H 18 | #define BT_SUBSIMPLEX_CONVEX_CAST_H 19 | 20 | #include "btConvexCast.h" 21 | #include "btSimplexSolverInterface.h" 22 | class btConvexShape; 23 | 24 | /// btSubsimplexConvexCast implements Gino van den Bergens' paper 25 | ///"Ray Casting against bteral Convex Objects with Application to Continuous Collision Detection" 26 | /// GJK based Ray Cast, optimized version 27 | /// Objects should not start in overlap, otherwise results are not defined. 28 | class btSubsimplexConvexCast : public btConvexCast 29 | { 30 | btSimplexSolverInterface* m_simplexSolver; 31 | const btConvexShape* m_convexA; 32 | const btConvexShape* m_convexB; 33 | 34 | public: 35 | 36 | btSubsimplexConvexCast (const btConvexShape* shapeA, const btConvexShape* shapeB, btSimplexSolverInterface* simplexSolver); 37 | 38 | //virtual ~btSubsimplexConvexCast(); 39 | ///SimsimplexConvexCast calculateTimeOfImpact calculates the time of impact+normal for the linear cast (sweep) between two moving objects. 40 | ///Precondition is that objects should not penetration/overlap at the start from the interval. Overlap can be tested using btGjkPairDetector. 41 | virtual bool calcTimeOfImpact( 42 | const btTransform& fromA, 43 | const btTransform& toA, 44 | const btTransform& fromB, 45 | const btTransform& toB, 46 | CastResult& result); 47 | 48 | }; 49 | 50 | #endif //BT_SUBSIMPLEX_CONVEX_CAST_H 51 | -------------------------------------------------------------------------------- /bullet/src/BulletCollision/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletCollision" 2 | 3 | language "C++" 4 | 5 | kind "StaticLib" 6 | 7 | includedirs { 8 | "..", 9 | } 10 | 11 | files { 12 | "**.cpp", 13 | "**.h" 14 | } -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_CHARACTER_CONTROLLER_INTERFACE_H 17 | #define BT_CHARACTER_CONTROLLER_INTERFACE_H 18 | 19 | #include "LinearMath/btVector3.h" 20 | #include "BulletDynamics/Dynamics/btActionInterface.h" 21 | 22 | class btCollisionShape; 23 | class btRigidBody; 24 | class btCollisionWorld; 25 | 26 | class btCharacterControllerInterface : public btActionInterface 27 | { 28 | public: 29 | btCharacterControllerInterface () {}; 30 | virtual ~btCharacterControllerInterface () {}; 31 | 32 | virtual void setWalkDirection(const btVector3& walkDirection) = 0; 33 | virtual void setVelocityForTimeInterval(const btVector3& velocity, btScalar timeInterval) = 0; 34 | virtual void reset ( btCollisionWorld* collisionWorld ) = 0; 35 | virtual void warp (const btVector3& origin) = 0; 36 | 37 | virtual void preStep ( btCollisionWorld* collisionWorld) = 0; 38 | virtual void playerStep (btCollisionWorld* collisionWorld, btScalar dt) = 0; 39 | virtual bool canJump () const = 0; 40 | virtual void jump () = 0; 41 | 42 | virtual bool onGround () const = 0; 43 | virtual void setUpInterpolate (bool value) = 0; 44 | }; 45 | 46 | #endif //BT_CHARACTER_CONTROLLER_INTERFACE_H 47 | 48 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btFixedConstraint.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2013 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_FIXED_CONSTRAINT_H 17 | #define BT_FIXED_CONSTRAINT_H 18 | 19 | #include "btTypedConstraint.h" 20 | 21 | ATTRIBUTE_ALIGNED16(class) btFixedConstraint : public btTypedConstraint 22 | { 23 | 24 | btTransform m_frameInA; 25 | btTransform m_frameInB; 26 | public: 27 | btFixedConstraint(btRigidBody& rbA,btRigidBody& rbB, const btTransform& frameInA,const btTransform& frameInB); 28 | 29 | virtual ~btFixedConstraint(); 30 | 31 | 32 | virtual void getInfo1 (btConstraintInfo1* info); 33 | 34 | virtual void getInfo2 (btConstraintInfo2* info); 35 | 36 | virtual void setParam(int num, btScalar value, int axis = -1) 37 | { 38 | btAssert(0); 39 | } 40 | virtual btScalar getParam(int num, int axis = -1) const 41 | { 42 | btAssert(0); 43 | return 0.f; 44 | } 45 | 46 | virtual void debugDraw(btIDebugDraw *debugDraw); 47 | }; 48 | 49 | #endif //BT_FIXED_CONSTRAINT_H 50 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGearConstraint.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2012 Advanced Micro Devices, Inc. http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | /// Implemented by Erwin Coumans. The idea for the constraint comes from Dimitris Papavasiliou. 17 | 18 | #include "btGearConstraint.h" 19 | 20 | btGearConstraint::btGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA, const btVector3& axisInB, btScalar ratio) 21 | :btTypedConstraint(GEAR_CONSTRAINT_TYPE, rbA, rbB), 22 | m_axisInA(axisInA), 23 | m_axisInB(axisInB), 24 | m_ratio(ratio) 25 | { 26 | } 27 | 28 | btGearConstraint::~btGearConstraint () 29 | { 30 | } 31 | 32 | void btGearConstraint::getInfo1 (btConstraintInfo1* info) 33 | { 34 | info->m_numConstraintRows = 1; 35 | info->nub = 1; 36 | } 37 | 38 | void btGearConstraint::getInfo2 (btConstraintInfo2* info) 39 | { 40 | btVector3 globalAxisA, globalAxisB; 41 | 42 | globalAxisA = m_rbA.getWorldTransform().getBasis()*this->m_axisInA; 43 | globalAxisB = m_rbB.getWorldTransform().getBasis()*this->m_axisInB; 44 | 45 | info->m_J1angularAxis[0] = globalAxisA[0]; 46 | info->m_J1angularAxis[1] = globalAxisA[1]; 47 | info->m_J1angularAxis[2] = globalAxisA[2]; 48 | 49 | info->m_J2angularAxis[0] = m_ratio*globalAxisB[0]; 50 | info->m_J2angularAxis[1] = m_ratio*globalAxisB[1]; 51 | info->m_J2angularAxis[2] = m_ratio*globalAxisB[2]; 52 | 53 | } 54 | 55 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btActionInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef _BT_ACTION_INTERFACE_H 17 | #define _BT_ACTION_INTERFACE_H 18 | 19 | class btIDebugDraw; 20 | class btCollisionWorld; 21 | 22 | #include "LinearMath/btScalar.h" 23 | #include "btRigidBody.h" 24 | 25 | ///Basic interface to allow actions such as vehicles and characters to be updated inside a btDynamicsWorld 26 | class btActionInterface 27 | { 28 | protected: 29 | 30 | static SIMD_FORCE_INLINE btRigidBody& getFixedBody() { 31 | static btRigidBody s_fixed(0, 0,0); 32 | s_fixed.setMassProps(btScalar(0.), btVector3(btScalar(0.), btScalar(0.), btScalar(0.))); 33 | return s_fixed; 34 | } 35 | 36 | 37 | public: 38 | 39 | virtual ~btActionInterface() 40 | { 41 | } 42 | 43 | virtual void updateAction( btCollisionWorld* collisionWorld, btScalar deltaTimeStep)=0; 44 | 45 | virtual void debugDraw(btIDebugDraw* debugDrawer) {(void)(debugDrawer);} 46 | 47 | }; 48 | 49 | #endif //_BT_ACTION_INTERFACE_H 50 | 51 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2013 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_MULTIBODY_JOINT_LIMIT_CONSTRAINT_H 17 | #define BT_MULTIBODY_JOINT_LIMIT_CONSTRAINT_H 18 | 19 | #include "btMultiBodyConstraint.h" 20 | struct btSolverInfo; 21 | 22 | class btMultiBodyJointLimitConstraint : public btMultiBodyConstraint 23 | { 24 | protected: 25 | 26 | btScalar m_lowerBound; 27 | btScalar m_upperBound; 28 | public: 29 | 30 | btMultiBodyJointLimitConstraint(btMultiBody* body, int link, btScalar lower, btScalar upper); 31 | virtual ~btMultiBodyJointLimitConstraint(); 32 | 33 | virtual int getIslandIdA() const; 34 | virtual int getIslandIdB() const; 35 | 36 | virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows, 37 | btMultiBodyJacobianData& data, 38 | const btContactSolverInfo& infoGlobal); 39 | 40 | 41 | }; 42 | 43 | #endif //BT_MULTIBODY_JOINT_LIMIT_CONSTRAINT_H 44 | 45 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2013 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | ///This file was written by Erwin Coumans 17 | 18 | #ifndef BT_MULTIBODY_JOINT_MOTOR_H 19 | #define BT_MULTIBODY_JOINT_MOTOR_H 20 | 21 | #include "btMultiBodyConstraint.h" 22 | struct btSolverInfo; 23 | 24 | class btMultiBodyJointMotor : public btMultiBodyConstraint 25 | { 26 | protected: 27 | 28 | 29 | btScalar m_desiredVelocity; 30 | 31 | public: 32 | 33 | btMultiBodyJointMotor(btMultiBody* body, int link, btScalar desiredVelocity, btScalar maxMotorImpulse); 34 | virtual ~btMultiBodyJointMotor(); 35 | 36 | virtual int getIslandIdA() const; 37 | virtual int getIslandIdB() const; 38 | 39 | virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows, 40 | btMultiBodyJacobianData& data, 41 | const btContactSolverInfo& infoGlobal); 42 | 43 | 44 | }; 45 | 46 | #endif //BT_MULTIBODY_JOINT_MOTOR_H 47 | 48 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2013 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | ///This file was written by Erwin Coumans 17 | 18 | #ifndef BT_MULTIBODY_POINT2POINT_H 19 | #define BT_MULTIBODY_POINT2POINT_H 20 | 21 | #include "btMultiBodyConstraint.h" 22 | 23 | class btMultiBodyPoint2Point : public btMultiBodyConstraint 24 | { 25 | protected: 26 | 27 | btRigidBody* m_rigidBodyA; 28 | btRigidBody* m_rigidBodyB; 29 | btVector3 m_pivotInA; 30 | btVector3 m_pivotInB; 31 | 32 | 33 | public: 34 | 35 | btMultiBodyPoint2Point(btMultiBody* body, int link, btRigidBody* bodyB, const btVector3& pivotInA, const btVector3& pivotInB); 36 | btMultiBodyPoint2Point(btMultiBody* bodyA, int linkA, btMultiBody* bodyB, int linkB, const btVector3& pivotInA, const btVector3& pivotInB); 37 | 38 | virtual ~btMultiBodyPoint2Point(); 39 | 40 | virtual int getIslandIdA() const; 41 | virtual int getIslandIdB() const; 42 | 43 | virtual void createConstraintRows(btMultiBodyConstraintArray& constraintRows, 44 | btMultiBodyJacobianData& data, 45 | const btContactSolverInfo& infoGlobal); 46 | 47 | const btVector3& getPivotInB() const 48 | { 49 | return m_pivotInB; 50 | } 51 | 52 | void setPivotInB(const btVector3& pivotInB) 53 | { 54 | m_pivotInB = pivotInB; 55 | } 56 | 57 | 58 | }; 59 | 60 | #endif //BT_MULTIBODY_POINT2POINT_H 61 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/bullet/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolverInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2013 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | ///original version written by Erwin Coumans, October 2013 16 | 17 | #ifndef BT_MLCP_SOLVER_INTERFACE_H 18 | #define BT_MLCP_SOLVER_INTERFACE_H 19 | 20 | #include "LinearMath/btMatrixX.h" 21 | 22 | class btMLCPSolverInterface 23 | { 24 | public: 25 | virtual ~btMLCPSolverInterface() 26 | { 27 | } 28 | 29 | //return true is it solves the problem successfully 30 | virtual bool solveMLCP(const btMatrixXu & A, const btVectorXu & b, btVectorXu& x, const btVectorXu & lo,const btVectorXu & hi,const btAlignedObjectArray& limitDependency, int numIterations, bool useSparsity = true)=0; 31 | }; 32 | 33 | #endif //BT_MLCP_SOLVER_INTERFACE_H 34 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btVehicleRaycaster.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2005 Erwin Coumans http://bulletphysics.org 3 | * 4 | * Permission to use, copy, modify, distribute and sell this software 5 | * and its documentation for any purpose is hereby granted without fee, 6 | * provided that the above copyright notice appear in all copies. 7 | * Erwin Coumans makes no representations about the suitability 8 | * of this software for any purpose. 9 | * It is provided "as is" without express or implied warranty. 10 | */ 11 | #ifndef BT_VEHICLE_RAYCASTER_H 12 | #define BT_VEHICLE_RAYCASTER_H 13 | 14 | #include "LinearMath/btVector3.h" 15 | 16 | struct btWheelInfo; 17 | 18 | /// btVehicleRaycaster is provides interface for between vehicle simulation and raycasting 19 | struct btVehicleRaycaster 20 | { 21 | virtual ~btVehicleRaycaster() 22 | { 23 | } 24 | 25 | struct btVehicleRaycasterResult 26 | { 27 | btVehicleRaycasterResult() :m_distFraction(btScalar(-1.)){}; 28 | btVector3 m_hitPointInWorld; 29 | btVector3 m_hitNormalInWorld; 30 | btScalar m_distFraction; 31 | }; 32 | 33 | virtual void* castRay(btWheelInfo *wheel, const btVector3& from, const btVector3& to, btVehicleRaycasterResult& result) = 0; 34 | 35 | }; 36 | 37 | #endif //BT_VEHICLE_RAYCASTER_H 38 | 39 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btWheelInfo.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/ 3 | * 4 | * Permission to use, copy, modify, distribute and sell this software 5 | * and its documentation for any purpose is hereby granted without fee, 6 | * provided that the above copyright notice appear in all copies. 7 | * Erwin Coumans makes no representations about the suitability 8 | * of this software for any purpose. 9 | * It is provided "as is" without express or implied warranty. 10 | */ 11 | #include "btWheelInfo.h" 12 | #include "BulletDynamics/Dynamics/btRigidBody.h" // for pointvelocity 13 | 14 | 15 | btScalar btWheelInfo::getSuspensionRestLength() const 16 | { 17 | return m_suspensionRestLength1; 18 | } 19 | 20 | void btWheelInfo::updateWheel(const btRigidBody& chassis, RaycastInfo& raycastInfo) 21 | { 22 | (void)raycastInfo; 23 | 24 | 25 | if (m_raycastInfo.m_isInContact) 26 | { 27 | btScalar project= m_raycastInfo.m_contactNormalWS.dot( m_raycastInfo.m_wheelDirectionWS ); 28 | btVector3 chassis_velocity_at_contactPoint; 29 | btVector3 relpos = m_raycastInfo.m_contactPointWS - chassis.getCenterOfMassPosition(); 30 | chassis_velocity_at_contactPoint = chassis.getVelocityInLocalPoint( relpos ); 31 | btScalar projVel = m_raycastInfo.m_contactNormalWS.dot( chassis_velocity_at_contactPoint ); 32 | if ( project >= btScalar(-0.1)) 33 | { 34 | m_suspensionRelativeVelocity = btScalar(0.0); 35 | m_clippedInvContactDotSuspension = btScalar(1.0) / btScalar(0.1); 36 | } 37 | else 38 | { 39 | btScalar inv = btScalar(-1.) / project; 40 | m_suspensionRelativeVelocity = projVel * inv; 41 | m_clippedInvContactDotSuspension = inv; 42 | } 43 | } 44 | else // Not in contact : position wheel in a nice (rest length) position 45 | { 46 | m_raycastInfo.m_suspensionLength = this->getSuspensionRestLength(); 47 | m_suspensionRelativeVelocity = btScalar(0.0); 48 | m_raycastInfo.m_contactNormalWS = -m_raycastInfo.m_wheelDirectionWS; 49 | m_clippedInvContactDotSuspension = btScalar(1.0); 50 | } 51 | } 52 | -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletDynamics" 2 | 3 | kind "StaticLib" 4 | 5 | language "C++" 6 | 7 | includedirs { 8 | "..", 9 | } 10 | 11 | files { 12 | "**.cpp", 13 | "**.h" 14 | } -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/Integrate.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer IntegrateCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float solverdt; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_vertexInverseMasses : register( t0 ); 13 | 14 | RWStructuredBuffer g_vertexPositions : register( u0 ); 15 | RWStructuredBuffer g_vertexVelocity : register( u1 ); 16 | RWStructuredBuffer g_vertexPreviousPositions : register( u2 ); 17 | RWStructuredBuffer g_vertexForceAccumulator : register( u3 ); 18 | 19 | [numthreads(128, 1, 1)] 20 | void 21 | IntegrateKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 22 | { 23 | int nodeID = DTid.x; 24 | if( nodeID < numNodes ) 25 | { 26 | float3 position = g_vertexPositions[nodeID].xyz; 27 | float3 velocity = g_vertexVelocity[nodeID].xyz; 28 | float3 force = g_vertexForceAccumulator[nodeID].xyz; 29 | float inverseMass = g_vertexInverseMasses[nodeID]; 30 | 31 | g_vertexPreviousPositions[nodeID] = float4(position, 0.f); 32 | velocity += force * inverseMass * solverdt; 33 | position += velocity * solverdt; 34 | 35 | g_vertexForceAccumulator[nodeID] = float4(0.f, 0.f, 0.f, 0.0f); 36 | g_vertexPositions[nodeID] = float4(position, 0.f); 37 | g_vertexVelocity[nodeID] = float4(velocity, 0.f); 38 | } 39 | } 40 | 41 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/OutputToVertexArray.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer OutputToVertexArrayCB : register( b0 ) 4 | { 5 | int startNode; 6 | int numNodes; 7 | int positionOffset; 8 | int positionStride; 9 | 10 | int normalOffset; 11 | int normalStride; 12 | int padding1; 13 | int padding2; 14 | }; 15 | 16 | 17 | StructuredBuffer g_vertexPositions : register( t0 ); 18 | StructuredBuffer g_vertexNormals : register( t1 ); 19 | 20 | RWBuffer g_vertexBuffer : register( u0 ); 21 | 22 | 23 | [numthreads(128, 1, 1)] 24 | void 25 | OutputToVertexArrayWithNormalsKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 26 | { 27 | int nodeID = DTid.x; 28 | if( nodeID < numNodes ) 29 | { 30 | float4 position = g_vertexPositions[nodeID + startNode]; 31 | float4 normal = g_vertexNormals[nodeID + startNode]; 32 | 33 | // Stride should account for the float->float4 conversion 34 | int positionDestination = nodeID * positionStride + positionOffset; 35 | g_vertexBuffer[positionDestination] = position.x; 36 | g_vertexBuffer[positionDestination+1] = position.y; 37 | g_vertexBuffer[positionDestination+2] = position.z; 38 | 39 | int normalDestination = nodeID * normalStride + normalOffset; 40 | g_vertexBuffer[normalDestination] = normal.x; 41 | g_vertexBuffer[normalDestination+1] = normal.y; 42 | g_vertexBuffer[normalDestination+2] = normal.z; 43 | } 44 | } 45 | 46 | [numthreads(128, 1, 1)] 47 | void 48 | OutputToVertexArrayWithoutNormalsKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 49 | { 50 | int nodeID = DTid.x; 51 | if( nodeID < numNodes ) 52 | { 53 | float4 position = g_vertexPositions[nodeID + startNode]; 54 | float4 normal = g_vertexNormals[nodeID + startNode]; 55 | 56 | // Stride should account for the float->float4 conversion 57 | int positionDestination = nodeID * positionStride + positionOffset; 58 | g_vertexBuffer[positionDestination] = position.x; 59 | g_vertexBuffer[positionDestination+1] = position.y; 60 | g_vertexBuffer[positionDestination+2] = position.z; 61 | } 62 | } 63 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/PrepareLinks.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer PrepareLinksCB : register( b0 ) 4 | { 5 | int numLinks; 6 | int padding0; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | StructuredBuffer g_linksMassLSC : register( t1 ); 14 | StructuredBuffer g_nodesPreviousPosition : register( t2 ); 15 | 16 | RWStructuredBuffer g_linksLengthRatio : register( u0 ); 17 | RWStructuredBuffer g_linksCurrentLength : register( u1 ); 18 | 19 | [numthreads(128, 1, 1)] 20 | void 21 | PrepareLinksKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 22 | { 23 | int linkID = DTid.x; 24 | if( linkID < numLinks ) 25 | { 26 | int2 nodeIndices = g_linksVertexIndices[linkID]; 27 | int node0 = nodeIndices.x; 28 | int node1 = nodeIndices.y; 29 | 30 | float4 nodePreviousPosition0 = g_nodesPreviousPosition[node0]; 31 | float4 nodePreviousPosition1 = g_nodesPreviousPosition[node1]; 32 | 33 | float massLSC = g_linksMassLSC[linkID]; 34 | 35 | float4 linkCurrentLength = nodePreviousPosition1 - nodePreviousPosition0; 36 | 37 | float linkLengthRatio = dot(linkCurrentLength, linkCurrentLength)*massLSC; 38 | linkLengthRatio = 1./linkLengthRatio; 39 | 40 | g_linksCurrentLength[linkID] = linkCurrentLength; 41 | g_linksLengthRatio[linkID] = linkLengthRatio; 42 | } 43 | } 44 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/SolvePositions.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer SolvePositionsFromLinksKernelCB : register( b0 ) 4 | { 5 | int startLink; 6 | int numLinks; 7 | float kst; 8 | float ti; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | 14 | StructuredBuffer g_linksMassLSC : register( t1 ); 15 | StructuredBuffer g_linksRestLengthSquared : register( t2 ); 16 | StructuredBuffer g_verticesInverseMass : register( t3 ); 17 | 18 | RWStructuredBuffer g_vertexPositions : register( u0 ); 19 | 20 | [numthreads(128, 1, 1)] 21 | void 22 | SolvePositionsFromLinksKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 23 | { 24 | int linkID = DTid.x + startLink; 25 | if( DTid.x < numLinks ) 26 | { 27 | float massLSC = g_linksMassLSC[linkID]; 28 | float restLengthSquared = g_linksRestLengthSquared[linkID]; 29 | 30 | if( massLSC > 0.0f ) 31 | { 32 | int2 nodeIndices = g_linksVertexIndices[linkID]; 33 | int node0 = nodeIndices.x; 34 | int node1 = nodeIndices.y; 35 | 36 | float3 position0 = g_vertexPositions[node0].xyz; 37 | float3 position1 = g_vertexPositions[node1].xyz; 38 | 39 | float inverseMass0 = g_verticesInverseMass[node0]; 40 | float inverseMass1 = g_verticesInverseMass[node1]; 41 | 42 | float3 del = position1 - position0; 43 | float len = dot(del, del); 44 | float k = ((restLengthSquared - len)/(massLSC*(restLengthSquared+len)))*kst; 45 | position0 = position0 - del*(k*inverseMass0); 46 | position1 = position1 + del*(k*inverseMass1); 47 | 48 | g_vertexPositions[node0] = float4(position0, 0.f); 49 | g_vertexPositions[node1] = float4(position1, 0.f); 50 | 51 | } 52 | } 53 | } 54 | 55 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateConstants.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdateConstantsCB : register( b0 ) 4 | { 5 | int numLinks; 6 | int padding0; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | StructuredBuffer g_vertexPositions : register( t1 ); 14 | StructuredBuffer g_vertexInverseMasses : register( t2 ); 15 | StructuredBuffer g_linksMaterialLSC : register( t3 ); 16 | 17 | RWStructuredBuffer g_linksMassLSC : register( u0 ); 18 | RWStructuredBuffer g_linksRestLengthSquared : register( u1 ); 19 | RWStructuredBuffer g_linksRestLengths : register( u2 ); 20 | 21 | [numthreads(128, 1, 1)] 22 | void 23 | UpdateConstantsKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 24 | { 25 | int linkID = DTid.x; 26 | if( linkID < numLinks ) 27 | { 28 | int2 nodeIndices = g_linksVertexIndices[linkID]; 29 | int node0 = nodeIndices.x; 30 | int node1 = nodeIndices.y; 31 | float linearStiffnessCoefficient = g_linksMaterialLSC[ linkID ]; 32 | 33 | float3 position0 = g_vertexPositions[node0].xyz; 34 | float3 position1 = g_vertexPositions[node1].xyz; 35 | float inverseMass0 = g_vertexInverseMasses[node0]; 36 | float inverseMass1 = g_vertexInverseMasses[node1]; 37 | 38 | float3 difference = position0 - position1; 39 | float length2 = dot(difference, difference); 40 | float length = sqrt(length2); 41 | 42 | g_linksRestLengths[linkID] = length; 43 | g_linksMassLSC[linkID] = (inverseMass0 + inverseMass1)/linearStiffnessCoefficient; 44 | g_linksRestLengthSquared[linkID] = length*length; 45 | } 46 | } 47 | 48 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateNodes.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdateVelocitiesFromPositionsWithVelocitiesCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float isolverdt; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | 12 | StructuredBuffer g_vertexPositions : register( t0 ); 13 | StructuredBuffer g_vertexPreviousPositions : register( t1 ); 14 | StructuredBuffer g_vertexClothIndices : register( t2 ); 15 | StructuredBuffer g_clothVelocityCorrectionCoefficients : register( t3 ); 16 | StructuredBuffer g_clothDampingFactor : register( t4 ); 17 | 18 | RWStructuredBuffer g_vertexVelocities : register( u0 ); 19 | RWStructuredBuffer g_vertexForces : register( u1 ); 20 | 21 | 22 | [numthreads(128, 1, 1)] 23 | void 24 | updateVelocitiesFromPositionsWithVelocitiesKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 25 | { 26 | int nodeID = DTid.x; 27 | if( nodeID < numNodes ) 28 | { 29 | float3 position = g_vertexPositions[nodeID].xyz; 30 | float3 previousPosition = g_vertexPreviousPositions[nodeID].xyz; 31 | float3 velocity = g_vertexVelocities[nodeID].xyz; 32 | int clothIndex = g_vertexClothIndices[nodeID]; 33 | float velocityCorrectionCoefficient = g_clothVelocityCorrectionCoefficients[clothIndex]; 34 | float dampingFactor = g_clothDampingFactor[clothIndex]; 35 | float velocityCoefficient = (1.f - dampingFactor); 36 | 37 | float3 difference = position - previousPosition; 38 | 39 | velocity += difference*velocityCorrectionCoefficient*isolverdt; 40 | 41 | // Damp the velocity 42 | velocity *= velocityCoefficient; 43 | 44 | g_vertexVelocities[nodeID] = float4(velocity, 0.f); 45 | g_vertexForces[nodeID] = float4(0.f, 0.f, 0.f, 0.f); 46 | } 47 | } 48 | 49 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositions.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdateVelocitiesFromPositionsWithoutVelocitiesCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float isolverdt; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | 12 | StructuredBuffer g_vertexPositions : register( t0 ); 13 | StructuredBuffer g_vertexPreviousPositions : register( t1 ); 14 | StructuredBuffer g_vertexClothIndices : register( t2 ); 15 | StructuredBuffer g_clothDampingFactor : register( t3 ); 16 | 17 | RWStructuredBuffer g_vertexVelocities : register( u0 ); 18 | RWStructuredBuffer g_vertexForces : register( u1 ); 19 | 20 | 21 | [numthreads(128, 1, 1)] 22 | void 23 | updateVelocitiesFromPositionsWithoutVelocitiesKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 24 | { 25 | int nodeID = DTid.x; 26 | if( nodeID < numNodes ) 27 | { 28 | float3 position = g_vertexPositions[nodeID].xyz; 29 | float3 previousPosition = g_vertexPreviousPositions[nodeID].xyz; 30 | float3 velocity = g_vertexVelocities[nodeID].xyz; 31 | int clothIndex = g_vertexClothIndices[nodeID]; 32 | float dampingFactor = g_clothDampingFactor[clothIndex]; 33 | float velocityCoefficient = (1.f - dampingFactor); 34 | 35 | float3 difference = position - previousPosition; 36 | 37 | velocity = difference*velocityCoefficient*isolverdt; 38 | 39 | g_vertexVelocities[nodeID] = float4(velocity, 0.f); 40 | g_vertexForces[nodeID] = float4(0.f, 0.f, 0.f, 0.f); 41 | } 42 | } 43 | 44 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositionsFromVelocities.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdatePositionsFromVelocitiesCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float solverSDT; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | 12 | StructuredBuffer g_vertexVelocities : register( t0 ); 13 | 14 | RWStructuredBuffer g_vertexPreviousPositions : register( u0 ); 15 | RWStructuredBuffer g_vertexCurrentPosition : register( u1 ); 16 | 17 | 18 | [numthreads(128, 1, 1)] 19 | void 20 | UpdatePositionsFromVelocitiesKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 21 | { 22 | int vertexID = DTid.x; 23 | if( vertexID < numNodes ) 24 | { 25 | float3 previousPosition = g_vertexPreviousPositions[vertexID].xyz; 26 | float3 velocity = g_vertexVelocities[vertexID].xyz; 27 | 28 | float3 newPosition = previousPosition + velocity*solverSDT; 29 | 30 | g_vertexCurrentPosition[vertexID] = float4(newPosition, 0.f); 31 | g_vertexPreviousPositions[vertexID] = float4(newPosition, 0.f); 32 | } 33 | } 34 | 35 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/VSolveLinks.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer VSolveLinksCB : register( b0 ) 4 | { 5 | int startLink; 6 | int numLinks; 7 | float kst; 8 | int padding; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | 14 | StructuredBuffer g_linksLengthRatio : register( t1 ); 15 | StructuredBuffer g_linksCurrentLength : register( t2 ); 16 | StructuredBuffer g_vertexInverseMass : register( t3 ); 17 | 18 | RWStructuredBuffer g_vertexVelocity : register( u0 ); 19 | 20 | [numthreads(128, 1, 1)] 21 | void 22 | VSolveLinksKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 23 | { 24 | int linkID = DTid.x + startLink; 25 | if( DTid.x < numLinks ) 26 | { 27 | int2 nodeIndices = g_linksVertexIndices[linkID]; 28 | int node0 = nodeIndices.x; 29 | int node1 = nodeIndices.y; 30 | 31 | float linkLengthRatio = g_linksLengthRatio[linkID]; 32 | float3 linkCurrentLength = g_linksCurrentLength[linkID].xyz; 33 | 34 | float3 vertexVelocity0 = g_vertexVelocity[node0].xyz; 35 | float3 vertexVelocity1 = g_vertexVelocity[node1].xyz; 36 | 37 | float vertexInverseMass0 = g_vertexInverseMass[node0]; 38 | float vertexInverseMass1 = g_vertexInverseMass[node1]; 39 | 40 | float3 nodeDifference = vertexVelocity0 - vertexVelocity1; 41 | float dotResult = dot(linkCurrentLength, nodeDifference); 42 | float j = -dotResult*linkLengthRatio*kst; 43 | 44 | float3 velocityChange0 = linkCurrentLength*(j*vertexInverseMass0); 45 | float3 velocityChange1 = linkCurrentLength*(j*vertexInverseMass1); 46 | 47 | vertexVelocity0 += velocityChange0; 48 | vertexVelocity1 -= velocityChange1; 49 | 50 | g_vertexVelocity[node0] = float4(vertexVelocity0, 0.f); 51 | g_vertexVelocity[node1] = float4(vertexVelocity1, 0.f); 52 | } 53 | } 54 | 55 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ApplyForces.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ApplyForces.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/Integrate.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | // Node indices for each link 4 | 5 | 6 | 7 | __kernel void 8 | IntegrateKernel( 9 | const int numNodes, 10 | const float solverdt, 11 | __global float * g_vertexInverseMasses, 12 | __global float4 * g_vertexPositions, 13 | __global float4 * g_vertexVelocity, 14 | __global float4 * g_vertexPreviousPositions, 15 | __global float4 * g_vertexForceAccumulator GUID_ARG) 16 | { 17 | int nodeID = get_global_id(0); 18 | if( nodeID < numNodes ) 19 | { 20 | float4 position = g_vertexPositions[nodeID]; 21 | float4 velocity = g_vertexVelocity[nodeID]; 22 | float4 force = g_vertexForceAccumulator[nodeID]; 23 | float inverseMass = g_vertexInverseMasses[nodeID]; 24 | 25 | g_vertexPreviousPositions[nodeID] = position; 26 | velocity += force * inverseMass * solverdt; 27 | position += velocity * solverdt; 28 | 29 | g_vertexForceAccumulator[nodeID] = (float4)(0.f, 0.f, 0.f, 0.0f); 30 | g_vertexPositions[nodeID] = position; 31 | g_vertexVelocity[nodeID] = velocity; 32 | } 33 | } 34 | 35 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/OutputToVertexArray.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | OutputToVertexArrayWithNormalsKernel( 5 | const int startNode, const int numNodes, __global float *g_vertexBuffer, 6 | const int positionOffset, const int positionStride, const __global float4* g_vertexPositions, 7 | const int normalOffset, const int normalStride, const __global float4* g_vertexNormals ) 8 | { 9 | int nodeID = get_global_id(0); 10 | if( nodeID < numNodes ) 11 | { 12 | float4 position = g_vertexPositions[nodeID + startNode]; 13 | float4 normal = g_vertexNormals[nodeID + startNode]; 14 | 15 | // Stride should account for the float->float4 conversion 16 | int positionDestination = nodeID * positionStride + positionOffset; 17 | g_vertexBuffer[positionDestination] = position.x; 18 | g_vertexBuffer[positionDestination+1] = position.y; 19 | g_vertexBuffer[positionDestination+2] = position.z; 20 | 21 | int normalDestination = nodeID * normalStride + normalOffset; 22 | g_vertexBuffer[normalDestination] = normal.x; 23 | g_vertexBuffer[normalDestination+1] = normal.y; 24 | g_vertexBuffer[normalDestination+2] = normal.z; 25 | } 26 | } 27 | 28 | __kernel void 29 | OutputToVertexArrayWithoutNormalsKernel( 30 | const int startNode, const int numNodes, __global float *g_vertexBuffer, 31 | const int positionOffset, const int positionStride, const __global float4* g_vertexPositions ) 32 | { 33 | int nodeID = get_global_id(0); 34 | if( nodeID < numNodes ) 35 | { 36 | float4 position = g_vertexPositions[nodeID + startNode]; 37 | 38 | // Stride should account for the float->float4 conversion 39 | int positionDestination = nodeID * positionStride + positionOffset; 40 | g_vertexBuffer[positionDestination] = position.x; 41 | g_vertexBuffer[positionDestination+1] = position.y; 42 | g_vertexBuffer[positionDestination+2] = position.z; 43 | } 44 | } 45 | 46 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/PrepareLinks.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | 4 | 5 | __kernel void 6 | PrepareLinksKernel( 7 | const int numLinks, 8 | __global int2 * g_linksVertexIndices, 9 | __global float * g_linksMassLSC, 10 | __global float4 * g_nodesPreviousPosition, 11 | __global float * g_linksLengthRatio, 12 | __global float4 * g_linksCurrentLength GUID_ARG) 13 | { 14 | int linkID = get_global_id(0); 15 | if( linkID < numLinks ) 16 | { 17 | 18 | int2 nodeIndices = g_linksVertexIndices[linkID]; 19 | int node0 = nodeIndices.x; 20 | int node1 = nodeIndices.y; 21 | 22 | float4 nodePreviousPosition0 = g_nodesPreviousPosition[node0]; 23 | float4 nodePreviousPosition1 = g_nodesPreviousPosition[node1]; 24 | 25 | float massLSC = g_linksMassLSC[linkID]; 26 | 27 | float4 linkCurrentLength = nodePreviousPosition1 - nodePreviousPosition0; 28 | linkCurrentLength.w = 0.f; 29 | 30 | float linkLengthRatio = dot(linkCurrentLength, linkCurrentLength)*massLSC; 31 | linkLengthRatio = 1.0f/linkLengthRatio; 32 | 33 | g_linksCurrentLength[linkID] = linkCurrentLength; 34 | g_linksLengthRatio[linkID] = linkLengthRatio; 35 | } 36 | } 37 | 38 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolvePositions.cl: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | MSTRINGIFY( 5 | 6 | 7 | float mydot3(float4 a, float4 b) 8 | { 9 | return a.x*b.x + a.y*b.y + a.z*b.z; 10 | } 11 | 12 | 13 | __kernel void 14 | SolvePositionsFromLinksKernel( 15 | const int startLink, 16 | const int numLinks, 17 | const float kst, 18 | const float ti, 19 | __global int2 * g_linksVertexIndices, 20 | __global float * g_linksMassLSC, 21 | __global float * g_linksRestLengthSquared, 22 | __global float * g_verticesInverseMass, 23 | __global float4 * g_vertexPositions GUID_ARG) 24 | 25 | { 26 | int linkID = get_global_id(0) + startLink; 27 | if( get_global_id(0) < numLinks ) 28 | { 29 | float massLSC = g_linksMassLSC[linkID]; 30 | float restLengthSquared = g_linksRestLengthSquared[linkID]; 31 | 32 | if( massLSC > 0.0f ) 33 | { 34 | int2 nodeIndices = g_linksVertexIndices[linkID]; 35 | int node0 = nodeIndices.x; 36 | int node1 = nodeIndices.y; 37 | 38 | float4 position0 = g_vertexPositions[node0]; 39 | float4 position1 = g_vertexPositions[node1]; 40 | 41 | float inverseMass0 = g_verticesInverseMass[node0]; 42 | float inverseMass1 = g_verticesInverseMass[node1]; 43 | 44 | float4 del = position1 - position0; 45 | float len = mydot3(del, del); 46 | float k = ((restLengthSquared - len)/(massLSC*(restLengthSquared+len)))*kst; 47 | position0 = position0 - del*(k*inverseMass0); 48 | position1 = position1 + del*(k*inverseMass1); 49 | 50 | g_vertexPositions[node0] = position0; 51 | g_vertexPositions[node1] = position1; 52 | 53 | } 54 | } 55 | } 56 | 57 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateConstants.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | /*#define float3 float4 4 | 5 | float dot3(float3 a, float3 b) 6 | { 7 | return a.x*b.x + a.y*b.y + a.z*b.z; 8 | }*/ 9 | 10 | __kernel void 11 | UpdateConstantsKernel( 12 | const int numLinks, 13 | __global int2 * g_linksVertexIndices, 14 | __global float4 * g_vertexPositions, 15 | __global float * g_vertexInverseMasses, 16 | __global float * g_linksMaterialLSC, 17 | __global float * g_linksMassLSC, 18 | __global float * g_linksRestLengthSquared, 19 | __global float * g_linksRestLengths) 20 | { 21 | int linkID = get_global_id(0); 22 | if( linkID < numLinks ) 23 | { 24 | int2 nodeIndices = g_linksVertexIndices[linkID]; 25 | int node0 = nodeIndices.x; 26 | int node1 = nodeIndices.y; 27 | float linearStiffnessCoefficient = g_linksMaterialLSC[ linkID ]; 28 | 29 | float3 position0 = g_vertexPositions[node0].xyz; 30 | float3 position1 = g_vertexPositions[node1].xyz; 31 | float inverseMass0 = g_vertexInverseMasses[node0]; 32 | float inverseMass1 = g_vertexInverseMasses[node1]; 33 | 34 | float3 difference = position0 - position1; 35 | float length2 = dot(difference, difference); 36 | float length = sqrt(length2); 37 | 38 | g_linksRestLengths[linkID] = length; 39 | g_linksMassLSC[linkID] = (inverseMass0 + inverseMass1)/linearStiffnessCoefficient; 40 | g_linksRestLengthSquared[linkID] = length*length; 41 | } 42 | } 43 | 44 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateFixedVertexPositions.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | UpdateFixedVertexPositions( 5 | const uint numNodes, 6 | __global int * g_anchorIndex, 7 | __global float4 * g_vertexPositions, 8 | __global float4 * g_anchorPositions GUID_ARG) 9 | { 10 | unsigned int nodeID = get_global_id(0); 11 | 12 | if( nodeID < numNodes ) 13 | { 14 | int anchorIndex = g_anchorIndex[nodeID]; 15 | float4 position = g_vertexPositions[nodeID]; 16 | 17 | if ( anchorIndex >= 0 ) 18 | { 19 | float4 anchorPosition = g_anchorPositions[anchorIndex]; 20 | g_vertexPositions[nodeID] = anchorPosition; 21 | } 22 | } 23 | } 24 | 25 | ); 26 | -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateNodes.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | 4 | __kernel void 5 | updateVelocitiesFromPositionsWithVelocitiesKernel( 6 | int numNodes, 7 | float isolverdt, 8 | __global float4 * g_vertexPositions, 9 | __global float4 * g_vertexPreviousPositions, 10 | __global int * g_vertexClothIndices, 11 | __global float *g_clothVelocityCorrectionCoefficients, 12 | __global float * g_clothDampingFactor, 13 | __global float4 * g_vertexVelocities, 14 | __global float4 * g_vertexForces GUID_ARG) 15 | { 16 | int nodeID = get_global_id(0); 17 | if( nodeID < numNodes ) 18 | { 19 | float4 position = g_vertexPositions[nodeID]; 20 | float4 previousPosition = g_vertexPreviousPositions[nodeID]; 21 | float4 velocity = g_vertexVelocities[nodeID]; 22 | int clothIndex = g_vertexClothIndices[nodeID]; 23 | float velocityCorrectionCoefficient = g_clothVelocityCorrectionCoefficients[clothIndex]; 24 | float dampingFactor = g_clothDampingFactor[clothIndex]; 25 | float velocityCoefficient = (1.f - dampingFactor); 26 | 27 | float4 difference = position - previousPosition; 28 | 29 | velocity += difference*velocityCorrectionCoefficient*isolverdt; 30 | 31 | // Damp the velocity 32 | velocity *= velocityCoefficient; 33 | 34 | g_vertexVelocities[nodeID] = velocity; 35 | g_vertexForces[nodeID] = (float4)(0.f, 0.f, 0.f, 0.f); 36 | } 37 | } 38 | 39 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositions.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | updateVelocitiesFromPositionsWithoutVelocitiesKernel( 5 | const int numNodes, 6 | const float isolverdt, 7 | __global float4 * g_vertexPositions, 8 | __global float4 * g_vertexPreviousPositions, 9 | __global int * g_vertexClothIndices, 10 | __global float * g_clothDampingFactor, 11 | __global float4 * g_vertexVelocities, 12 | __global float4 * g_vertexForces GUID_ARG) 13 | 14 | { 15 | int nodeID = get_global_id(0); 16 | if( nodeID < numNodes ) 17 | { 18 | float4 position = g_vertexPositions[nodeID]; 19 | float4 previousPosition = g_vertexPreviousPositions[nodeID]; 20 | float4 velocity = g_vertexVelocities[nodeID]; 21 | int clothIndex = g_vertexClothIndices[nodeID]; 22 | float dampingFactor = g_clothDampingFactor[clothIndex]; 23 | float velocityCoefficient = (1.f - dampingFactor); 24 | 25 | float4 difference = position - previousPosition; 26 | 27 | velocity = difference*velocityCoefficient*isolverdt; 28 | 29 | g_vertexVelocities[nodeID] = velocity; 30 | g_vertexForces[nodeID] = (float4)(0.f, 0.f, 0.f, 0.f); 31 | } 32 | } 33 | 34 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositionsFromVelocities.cl: -------------------------------------------------------------------------------- 1 | 2 | MSTRINGIFY( 3 | 4 | 5 | 6 | 7 | __kernel void 8 | UpdatePositionsFromVelocitiesKernel( 9 | const int numNodes, 10 | const float solverSDT, 11 | __global float4 * g_vertexVelocities, 12 | __global float4 * g_vertexPreviousPositions, 13 | __global float4 * g_vertexCurrentPosition GUID_ARG) 14 | { 15 | int vertexID = get_global_id(0); 16 | if( vertexID < numNodes ) 17 | { 18 | float4 previousPosition = g_vertexPreviousPositions[vertexID]; 19 | float4 velocity = g_vertexVelocities[vertexID]; 20 | 21 | float4 newPosition = previousPosition + velocity*solverSDT; 22 | 23 | g_vertexCurrentPosition[vertexID] = newPosition; 24 | g_vertexPreviousPositions[vertexID] = newPosition; 25 | } 26 | } 27 | 28 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/VSolveLinks.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | VSolveLinksKernel( 5 | int startLink, 6 | int numLinks, 7 | float kst, 8 | __global int2 * g_linksVertexIndices, 9 | __global float * g_linksLengthRatio, 10 | __global float4 * g_linksCurrentLength, 11 | __global float * g_vertexInverseMass, 12 | __global float4 * g_vertexVelocity GUID_ARG) 13 | { 14 | int linkID = get_global_id(0) + startLink; 15 | if( get_global_id(0) < numLinks ) 16 | { 17 | int2 nodeIndices = g_linksVertexIndices[linkID]; 18 | int node0 = nodeIndices.x; 19 | int node1 = nodeIndices.y; 20 | 21 | float linkLengthRatio = g_linksLengthRatio[linkID]; 22 | float3 linkCurrentLength = g_linksCurrentLength[linkID].xyz; 23 | 24 | float3 vertexVelocity0 = g_vertexVelocity[node0].xyz; 25 | float3 vertexVelocity1 = g_vertexVelocity[node1].xyz; 26 | 27 | float vertexInverseMass0 = g_vertexInverseMass[node0]; 28 | float vertexInverseMass1 = g_vertexInverseMass[node1]; 29 | 30 | float3 nodeDifference = vertexVelocity0 - vertexVelocity1; 31 | float dotResult = dot(linkCurrentLength, nodeDifference); 32 | float j = -dotResult*linkLengthRatio*kst; 33 | 34 | float3 velocityChange0 = linkCurrentLength*(j*vertexInverseMass0); 35 | float3 velocityChange1 = linkCurrentLength*(j*vertexInverseMass1); 36 | 37 | vertexVelocity0 += velocityChange0; 38 | vertexVelocity1 -= velocityChange1; 39 | 40 | g_vertexVelocity[node0] = (float4)(vertexVelocity0, 0.f); 41 | g_vertexVelocity[node1] = (float4)(vertexVelocity1, 0.f); 42 | } 43 | } 44 | 45 | ); -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverVertexData_OpenCL.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "BulletMultiThreaded/GpuSoftBodySolvers/Shared/btSoftBodySolverData.h" 17 | #include "btSoftBodySolverBuffer_OpenCL.h" 18 | 19 | #ifndef BT_SOFT_BODY_SOLVER_VERTEX_DATA_OPENCL_H 20 | #define BT_SOFT_BODY_SOLVER_VERTEX_DATA_OPENCL_H 21 | 22 | 23 | class btSoftBodyVertexDataOpenCL : public btSoftBodyVertexData 24 | { 25 | protected: 26 | bool m_onGPU; 27 | cl_command_queue m_queue; 28 | 29 | public: 30 | btOpenCLBuffer m_clClothIdentifier; 31 | btOpenCLBuffer m_clVertexPosition; 32 | btOpenCLBuffer m_clVertexPreviousPosition; 33 | btOpenCLBuffer m_clVertexVelocity; 34 | btOpenCLBuffer m_clVertexForceAccumulator; 35 | btOpenCLBuffer m_clVertexNormal; 36 | btOpenCLBuffer m_clVertexInverseMass; 37 | btOpenCLBuffer m_clVertexArea; 38 | btOpenCLBuffer m_clVertexTriangleCount; 39 | public: 40 | btSoftBodyVertexDataOpenCL( cl_command_queue queue, cl_context ctx); 41 | 42 | virtual ~btSoftBodyVertexDataOpenCL(); 43 | 44 | virtual bool onAccelerator(); 45 | 46 | virtual bool moveToAccelerator(); 47 | 48 | virtual bool moveFromAccelerator(bool bCopy = false, bool bCopyMinimum = true); 49 | }; 50 | 51 | 52 | #endif // #ifndef BT_SOFT_BODY_SOLVER_VERTEX_DATA_OPENCL_H 53 | -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/PpuAddressSpace.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2010 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #ifndef BT_PPU_ADDRESS_SPACE_H 18 | #define BT_PPU_ADDRESS_SPACE_H 19 | 20 | 21 | #ifdef _WIN32 22 | //stop those casting warnings until we have a better solution for ppu_address_t / void* / uint64 conversions 23 | #pragma warning (disable: 4311) 24 | #pragma warning (disable: 4312) 25 | #endif //_WIN32 26 | 27 | 28 | #if defined(_WIN64) 29 | typedef unsigned __int64 ppu_address_t; 30 | #elif defined(__LP64__) || defined(__x86_64__) 31 | typedef uint64_t ppu_address_t; 32 | #else 33 | typedef uint32_t ppu_address_t; 34 | #endif //defined(_WIN64) 35 | 36 | #endif //BT_PPU_ADDRESS_SPACE_H 37 | 38 | -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpuUtilsSharedCode.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, http://bulletphysics.org 3 | Copyright (C) 2006, 2009 Sony Computer Entertainment Inc. 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | //---------------------------------------------------------------------------------------- 17 | 18 | // Shared code for GPU-based utilities 19 | 20 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 21 | // Keep this file free from Bullet headers 22 | // will be compiled by both CPU and CUDA compilers 23 | // file with definitions of BT_GPU_xxx should be included first 24 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 25 | 26 | //---------------------------------------------------------------------------------------- 27 | 28 | #include "btGpuUtilsSharedDefs.h" 29 | 30 | //---------------------------------------------------------------------------------------- 31 | 32 | extern "C" 33 | { 34 | 35 | //---------------------------------------------------------------------------------------- 36 | 37 | //Round a / b to nearest higher integer value 38 | int BT_GPU_PREF(iDivUp)(int a, int b) 39 | { 40 | return (a % b != 0) ? (a / b + 1) : (a / b); 41 | } // iDivUp() 42 | 43 | //---------------------------------------------------------------------------------------- 44 | 45 | // compute grid and thread block size for a given number of elements 46 | void BT_GPU_PREF(computeGridSize)(int n, int blockSize, int &numBlocks, int &numThreads) 47 | { 48 | numThreads = BT_GPU_min(blockSize, n); 49 | numBlocks = BT_GPU_PREF(iDivUp)(n, numThreads); 50 | } // computeGridSize() 51 | 52 | //---------------------------------------------------------------------------------------- 53 | 54 | } // extern "C" 55 | 56 | -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpuUtilsSharedDefs.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, http://bulletphysics.org 3 | Copyright (C) 2006, 2007 Sony Computer Entertainment Inc. 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | // Shared definitions for GPU-based utilities 17 | 18 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 19 | // Keep this file free from Bullet headers 20 | // it is included into both CUDA and CPU code 21 | // file with definitions of BT_GPU_xxx should be included first 22 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 23 | 24 | 25 | #ifndef BTGPUUTILSDHAREDDEFS_H 26 | #define BTGPUUTILSDHAREDDEFS_H 27 | 28 | 29 | extern "C" 30 | { 31 | 32 | 33 | //Round a / b to nearest higher integer value 34 | int BT_GPU_PREF(iDivUp)(int a, int b); 35 | 36 | // compute grid and thread block size for a given number of elements 37 | void BT_GPU_PREF(computeGridSize)(int n, int blockSize, int &numBlocks, int &numThreads); 38 | 39 | void BT_GPU_PREF(allocateArray)(void** devPtr, unsigned int size); 40 | void BT_GPU_PREF(freeArray)(void* devPtr); 41 | void BT_GPU_PREF(copyArrayFromDevice)(void* host, const void* device, unsigned int size); 42 | void BT_GPU_PREF(copyArrayToDevice)(void* device, const void* host, unsigned int size); 43 | void BT_GPU_PREF(registerGLBufferObject(unsigned int vbo)); 44 | void* BT_GPU_PREF(mapGLBufferObject(unsigned int vbo)); 45 | void BT_GPU_PREF(unmapGLBufferObject(unsigned int vbo)); 46 | 47 | 48 | } // extern "C" 49 | 50 | 51 | #endif // BTGPUUTILSDHAREDDEFS_H 52 | 53 | -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btParallelCollisionDispatcher.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_PARALLELCOLLISIONDISPATCHER_H 2 | #define BT_PARALLELCOLLISIONDISPATCHER_H 3 | 4 | #include "BulletCollision/BroadphaseCollision/btDispatcher.h" 5 | #include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h" 6 | #include "LinearMath/btPoolAllocator.h" 7 | 8 | #include "btThreadPool.h" 9 | #include "btThreading.h" 10 | 11 | class btParallelCollisionDispatcher : public btCollisionDispatcher { 12 | public: 13 | btParallelCollisionDispatcher(btCollisionConfiguration *pConfiguration, btThreadPool *pThreadPool); 14 | ~btParallelCollisionDispatcher(); 15 | 16 | virtual btPersistentManifold *getNewManifold(const btCollisionObject *ob1, const btCollisionObject *ob2); 17 | virtual void releaseManifold(btPersistentManifold *pManifold); 18 | 19 | virtual void *allocateCollisionAlgorithm(int size); 20 | virtual void freeCollisionAlgorithm(void *ptr); 21 | 22 | virtual void *allocateTask(int size); 23 | virtual void freeTask(void *ptr); 24 | 25 | virtual void dispatchAllCollisionPairs(btOverlappingPairCache *pairCache, const btDispatcherInfo &dispatchInfo, btDispatcher *dispatcher); 26 | 27 | btThreadPool *getThreadPool(); 28 | 29 | private: 30 | btPoolAllocator * m_pTaskPool; 31 | 32 | btICriticalSection *m_pPoolCritSect; // Manifold pool crit section 33 | btICriticalSection *m_pAlgoPoolSect; // Algorithm pool crit section 34 | btThreadPool * m_pThreadPool; 35 | }; 36 | 37 | #endif // BT_PARALLELCOLLISIONDISPATCHER_H -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btThreadPool.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_THREADPOOL_H 2 | #define BT_THREADPOOL_H 3 | 4 | #include "btThreading.h" 5 | #include "LinearMath/btAlignedObjectArray.h" 6 | 7 | class btIThreadTask { 8 | public: 9 | virtual void run() = 0; 10 | virtual void destroy() {}; // Destroys this task. Called on main thread after run (duh) 11 | }; 12 | 13 | class btThreadPool; 14 | 15 | struct btThreadPoolInfo { 16 | btIThread *pThread; 17 | btIEvent *pIdleEvent; 18 | btIEvent *pStartEvent; 19 | btThreadPool *pThreadPool; 20 | int threadId; 21 | 22 | // Task information 23 | btIThreadTask **pTaskArr; 24 | int numTasks; 25 | }; 26 | 27 | class btThreadPool { 28 | public: 29 | btThreadPool(); 30 | ~btThreadPool(); 31 | 32 | void startThreads(int numThreads); 33 | void stopThreads(); 34 | void resizeThreads(int numThreads); 35 | 36 | int getNumThreads(); 37 | 38 | void addTask(btIThreadTask *pTask); 39 | void clearTasks(); // Clear task queue 40 | 41 | int getNumTasks() { 42 | return m_taskArray.size(); 43 | } 44 | 45 | // WARNING: Do not delete the elements here! This will be done in clearTasks() 46 | btIThreadTask *getTask(int i) { 47 | return m_taskArray[i]; 48 | } 49 | 50 | void runTasks(); // Runs the threads until task pool is empty 51 | void waitIdle(); // Waits until thread pool is idle (no more tasks) 52 | 53 | // Internal functions (do not call these) 54 | 55 | void threadFunction(btThreadPoolInfo *pInfo); 56 | 57 | private: 58 | void beginThread(btThreadPoolInfo *pInfo); 59 | void endThread(btThreadPoolInfo *pInfo); 60 | 61 | btAlignedObjectArray m_pThreadInfo; 62 | //btThreadPoolInfo ** m_pThreadInfo; 63 | int m_numThreads; 64 | bool m_bThreadsStarted; 65 | bool m_bThreadsShouldExit; 66 | bool m_bRunningTasks; 67 | 68 | btAlignedObjectArray m_taskArray; // FIXME: We don't need an aligned array. 69 | }; 70 | 71 | #endif // BT_THREADPOOL_H -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btThreading.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_THREAD_H 2 | #define BT_THREAD_H 3 | 4 | typedef void (*btThreadFunc)(void *arg); 5 | 6 | class btIThread { 7 | public: 8 | virtual ~btIThread() {}; 9 | 10 | virtual void run(void *pArgument) = 0; 11 | virtual void waitForExit() = 0; 12 | 13 | virtual void setThreadFunc(btThreadFunc fn) = 0; 14 | virtual void setThreadArgument(void *pArg) = 0; 15 | virtual void setThreadName(const char *name) {}; // Debugging thread name (may not be available on some implementations) 16 | }; 17 | 18 | btIThread *btCreateThread(); 19 | void btDeleteThread(btIThread *thread); 20 | 21 | class btICriticalSection { 22 | public: 23 | virtual ~btICriticalSection() {}; 24 | 25 | virtual void lock() = 0; 26 | virtual void unlock() = 0; 27 | }; 28 | 29 | btICriticalSection *btCreateCriticalSection(); 30 | void btDeleteCriticalSection(btICriticalSection *pCritSection); 31 | 32 | class btIEvent { 33 | public: 34 | virtual ~btIEvent() {}; 35 | 36 | virtual void trigger() = 0; // Trigger this semaphore. Threads waiting on this will be released. 37 | virtual void reset() = 0; // Resets back to the untriggered state. 38 | virtual void wait() = 0; // Waits for semaphore to be triggered. Once triggered, this is set back to untriggered and function returns. 39 | }; 40 | 41 | // TODO in posix: Actually use manual reset (always acts like manual reset = true right now) 42 | // Beware: Linux with manual reset = false is UNTESTED! 43 | btIEvent *btCreateEvent(bool bManualReset = false); 44 | void btDeleteEvent(btIEvent *pSemaphore); 45 | 46 | class btIConditionalVariable { 47 | public: 48 | virtual ~btIConditionalVariable() {}; 49 | 50 | virtual void wakeAll() = 0; // Wake all threads waiting on this variable 51 | virtual void wake() = 0; // Wake one of the threads waiting on this variable 52 | 53 | // Unlocks a critical section and waits on this variable. When we're woken up, 54 | // locks the critical section again. 55 | virtual void wait(btICriticalSection *pCritSection) = 0; 56 | }; 57 | 58 | btIConditionalVariable *btCreateConditionalVariable(); 59 | void btDeleteConditionalVariable(btIConditionalVariable *pVariable); 60 | 61 | #endif // BT_THREAD_H -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletMultiThreaded" 2 | 3 | kind "StaticLib" 4 | 5 | language "C++" 6 | 7 | links { "BulletCollision" } 8 | 9 | includedirs { 10 | "..", 11 | } 12 | 13 | files { 14 | "**.cpp", 15 | "**.h" 16 | } 17 | 18 | excludes { 19 | "GpuSoftBodySolvers/**" 20 | } -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btDefaultSoftBodySolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SOFT_BODY_DEFAULT_SOLVER_H 17 | #define BT_SOFT_BODY_DEFAULT_SOLVER_H 18 | 19 | 20 | #include "BulletSoftBody/btSoftBodySolvers.h" 21 | #include "btSoftBodySolverVertexBuffer.h" 22 | struct btCollisionObjectWrapper; 23 | 24 | class btDefaultSoftBodySolver : public btSoftBodySolver 25 | { 26 | protected: 27 | /** Variable to define whether we need to update solver constants on the next iteration */ 28 | bool m_updateSolverConstants; 29 | 30 | btAlignedObjectArray< btSoftBody * > m_softBodySet; 31 | 32 | 33 | public: 34 | btDefaultSoftBodySolver(); 35 | 36 | virtual ~btDefaultSoftBodySolver(); 37 | 38 | virtual SolverTypes getSolverType() const 39 | { 40 | return DEFAULT_SOLVER; 41 | } 42 | 43 | virtual bool checkInitialized(); 44 | 45 | virtual void updateSoftBodies( ); 46 | 47 | virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies, bool forceUpdate=false ); 48 | 49 | virtual void copyBackToSoftBodies(bool bMove = true); 50 | 51 | virtual void solveConstraints( float solverdt ); 52 | 53 | virtual void predictMotion( float solverdt ); 54 | 55 | virtual void copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer ); 56 | 57 | virtual void processCollision( btSoftBody *, const btCollisionObjectWrapper* ); 58 | 59 | virtual void processCollision( btSoftBody*, btSoftBody* ); 60 | 61 | }; 62 | 63 | #endif // #ifndef BT_ACCELERATED_SOFT_BODY_CPU_SOLVER_H 64 | -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/bullet/src/BulletSoftBody/btSoftBody.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION 17 | #define BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION 18 | 19 | #include "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h" 20 | 21 | class btVoronoiSimplexSolver; 22 | class btGjkEpaPenetrationDepthSolver; 23 | 24 | 25 | ///btSoftBodyRigidBodyCollisionConfiguration add softbody interaction on top of btDefaultCollisionConfiguration 26 | class btSoftBodyRigidBodyCollisionConfiguration : public btDefaultCollisionConfiguration 27 | { 28 | 29 | //default CreationFunctions, filling the m_doubleDispatch table 30 | btCollisionAlgorithmCreateFunc* m_softSoftCreateFunc; 31 | btCollisionAlgorithmCreateFunc* m_softRigidConvexCreateFunc; 32 | btCollisionAlgorithmCreateFunc* m_swappedSoftRigidConvexCreateFunc; 33 | btCollisionAlgorithmCreateFunc* m_softRigidConcaveCreateFunc; 34 | btCollisionAlgorithmCreateFunc* m_swappedSoftRigidConcaveCreateFunc; 35 | 36 | public: 37 | 38 | btSoftBodyRigidBodyCollisionConfiguration(const btDefaultCollisionConstructionInfo& constructionInfo = btDefaultCollisionConstructionInfo()); 39 | 40 | virtual ~btSoftBodyRigidBodyCollisionConfiguration(); 41 | 42 | ///creation of soft-soft and soft-rigid, and otherwise fallback to base class implementation 43 | virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0, int proxyType1); 44 | 45 | }; 46 | 47 | #endif //BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION 48 | 49 | -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletSoftBody" 2 | 3 | kind "StaticLib" 4 | 5 | language "C++" 6 | 7 | links { "BulletCollision" } 8 | 9 | includedirs { 10 | "..", 11 | } 12 | 13 | files { 14 | "**.cpp", 15 | "**.h" 16 | } -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDebug.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2013 Dr.Chat / Erwin Coumans http://bullet.googlecode.com 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | #include 16 | #include 17 | 18 | #include "btDebug.h" 19 | 20 | #if defined(__CELLOS_LV2__) && defined(__SPU__) 21 | #include 22 | #define printf spu_printf 23 | #endif 24 | 25 | void btDefDbgMsg(const char *str) { 26 | printf("%s", str); 27 | } 28 | 29 | btDbgMsgFn g_pDbgMsg = btDefDbgMsg; 30 | 31 | void btDefDbgWarning(const char *str) { 32 | printf("%s", str); 33 | } 34 | 35 | btDbgMsgFn g_pDbgWarn = btDefDbgWarning; 36 | 37 | void btSetDbgMsgFn(btDbgMsgFn fn) { 38 | fn ? g_pDbgMsg = fn : g_pDbgMsg = btDefDbgMsg; 39 | } 40 | 41 | void btSetDbgWarnFn(btDbgMsgFn fn) { 42 | fn ? g_pDbgWarn = fn : g_pDbgWarn = btDefDbgWarning; 43 | } 44 | 45 | void btDbgMsgInternal(const char *fmt, ...) { 46 | char buff[2048]; 47 | 48 | va_list va; 49 | va_start(va, fmt); 50 | vsnprintf(buff, 2048, fmt, va); 51 | va_end(va); 52 | 53 | g_pDbgMsg(buff); 54 | } 55 | 56 | void btDbgWarningInternal(const char *fmt, ...) { 57 | char buff[2048]; 58 | 59 | va_list va; 60 | va_start(va, fmt); 61 | vsnprintf(buff, 2048, fmt, va); 62 | va_end(va); 63 | 64 | g_pDbgWarn(buff); 65 | } -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDebug.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2013 Dr.Chat / Erwin Coumans http://bullet.googlecode.com 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | #ifndef BT_DEBUG_H 16 | #define BT_DEBUG_H 17 | 18 | // TODO: Do we want versions of these with source information? 19 | // Can't really do this due to limitations of compiler macros (vararg support for macros changes per compiler) 20 | 21 | void btDbgMsgInternal(const char *fmt, ...); 22 | void btDbgWarningInternal(const char *fmt, ...); 23 | 24 | #define btDbgMsg btDbgMsgInternal 25 | #define btDbgWarning btDbgWarningInternal 26 | 27 | typedef void (*btDbgMsgFn)(const char *str); 28 | 29 | // Sets a user function for bullet debug messages 30 | // Call with NULL to reset back to default bullet ones. 31 | 32 | void btSetDbgMsgFn(btDbgMsgFn fn); 33 | void btSetDbgWarnFn(btDbgMsgFn fn); 34 | 35 | #endif // BT_DEBUG_H -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDefaultMotionState.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_DEFAULT_MOTION_STATE_H 2 | #define BT_DEFAULT_MOTION_STATE_H 3 | 4 | #include "btMotionState.h" 5 | 6 | ///The btDefaultMotionState provides a common implementation to synchronize world transforms with offsets. 7 | ATTRIBUTE_ALIGNED16(struct) btDefaultMotionState : public btMotionState 8 | { 9 | btTransform m_graphicsWorldTrans; 10 | btTransform m_centerOfMassOffset; 11 | btTransform m_startWorldTrans; 12 | void* m_userPointer; 13 | 14 | BT_DECLARE_ALIGNED_ALLOCATOR(); 15 | 16 | btDefaultMotionState(const btTransform& startTrans = btTransform::getIdentity(), const btTransform& centerOfMassOffset = btTransform::getIdentity()) 17 | : m_graphicsWorldTrans(startTrans), 18 | m_centerOfMassOffset(centerOfMassOffset), 19 | m_startWorldTrans(startTrans), 20 | m_userPointer(0) 21 | 22 | { 23 | } 24 | 25 | ///synchronizes world transform from user to physics 26 | virtual void getWorldTransform(btTransform& centerOfMassWorldTrans ) const 27 | { 28 | centerOfMassWorldTrans = m_centerOfMassOffset.inverse() * m_graphicsWorldTrans ; 29 | } 30 | 31 | ///synchronizes world transform from physics to user 32 | ///Bullet only calls the update of worldtransform for active objects 33 | virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans) 34 | { 35 | m_graphicsWorldTrans = centerOfMassWorldTrans * m_centerOfMassOffset ; 36 | } 37 | 38 | 39 | 40 | }; 41 | 42 | #endif //BT_DEFAULT_MOTION_STATE_H 43 | -------------------------------------------------------------------------------- /bullet/src/LinearMath/btGeometryUtil.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | 16 | #ifndef BT_GEOMETRY_UTIL_H 17 | #define BT_GEOMETRY_UTIL_H 18 | 19 | #include "btVector3.h" 20 | #include "btAlignedObjectArray.h" 21 | 22 | ///The btGeometryUtil helper class provides a few methods to convert between plane equations and vertices. 23 | class btGeometryUtil 24 | { 25 | public: 26 | 27 | 28 | static void getPlaneEquationsFromVertices(btAlignedObjectArray& vertices, btAlignedObjectArray& planeEquationsOut ); 29 | 30 | static void getVerticesFromPlaneEquations(const btAlignedObjectArray& planeEquations, btAlignedObjectArray& verticesOut ); 31 | 32 | static bool isInside(const btAlignedObjectArray& vertices, const btVector3& planeNormal, btScalar margin); 33 | 34 | static bool isPointInsidePlanes(const btAlignedObjectArray& planeEquations, const btVector3& point, btScalar margin); 35 | 36 | static bool areVerticesBehindPlane(const btVector3& planeNormal, const btAlignedObjectArray& vertices, btScalar margin); 37 | 38 | }; 39 | 40 | 41 | #endif //BT_GEOMETRY_UTIL_H 42 | 43 | -------------------------------------------------------------------------------- /bullet/src/LinearMath/btMinMax.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | 16 | 17 | #ifndef BT_GEN_MINMAX_H 18 | #define BT_GEN_MINMAX_H 19 | 20 | #include "btScalar.h" 21 | 22 | template 23 | SIMD_FORCE_INLINE const T& btMin(const T& a, const T& b) 24 | { 25 | return a < b ? a : b ; 26 | } 27 | 28 | template 29 | SIMD_FORCE_INLINE const T& btMax(const T& a, const T& b) 30 | { 31 | return a > b ? a : b; 32 | } 33 | 34 | template 35 | SIMD_FORCE_INLINE const T& btClamped(const T& a, const T& lb, const T& ub) 36 | { 37 | return a < lb ? lb : (ub < a ? ub : a); 38 | } 39 | 40 | template 41 | SIMD_FORCE_INLINE void btSetMin(T& a, const T& b) 42 | { 43 | if (b < a) 44 | { 45 | a = b; 46 | } 47 | } 48 | 49 | template 50 | SIMD_FORCE_INLINE void btSetMax(T& a, const T& b) 51 | { 52 | if (a < b) 53 | { 54 | a = b; 55 | } 56 | } 57 | 58 | template 59 | SIMD_FORCE_INLINE void btClamp(T& a, const T& lb, const T& ub) 60 | { 61 | if (a < lb) 62 | { 63 | a = lb; 64 | } 65 | else if (ub < a) 66 | { 67 | a = ub; 68 | } 69 | } 70 | 71 | #endif //BT_GEN_MINMAX_H 72 | -------------------------------------------------------------------------------- /bullet/src/LinearMath/btMotionState.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages 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 freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_MOTIONSTATE_H 17 | #define BT_MOTIONSTATE_H 18 | 19 | #include "btTransform.h" 20 | 21 | ///The btMotionState interface class allows the dynamics world to synchronize and interpolate the updated world transforms with graphics 22 | ///For optimizations, potentially only moving objects get synchronized (using setWorldPosition/setWorldOrientation) 23 | class btMotionState 24 | { 25 | public: 26 | 27 | virtual ~btMotionState() 28 | { 29 | 30 | } 31 | 32 | virtual void getWorldTransform(btTransform& worldTrans ) const =0; 33 | 34 | //Bullet only calls the update of worldtransform for active objects 35 | virtual void setWorldTransform(const btTransform& worldTrans)=0; 36 | 37 | 38 | }; 39 | 40 | #endif //BT_MOTIONSTATE_H 41 | -------------------------------------------------------------------------------- /bullet/src/LinearMath/btRandom.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | 16 | 17 | #ifndef BT_GEN_RANDOM_H 18 | #define BT_GEN_RANDOM_H 19 | 20 | #include "btScalar.h" 21 | 22 | #ifdef MT19937 23 | 24 | #include 25 | #include 26 | 27 | #define GEN_RAND_MAX UINT_MAX 28 | 29 | SIMD_FORCE_INLINE void GEN_srand(unsigned int seed) { init_genrand(seed); } 30 | SIMD_FORCE_INLINE unsigned int GEN_rand() { return genrand_int32(); } 31 | 32 | #else 33 | 34 | #include 35 | 36 | #define GEN_RAND_MAX RAND_MAX 37 | 38 | SIMD_FORCE_INLINE void GEN_srand(unsigned int seed) { srand(seed); } 39 | SIMD_FORCE_INLINE unsigned int GEN_rand() { return rand(); } 40 | 41 | #endif 42 | 43 | #endif //BT_GEN_RANDOM_H 44 | 45 | -------------------------------------------------------------------------------- /bullet/src/LinearMath/premake4.lua: -------------------------------------------------------------------------------- 1 | project "LinearMath" 2 | 3 | kind "StaticLib" 4 | 5 | language "C++" 6 | 7 | includedirs { 8 | "..", 9 | } 10 | 11 | files { 12 | "**.cpp", 13 | "**.h" 14 | } -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCLTask/MiniCLTask.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, Copyright (c) 2007 Erwin Coumans 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | 14 | */ 15 | 16 | 17 | #include "MiniCLTask.h" 18 | #include "BulletMultiThreaded/PlatformDefinitions.h" 19 | #include "BulletMultiThreaded/SpuFakeDma.h" 20 | #include "LinearMath/btMinMax.h" 21 | #include "MiniCLTask.h" 22 | #include "MiniCL/MiniCLTaskScheduler.h" 23 | 24 | 25 | #ifdef __SPU__ 26 | #include 27 | #else 28 | #include 29 | #define spu_printf printf 30 | #endif 31 | 32 | int gMiniCLNumOutstandingTasks = 0; 33 | 34 | struct MiniCLTask_LocalStoreMemory 35 | { 36 | 37 | }; 38 | 39 | 40 | //-- MAIN METHOD 41 | void processMiniCLTask(void* userPtr, void* lsMemory) 42 | { 43 | // BT_PROFILE("processSampleTask"); 44 | 45 | MiniCLTask_LocalStoreMemory* localMemory = (MiniCLTask_LocalStoreMemory*)lsMemory; 46 | 47 | MiniCLTaskDesc* taskDescPtr = (MiniCLTaskDesc*)userPtr; 48 | MiniCLTaskDesc& taskDesc = *taskDescPtr; 49 | 50 | for (unsigned int i=taskDesc.m_firstWorkUnit;im_launcher(&taskDesc, i); 53 | } 54 | 55 | // printf("Compute Unit[%d] executed kernel %d work items [%d..%d)\n",taskDesc.m_taskId,taskDesc.m_kernelProgramId,taskDesc.m_firstWorkUnit,taskDesc.m_lastWorkUnit); 56 | 57 | } 58 | 59 | 60 | #if defined(__CELLOS_LV2__) || defined (LIBSPE2) 61 | 62 | ATTRIBUTE_ALIGNED16(MiniCLTask_LocalStoreMemory gLocalStoreMemory); 63 | 64 | void* createMiniCLLocalStoreMemory() 65 | { 66 | return &gLocalStoreMemory; 67 | } 68 | #else 69 | void* createMiniCLLocalStoreMemory() 70 | { 71 | return new MiniCLTask_LocalStoreMemory; 72 | }; 73 | 74 | #endif 75 | -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCLTask/MiniCLTask.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, Copyright (c) 2007 Erwin Coumans 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | 14 | */ 15 | 16 | #ifndef MINICL__TASK_H 17 | #define MINICL__TASK_H 18 | 19 | #include "BulletMultiThreaded/PlatformDefinitions.h" 20 | #include "LinearMath/btScalar.h" 21 | 22 | #include "LinearMath/btAlignedAllocator.h" 23 | 24 | 25 | #define MINICL_MAX_ARGLENGTH (sizeof(void*)) 26 | #define MINI_CL_MAX_ARG 16 27 | #define MINI_CL_MAX_KERNEL_NAME 256 28 | 29 | struct MiniCLKernel; 30 | 31 | ATTRIBUTE_ALIGNED16(struct) MiniCLTaskDesc 32 | { 33 | BT_DECLARE_ALIGNED_ALLOCATOR(); 34 | 35 | MiniCLTaskDesc() 36 | { 37 | for (int i=0;i 9 | #else //(USE_SYSTEM_VECTORMATH) 10 | #if defined (BT_USE_SSE) 11 | #include "sse/vectormath_aos.h" 12 | #else //all other platforms 13 | #if defined (BT_USE_NEON) 14 | #include "neon/vectormath_aos.h" 15 | #else 16 | #include "scalar/vectormath_aos.h" 17 | #endif 18 | #endif //(BT_USE_SSE) && defined (_WIN32) 19 | #endif //(USE_SYSTEM_VECTORMATH) 20 | 21 | 22 | 23 | typedef Vectormath::Aos::Vector3 vmVector3; 24 | typedef Vectormath::Aos::Quat vmQuat; 25 | typedef Vectormath::Aos::Matrix3 vmMatrix3; 26 | typedef Vectormath::Aos::Transform3 vmTransform3; 27 | typedef Vectormath::Aos::Point3 vmPoint3; 28 | 29 | #endif //__VM_INCLUDE_H 30 | 31 | 32 | -------------------------------------------------------------------------------- /include/vphysics/softbodyV32.h: -------------------------------------------------------------------------------- 1 | #ifndef SOFTBODYV32_H 2 | #define SOFTBODYV32_H 3 | #ifdef _MSC_VER 4 | #pragma once 5 | #endif 6 | 7 | struct softbodynode_t { 8 | Vector pos, vel; 9 | float invMass; 10 | }; 11 | 12 | struct softbodyface_t { 13 | int nodeIndexes[3]; // Node indexes that can be passed into the node functions 14 | softbodynode_t nodes[3]; 15 | Vector normal; 16 | }; 17 | 18 | struct softbodylink_t { 19 | int nodeIndexes[2]; // Node indexes that can be passed into the node functions 20 | softbodynode_t nodes[2]; 21 | }; 22 | 23 | struct softbodyparams_t { 24 | float totalMass; 25 | }; 26 | 27 | class IPhysicsSoftBody { 28 | public: 29 | virtual ~IPhysicsSoftBody() {} 30 | 31 | virtual void SetTotalMass(float fMass, bool bFromFaces = false) = 0; 32 | virtual void Anchor(int node, IPhysicsObject *pObj) = 0; 33 | 34 | virtual int GetNodeCount() const = 0; 35 | virtual int GetFaceCount() const = 0; 36 | virtual int GetLinkCount() const = 0; 37 | 38 | virtual softbodynode_t GetNode(int i) const = 0; 39 | virtual softbodyface_t GetFace(int i) const = 0; 40 | virtual softbodylink_t GetLink(int i) const = 0; 41 | 42 | // Get soft body AABB (cannot be implemented in collision interface because soft bodies change shape) 43 | virtual void GetAABB(Vector *mins, Vector *maxs) const = 0; 44 | virtual void RayTest(Ray_t &ray, trace_t *pTrace) const = 0; 45 | 46 | virtual void Transform(const matrix3x4_t &mat) = 0; 47 | virtual void Transform(const Vector *vec, const QAngle *ang) = 0; 48 | virtual void Scale(const Vector &scale) = 0; // Scales a softbody. Do this before it's moved from the origin, or bad things will happen! 49 | 50 | virtual IPhysicsEnvironment32 *GetPhysicsEnvironment() const = 0; 51 | }; 52 | 53 | #endif // SOFTBODYV32_H -------------------------------------------------------------------------------- /include/vphysics/vehiclesV32.h: -------------------------------------------------------------------------------- 1 | #ifndef VEHICLESV32_H 2 | #define VEHICLESV32_h 3 | #ifdef _MSC_VER 4 | #pragma once 5 | #endif 6 | 7 | #include "vphysics/vehicles.h" 8 | 9 | // THIS INTERFACE IS NOT FINALIZED! FUNCTIONS MAY CHANGE! 10 | 11 | class IPhysicsVehicleController32 : public IPhysicsVehicleController { 12 | public: 13 | // force in kg*in/s 14 | virtual void SetWheelForce(int wheelIndex, float force) = 0; 15 | virtual void SetWheelBrake(int wheelIndex, float brakeVal) = 0; 16 | // steerVal is in degrees! 17 | virtual void SetWheelSteering(int wheelIndex, float steerVal) = 0; 18 | }; 19 | 20 | #endif // VEHICLESV32_H -------------------------------------------------------------------------------- /proj/gmake.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | # REMOVE THIS AFTER YOU CONFIGURE THE FILE 4 | echo "Configure the script first!" 5 | exit 1 6 | 7 | ./premake4 --srcdsbindir="x/srcds/orangebox/bin" gmake 8 | -------------------------------------------------------------------------------- /proj/options.lua: -------------------------------------------------------------------------------- 1 | --[[----------- 2 | -- Options 3 | -------------]] 4 | 5 | -- SRCDS dir 6 | newoption { 7 | trigger = "srcdsbindir", 8 | value = "path", 9 | description = "Source Dedicated Server engine bin directory (required on linux)" 10 | } 11 | 12 | SRCDS_BIN_DIR = _OPTIONS["srcdsbindir"] 13 | 14 | -- Generate post build commands for VS projects 15 | newoption { 16 | trigger = "genpostbuildcommand", 17 | value = "true", 18 | description = "Allow post build command generation (VS only)", 19 | allowed = { 20 | { "true", "true" }, 21 | { "false", "false" }, 22 | } 23 | } 24 | 25 | GEN_POSTBUILDCOMMANDS = false 26 | if _OPTIONS["genpostbuildcommand"] == "true" then 27 | GEN_POSTBUILDCOMMANDS = true 28 | end -------------------------------------------------------------------------------- /proj/premake4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/proj/premake4 -------------------------------------------------------------------------------- /proj/premake4.exe: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/proj/premake4.exe -------------------------------------------------------------------------------- /proj/premake4.lua: -------------------------------------------------------------------------------- 1 | solution "vphysics" 2 | 3 | if _ACTION == "vs2010" or _ACTION == "vs2008" then 4 | -- Enable multi-processor compilation 5 | buildoptions { "/MP" } 6 | end 7 | 8 | act = "" 9 | 10 | if _ACTION then 11 | act = _ACTION 12 | end 13 | 14 | -- Options 15 | dofile("options.lua") 16 | 17 | --[[--------------------------------- 18 | -- Main configuration properities 19 | -----------------------------------]] 20 | configurations { "Release", "Debug" } 21 | 22 | configuration "Release" 23 | defines { "RELEASE=1", "NDEBUG=1", "_RELEASE=1" } 24 | if os.is( "linux" ) then 25 | defines { "_LINUX=1", "__linux__=1", "LINUX=1" } 26 | end 27 | 28 | -- TODO: When supported, add NoIncrementalLink flag 29 | flags { "OptimizeSpeed", "EnableSSE", "StaticRuntime", "NoMinimalRebuild", "FloatFast" } 30 | targetdir( "../build/bin/" .. os.get() .. "/release" ) 31 | 32 | configuration "Debug" 33 | defines { "_DEBUG=1" } 34 | if os.is("linux") then 35 | defines { "_LINUX=1", "__linux__=1", "LINUX=1" } 36 | end 37 | 38 | flags { "Symbols", "StaticRuntime", "NoMinimalRebuild", "FloatFast" } 39 | targetdir("../build/bin/" .. os.get() .. "/debug") 40 | 41 | configuration {} 42 | 43 | -- Only support 32 bit builds 44 | configuration { "linux", "gmake" } 45 | buildoptions { "-fPIC", "-m32" } 46 | linkoptions { "-m32" } 47 | 48 | configuration {} 49 | 50 | location( "./" .. act ) 51 | 52 | --[[-------------- 53 | -- Projects 54 | ----------------]] 55 | -- Hardcoded path now because this won't ever change 56 | SDK_DIR = "../thirdparty/sourcesdk/mp/src" 57 | GM_MODULEBASE = "../thirdparty/gmmodulebase/include" 58 | 59 | include "../GMVPhy" 60 | 61 | if os.is("linux") and not SRCDS_BIN_DIR then 62 | print "Fatal: SRCDS bin dir was not defined (which is required for linux builds)\nCannot generate vphysics project files" 63 | else 64 | include "../src" 65 | end 66 | 67 | include "../bullet/src" -------------------------------------------------------------------------------- /proj/readme.txt: -------------------------------------------------------------------------------- 1 | Download premake from http://industriousone.com/premake/download 2 | 3 | Before you generate your projects, edit vs2010.bat and set the SDK path (sdkdir) and gmod module base (gmmodulebase) 4 | Command should look like premake4 --sdkdir="path" --gmmodulebase="path" vs2010 -------------------------------------------------------------------------------- /proj/vs2010.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | 3 | premake4 vs2010 4 | -------------------------------------------------------------------------------- /src/DebugDrawer.h: -------------------------------------------------------------------------------- 1 | #ifndef GL_DEBUG_DRAWER_H 2 | #define GL_DEBUG_DRAWER_H 3 | 4 | #include 5 | 6 | //#define DEBUGDRAW_RENDER_SDL 7 | 8 | class CPhysicsEnvironment; 9 | struct SDL_Surface; 10 | 11 | class CProfileIterator; 12 | 13 | class CDebugDrawer : public btIDebugDraw { 14 | public: 15 | CDebugDrawer(btCollisionWorld *world); 16 | virtual ~CDebugDrawer(); 17 | 18 | virtual void drawLine(const btVector3 &from, const btVector3 &to, const btVector3 &fromColor, const btVector3 &toColor); 19 | virtual void drawLine(const btVector3 &from, const btVector3 &to, const btVector3 &color); 20 | 21 | #ifdef DEBUGDRAW_RENDER_SDL 22 | virtual void drawSphere(const btVector3 &p, btScalar radius, const btVector3 &color); 23 | #endif 24 | virtual void drawBox(const btVector3 &boxMin, const btVector3 &boxMax, const btVector3 &color, btScalar alpha); 25 | virtual void drawTriangle(const btVector3 &a, const btVector3 &b, const btVector3 &c, const btVector3 &color, btScalar alpha); 26 | virtual void drawContactPoint(const btVector3 &PointOnB, const btVector3 &normalOnB, btScalar distance, int lifeTime, const btVector3 &color); 27 | virtual void reportErrorWarning(const char *warningString); 28 | virtual void draw3dText(const btVector3 &location, const char *textString); 29 | virtual void setDebugMode(int debugMode); 30 | virtual int getDebugMode() const { return m_debugMode; } 31 | 32 | void SetDebugOverlay(IVPhysicsDebugOverlay *pOverlay); 33 | IVPhysicsDebugOverlay * GetDebugOverlay(); 34 | void DrawWorld(); 35 | 36 | private: 37 | int m_debugMode; 38 | btCollisionWorld * m_world; 39 | // CProfileIterator * m_pProfIterator; 40 | 41 | #ifdef DEBUGDRAW_RENDER_SDL 42 | SDL_Surface * m_pDisplay; 43 | #endif 44 | 45 | IVPhysicsDebugOverlay * m_overlay; 46 | }; 47 | 48 | #endif//GL_DEBUG_DRAWER_H 49 | -------------------------------------------------------------------------------- /src/IController.h: -------------------------------------------------------------------------------- 1 | #ifndef ICONTROLLER_H 2 | #define ICONTROLLER_H 3 | 4 | class CPhysicsObject; 5 | 6 | class IController { 7 | public: 8 | // Bullet tick, called post-simulation 9 | virtual void Tick(float deltaTime) = 0; 10 | }; 11 | 12 | #endif // ICONTROLLER_H 13 | -------------------------------------------------------------------------------- /src/Physics.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_H 2 | #define PHYSICS_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | #include 8 | 9 | class IPhysicsEnvironment; 10 | class IPhysicsCollisionSet; 11 | 12 | class CPhysics : public CTier1AppSystem { 13 | typedef CTier1AppSystem BaseClass; 14 | public: 15 | ~CPhysics(); 16 | 17 | void * QueryInterface(const char *pInterfaceName); 18 | InitReturnVal_t Init(); 19 | void Shutdown(); 20 | 21 | IPhysicsEnvironment * CreateEnvironment(); 22 | void DestroyEnvironment(IPhysicsEnvironment *pEnv); 23 | IPhysicsEnvironment * GetActiveEnvironmentByIndex(int index); 24 | int GetActiveEnvironmentCount(); 25 | 26 | IPhysicsObjectPairHash * CreateObjectPairHash(); 27 | void DestroyObjectPairHash(IPhysicsObjectPairHash *pHash); 28 | 29 | IPhysicsCollisionSet * FindOrCreateCollisionSet(unsigned int id, int maxElementCount); 30 | IPhysicsCollisionSet * FindCollisionSet(unsigned int id); 31 | void DestroyAllCollisionSets(); 32 | private: 33 | CUtlVector m_envList; 34 | CUtlVector m_collisionSets; 35 | CUtlHashtable m_colSetTable; 36 | }; 37 | 38 | extern CPhysics g_Physics; 39 | 40 | #endif -------------------------------------------------------------------------------- /src/Physics_CollisionSet.cpp: -------------------------------------------------------------------------------- 1 | #include "StdAfx.h" 2 | 3 | #include "Physics_CollisionSet.h" 4 | 5 | // memdbgon must be the last include file in a .cpp file!!! 6 | #include "tier0/memdbgon.h" 7 | 8 | /****************************** 9 | * CLASS CPhysicsCollisionSet 10 | ******************************/ 11 | 12 | // Is this class sort of like CPhysicsObjectPairHash? 13 | // ShouldCollide is called by game code from the collision event handler in CPhysicsEnvironment 14 | 15 | // TODO: Needs a better design, right now it's hardcoded to support a max of 32 entries (sizeof int). 16 | 17 | // All objects default with no collisions between other objects. 18 | // The game has to explicitly enable collisions between two objects (IVP behavior) 19 | 20 | CPhysicsCollisionSet::CPhysicsCollisionSet(int iMaxEntries) { 21 | Assert(iMaxEntries <= 32); 22 | 23 | m_iMaxEntries = iMaxEntries; 24 | 25 | m_collArray = new int[iMaxEntries]; 26 | for (int i = 0; i < iMaxEntries; i++) { 27 | m_collArray[i] = 0; 28 | } 29 | } 30 | 31 | CPhysicsCollisionSet::~CPhysicsCollisionSet() { 32 | delete [] m_collArray; 33 | } 34 | 35 | void CPhysicsCollisionSet::EnableCollisions(int index0, int index1) { 36 | Assert((index0 < m_iMaxEntries && index0 >= 0) && (index1 < m_iMaxEntries && index1 >= 0)); 37 | if ((index0 >= m_iMaxEntries || index0 < 0) || (index1 >= m_iMaxEntries || index1 < 0)) { 38 | return; 39 | } 40 | 41 | // Totally stolen from valve! 42 | m_collArray[index0] |= 1 << index1; 43 | m_collArray[index1] |= 1 << index0; 44 | } 45 | 46 | void CPhysicsCollisionSet::DisableCollisions(int index0, int index1) { 47 | Assert((index0 < m_iMaxEntries && index0 >= 0) && (index1 < m_iMaxEntries && index1 >= 0)); 48 | if ((index0 >= m_iMaxEntries || index0 < 0) || (index1 >= m_iMaxEntries || index1 < 0)) { 49 | return; 50 | } 51 | 52 | m_collArray[index0] &= ~(1 << index1); 53 | m_collArray[index1] &= ~(1 << index0); 54 | } 55 | 56 | bool CPhysicsCollisionSet::ShouldCollide(int index0, int index1) { 57 | Assert((index0 < m_iMaxEntries && index0 >= 0) && (index1 < m_iMaxEntries && index1 >= 0)); 58 | if ((index0 >= m_iMaxEntries || index0 < 0) || (index1 >= m_iMaxEntries || index1 < 0)) { 59 | return true; 60 | } 61 | 62 | return (((1 << index1) & m_collArray[index0]) != 0) || 63 | (((1 << index0) & m_collArray[index1]) != 0); 64 | } 65 | 66 | /********************* 67 | * CREATION FUNCTIONS 68 | *********************/ 69 | 70 | CPhysicsCollisionSet *CreateCollisionSet(int maxElements) { 71 | return new CPhysicsCollisionSet(maxElements); 72 | } -------------------------------------------------------------------------------- /src/Physics_CollisionSet.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_COLLISIONSET_H 2 | #define PHYSICS_COLLISIONSET_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | class CPhysicsCollisionSet : public IPhysicsCollisionSet { 8 | public: 9 | CPhysicsCollisionSet(int iMaxEntries); 10 | ~CPhysicsCollisionSet(); 11 | 12 | void EnableCollisions(int index0, int index1); 13 | void DisableCollisions(int index0, int index1); 14 | 15 | bool ShouldCollide(int index0, int index1); 16 | 17 | private: 18 | int m_iMaxEntries; 19 | int * m_collArray; 20 | }; 21 | 22 | CPhysicsCollisionSet *CreateCollisionSet(int maxElements); 23 | 24 | #endif // PHYSICS_COLLISIONSET_H -------------------------------------------------------------------------------- /src/Physics_DragController.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_DRAGCONTROLLER_H 2 | #define PHYSICS_DRAGCONTROLLER_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | class CPhysicsObject; 8 | 9 | class CPhysicsDragController { 10 | public: 11 | CPhysicsDragController(); 12 | void SetAirDensity(float density); 13 | float GetAirDensity(); 14 | 15 | void AddPhysicsObject(CPhysicsObject *pObject); 16 | void RemovePhysicsObject(CPhysicsObject *pObject); 17 | void Tick(btScalar dt); 18 | bool IsControlling(const CPhysicsObject *pObject) const; 19 | private: 20 | float m_airDensity; 21 | 22 | CUtlVectorm_ents; 23 | }; 24 | 25 | #endif // PHYSICS_DRAGCONTROLLER_H -------------------------------------------------------------------------------- /src/Physics_FluidController.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_FLUIDCONTROLLER_H 2 | #define PHYSICS_FLUIDCONTROLLER_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | #include "IController.h" 8 | 9 | class CPhysicsEnvironment; 10 | class CPhysicsFluidCallback; 11 | class CPhysicsObject; 12 | 13 | class CPhysicsFluidController : public IPhysicsFluidController, public IController 14 | { 15 | public: 16 | CPhysicsFluidController(CPhysicsEnvironment *pEnv, CPhysicsObject *pFluidObject, fluidparams_t *pParams); 17 | ~CPhysicsFluidController(); 18 | 19 | void SetGameData(void *pGameData); 20 | void * GetGameData() const; 21 | 22 | void GetSurfacePlane(Vector *pNormal, float *pDist) const; 23 | float GetDensity() const; 24 | void WakeAllSleepingObjects(); 25 | int GetContents() const; 26 | 27 | // UNEXPOSED FUNCTIONS 28 | public: 29 | void Tick(float deltaTime); 30 | void ObjectRemoved(CPhysicsObject *pObject); 31 | void ObjectAdded(CPhysicsObject *pObject); 32 | 33 | void TransferToEnvironment(CPhysicsEnvironment *pDest); 34 | private: 35 | void * m_pGameData; 36 | int m_iContents; 37 | float m_fDensity; 38 | 39 | // surface plane is a Vector surface normal and float distance 40 | Vector4D m_vSurfacePlane; 41 | btVector3 m_currentVelocity; // Velocity of water current 42 | CPhysicsEnvironment * m_pEnv; 43 | btGhostObject * m_pGhostObject; 44 | CPhysicsFluidCallback * m_pCallback; 45 | }; 46 | 47 | CPhysicsFluidController *CreateFluidController(CPhysicsEnvironment *pEnv, CPhysicsObject *pFluidObject, fluidparams_t *pParams); 48 | 49 | #endif // PHYSICS_FLUIDCONTROLLER_H 50 | -------------------------------------------------------------------------------- /src/Physics_FrictionSnapshot.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_FRICTIONSNAPSHOT_H 2 | #define PHYSICS_FRICTIONSNAPSHOT_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | #include 8 | 9 | class CPhysicsObject; 10 | class btPersistentManifold; 11 | 12 | class CPhysicsFrictionSnapshot : public IPhysicsFrictionSnapshot 13 | { 14 | public: 15 | CPhysicsFrictionSnapshot(CPhysicsObject *pObject); 16 | ~CPhysicsFrictionSnapshot(); 17 | 18 | bool IsValid(); 19 | 20 | IPhysicsObject * GetObject(int index); 21 | int GetMaterial(int index); 22 | 23 | void GetContactPoint(Vector &out); 24 | 25 | void GetSurfaceNormal(Vector &out); 26 | float GetNormalForce(); 27 | float GetEnergyAbsorbed(); 28 | 29 | void RecomputeFriction(); 30 | void ClearFrictionForce(); 31 | 32 | void MarkContactForDelete(); 33 | void DeleteAllMarkedContacts(bool wakeObjects); 34 | 35 | void NextFrictionData(); 36 | float GetFrictionCoefficient(); 37 | private: 38 | CUtlVector m_manifolds; 39 | CPhysicsObject * m_pObject; 40 | int m_iCurManifold; 41 | int m_iCurContactPoint; 42 | }; 43 | 44 | CPhysicsFrictionSnapshot *CreateFrictionSnapshot(CPhysicsObject *pObject); 45 | 46 | #endif // PHYSICS_FRICTIONSNAPSHOT_H 47 | -------------------------------------------------------------------------------- /src/Physics_KeyParser.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_KEYPARSER_H 2 | #define PHYSICS_KEYPARSER_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | #include 8 | #include 9 | 10 | class KeyValues; 11 | 12 | class CPhysicsKeyParser : public IVPhysicsKeyParser 13 | { 14 | public: 15 | CPhysicsKeyParser(const char *pKeyValues); 16 | ~CPhysicsKeyParser(); 17 | 18 | void NextBlock(); 19 | 20 | const char * GetCurrentBlockName(); 21 | bool Finished(); 22 | void ParseSolid(solid_t *pSolid, IVPhysicsKeyHandler *unknownKeyHandler); 23 | void ParseFluid(fluid_t *pFluid, IVPhysicsKeyHandler *unknownKeyHandler); 24 | void ParseRagdollConstraint(constraint_ragdollparams_t *pConstraint, IVPhysicsKeyHandler *unknownKeyHandler); 25 | void ParseSurfaceTable(int *table, IVPhysicsKeyHandler *unknownKeyHandler); 26 | void ParseCustom(void *pCustom, IVPhysicsKeyHandler *unknownKeyHandler); 27 | void ParseVehicle(vehicleparams_t *pVehicle, IVPhysicsKeyHandler *unknownKeyHandler); 28 | void SkipBlock() { NextBlock(); }; 29 | 30 | // Unexposed functions 31 | public: 32 | void ParseVehicleAxle(vehicle_axleparams_t &axle, KeyValues *kv); 33 | void ParseVehicleWheel(vehicle_wheelparams_t &wheel, KeyValues *kv); 34 | void ParseVehicleSuspension(vehicle_suspensionparams_t &suspension, KeyValues *kv); 35 | void ParseVehicleBody(vehicle_bodyparams_t &body, KeyValues *kv); 36 | void ParseVehicleEngine(vehicle_engineparams_t &engine, KeyValues *kv); 37 | void ParseVehicleEngineBoost(vehicle_engineparams_t &engine, KeyValues *kv); 38 | void ParseVehicleSteering(vehicle_steeringparams_t &steering, KeyValues *kv); 39 | 40 | private: 41 | KeyValues * m_pKeyValues; 42 | KeyValues * m_pCurrentBlock; 43 | }; 44 | 45 | #endif // PHYSICS_KEYPARSER_H 46 | -------------------------------------------------------------------------------- /src/Physics_MotionController.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_MOTIONCONTROLLER_H 2 | #define PHYSICS_MOTIONCONTROLLER_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | #include "IController.h" 8 | 9 | #include "Physics_Object.h" 10 | 11 | class CPhysicsEnvironment; 12 | 13 | class CPhysicsMotionController : public IController, public IPhysicsMotionController, public IObjectEventListener 14 | { 15 | public: 16 | CPhysicsMotionController(IMotionEvent *pHandler, CPhysicsEnvironment *pEnv); 17 | ~CPhysicsMotionController(); 18 | 19 | void SetEventHandler(IMotionEvent *handler); 20 | void AttachObject(IPhysicsObject *pObject, bool checkIfAlreadyAttached); 21 | void DetachObject(IPhysicsObject *pObject); 22 | 23 | int CountObjects(); 24 | void GetObjects(IPhysicsObject **pObjectList); 25 | void ClearObjects(); 26 | void WakeObjects(); 27 | 28 | void SetPriority(priority_t priority); 29 | public: 30 | void Tick(float deltaTime); 31 | void ObjectDestroyed(CPhysicsObject *pObject); 32 | 33 | private: 34 | IMotionEvent * m_handler; 35 | CUtlVector m_objectList; 36 | CPhysicsEnvironment * m_pEnv; 37 | 38 | int m_priority; 39 | }; 40 | 41 | IPhysicsMotionController *CreateMotionController(CPhysicsEnvironment *pEnv, IMotionEvent *pHandler); 42 | 43 | #endif // PHYSICS_MOTIONCONTROLLER_H 44 | -------------------------------------------------------------------------------- /src/Physics_ObjectPairHash.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_OBJECTPAIRHASH_H 2 | #define PHYSICS_OBJECTPAIRHASH_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | #include 8 | 9 | struct pair_hash_list { 10 | void *object0; 11 | void *object1; 12 | 13 | pair_hash_list *next; 14 | }; 15 | 16 | class CPhysicsObjectPairHash : public IPhysicsObjectPairHash { 17 | public: 18 | CPhysicsObjectPairHash(); 19 | 20 | void AddObjectPair(void *pObject0, void *pObject1); 21 | void RemoveObjectPair(void *pObject0, void *pObject1); 22 | bool IsObjectPairInHash(void *pObject0, void *pObject1); 23 | void RemoveAllPairsForObject(void *pObject0); 24 | bool IsObjectInHash(void *pObject0); 25 | 26 | int GetPairCountForObject(void *pObject0); 27 | int GetPairListForObject(void *pObject0, int nMaxCount, void **ppObjectList); 28 | 29 | int GetEntry(void *pObject0, void *pObject1); 30 | 31 | private: 32 | pair_hash_list *m_pHashList[256]; 33 | }; 34 | 35 | #endif // PHYSICS_OBJECTPAIRHASH_H 36 | -------------------------------------------------------------------------------- /src/Physics_SurfaceProps.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_SURFACEPROPS_H 2 | #define PHYSICS_SURFACEPROPS_H 3 | #if defined(_MSC_VER) || (defined(__GNUC__) && __GNUC__ > 3) 4 | #pragma once 5 | #endif 6 | 7 | enum { 8 | MATERIAL_INDEX_SHADOW = 0xF000, 9 | }; 10 | 11 | class CSurface { 12 | public: 13 | CUtlSymbol m_name; 14 | surfacedata_t data; 15 | }; 16 | 17 | class CPhysicsSurfaceProps : public IPhysicsSurfaceProps { 18 | public: 19 | CPhysicsSurfaceProps(); 20 | ~CPhysicsSurfaceProps(); 21 | 22 | int ParseSurfaceData(const char *pFilename, const char *pTextfile); 23 | int SurfacePropCount() const; 24 | 25 | int GetSurfaceIndex(const char *pSurfacePropName) const; 26 | void GetPhysicsProperties(int surfaceDataIndex, float *density, float *thickness, float *friction, float *elasticity) const; 27 | 28 | surfacedata_t * GetSurfaceData(int surfaceDataIndex); 29 | const char * GetString(unsigned short stringTableIndex) const; 30 | 31 | const char * GetPropName(int surfaceDataIndex) const; 32 | 33 | void SetWorldMaterialIndexTable(int *pMapArray, int mapSize); 34 | 35 | void GetPhysicsParameters(int surfaceDataIndex, surfacephysicsparams_t *pParamsOut) const; 36 | 37 | private: 38 | int GetReservedSurfaceIndex(const char *pSurfacePropName) const; 39 | 40 | CSurface * GetInternalSurface(int materialIndex); 41 | const CSurface * GetInternalSurface(int materialIndex) const; 42 | 43 | void CopyPhysicsProperties(CSurface *pOut, int baseIndex); 44 | bool AddFileToDatabase(const char *pFilename); 45 | int FindOrAddSound(CUtlSymbol sym); 46 | 47 | private: 48 | CUtlSymbolTable * m_strings; 49 | CUtlVector m_soundList; 50 | CUtlVector m_props; 51 | CUtlVector m_fileList; 52 | }; 53 | 54 | extern CPhysicsSurfaceProps g_SurfaceDatabase; 55 | 56 | #endif // PHYSICS_SURFACEPROPS_H 57 | -------------------------------------------------------------------------------- /src/Physics_VehicleAirboat.cpp: -------------------------------------------------------------------------------- 1 | #include "StdAfx.h" 2 | 3 | #include "Physics_VehicleAirboat.h" 4 | 5 | CAirboatVehicle::CAirboatVehicle(CPhysicsObject *pBody, IPhysicsGameTrace *pGameTrace) { 6 | 7 | } 8 | 9 | CAirboatVehicle::~CAirboatVehicle() { 10 | 11 | } 12 | 13 | void CAirboatVehicle::updateAction(btCollisionWorld *pWorld, btScalar dt) { 14 | 15 | } 16 | 17 | void CAirboatVehicle::debugDraw(btIDebugDraw *pDebugDrawer) { 18 | 19 | } 20 | -------------------------------------------------------------------------------- /src/Physics_VehicleAirboat.h: -------------------------------------------------------------------------------- 1 | #ifndef PHYSICS_VEHICLEAIRBOAT_H 2 | #define PHYSICS_VEHICLEAIRBOAT_H 3 | 4 | class CPhysicsObject; 5 | class IPhysicsGameTrace; 6 | 7 | class CAirboatVehicle : public btActionInterface { 8 | public: 9 | CAirboatVehicle(CPhysicsObject *pBody, IPhysicsGameTrace *pGameTrace); 10 | ~CAirboatVehicle(); 11 | 12 | virtual void updateAction(btCollisionWorld *pWorld, btScalar dt); 13 | virtual void debugDraw(btIDebugDraw *pDebugDrawer); 14 | 15 | private: 16 | CPhysicsObject *m_pBody; 17 | IPhysicsGameTrace *m_pGameTrace; 18 | }; 19 | 20 | #endif // PHYSICS_VEHICLEAIRBOAT_H -------------------------------------------------------------------------------- /src/Physics_VehicleControllerCustom.cpp: -------------------------------------------------------------------------------- 1 | #include "StdAfx.h" 2 | 3 | #include "Physics_Environment.h" 4 | #include "Physics_Object.h" 5 | #include "Physics_VehicleControllerCustom.h" 6 | 7 | // memdbgon must be the last include file in a .cpp file!!! 8 | #include "tier0/memdbgon.h" 9 | 10 | class CWheelVehicle : public btActionInterface { 11 | public: 12 | CWheelVehicle(btRigidBody *chassis); 13 | 14 | void updateAction(btCollisionWorld *collisionWorld, btScalar dt); 15 | void debugDraw(btIDebugDraw *pDebugDraw); 16 | 17 | private: 18 | btRigidBody * m_pChassis; 19 | }; 20 | 21 | CWheelVehicle::CWheelVehicle(btRigidBody *chassis) { 22 | m_pChassis = chassis; 23 | } 24 | 25 | void CWheelVehicle::updateAction(btCollisionWorld *collisionWorld, btScalar dt) { 26 | 27 | } 28 | 29 | void CWheelVehicle::debugDraw(btIDebugDraw *pDebugDraw) { 30 | 31 | } 32 | 33 | /***************************************** 34 | * CLASS CPhysicsVehicleControllerCustom 35 | *****************************************/ 36 | 37 | CPhysicsVehicleControllerCustom::CPhysicsVehicleControllerCustom(CPhysicsEnvironment *pEnv, CPhysicsObject *pBody, IPhysicsGameTrace *pGameTrace) { 38 | m_pEnv = pEnv; 39 | m_pBody = pBody; 40 | m_pGameTrace = pGameTrace; 41 | } 42 | 43 | CPhysicsVehicleControllerCustom::~CPhysicsVehicleControllerCustom() { 44 | 45 | } 46 | 47 | void CPhysicsVehicleControllerCustom::SetWheelForce(int wheelIndex, float force) { 48 | NOT_IMPLEMENTED 49 | } 50 | 51 | void CPhysicsVehicleControllerCustom::SetWheelBrake(int wheelIndex, float brakeVal) { 52 | NOT_IMPLEMENTED 53 | } 54 | 55 | void CPhysicsVehicleControllerCustom::SetWheelSteering(int wheelIndex, float steerVal) { 56 | NOT_IMPLEMENTED 57 | } 58 | 59 | void CPhysicsVehicleControllerCustom::Update(float dt) { 60 | NOT_IMPLEMENTED 61 | } 62 | 63 | void CPhysicsVehicleControllerCustom::CreateWheel(const vehicle_customwheelparams_t ¶ms) { 64 | NOT_IMPLEMENTED 65 | } 66 | -------------------------------------------------------------------------------- /src/StdAfx.cpp: -------------------------------------------------------------------------------- 1 | #include "StdAfx.h" 2 | -------------------------------------------------------------------------------- /src/StdAfx.h: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | #include 8 | #include // THIS FILE HAS NO INCLUDE GUARDS! 9 | 10 | // NEW INTERFACE HEADERS 11 | #include "vphysics_interfaceV32.h" 12 | 13 | #include 14 | 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | 21 | #if defined(_WIN32) 22 | #define DEBUG_DRAW 1 23 | #endif 24 | 25 | // Probably shouldn't be using defines for these. 26 | #define SLEEP_LINEAR_THRESHOLD 0.15 // m/s 27 | #define SLEEP_ANGULAR_THRESHOLD 0.1 // rad/s 28 | 29 | #define NOT_IMPLEMENTED DevWarning("VPhysics UNIMPLEMENTED: %s (%s:%u)\n", __FUNCTION__, __FILE__, __LINE__); 30 | #define NOT_IMPLEMENTED_CRITICAL Error("VPhysics UNIMPLEMENTED: %s (%s:%u)\n", __FUNCTION__, __FILE__, __LINE__); 31 | 32 | // NOTE: Not available on non-MSVC builds due to use of __asm. 33 | //#define NOT_IMPLEMENTED_BREAK {DevWarning("VPhysics UNIMPLEMENTED: %s (%s:%u)\n", __FUNCTION__, __FILE__, __LINE__); __asm int 3;} 34 | -------------------------------------------------------------------------------- /src/miscmath.cpp: -------------------------------------------------------------------------------- 1 | #include "StdAfx.h" 2 | 3 | #include "miscmath.h" 4 | 5 | // memdbgon must be the last include file in a .cpp file!!! 6 | #include "tier0/memdbgon.h" 7 | 8 | float AngDragIntegral(float invInertia, float l, float w, float h) { 9 | float w2 = w*w; 10 | float l2 = l*l; 11 | float h2 = h*h; 12 | 13 | return invInertia * ((1.f/3.f)*w2*l*l2 + 0.5 * w2*w2*l + l*w2*h2); 14 | } 15 | 16 | void BtMatrix_vimult(const btMatrix3x3 &matrix, const btVector3 &in, btVector3 &out) { 17 | btScalar a = (matrix.getRow(0).getX()) * in.getX() + (matrix.getRow(1).getX()) * in.getY() + (matrix.getRow(2).getX()) * in.getZ(); 18 | btScalar b = (matrix.getRow(0).getY()) * in.getX() + (matrix.getRow(1).getY()) * in.getY() + (matrix.getRow(2).getY()) * in.getZ(); 19 | btScalar c = (matrix.getRow(0).getZ()) * in.getX() + (matrix.getRow(1).getZ()) * in.getY() + (matrix.getRow(2).getZ()) * in.getZ(); 20 | 21 | out.setX(a); 22 | out.setY(b); 23 | out.setZ(c); 24 | } 25 | 26 | -------------------------------------------------------------------------------- /src/miscmath.h: -------------------------------------------------------------------------------- 1 | #ifndef MISCMATH_H 2 | #define MISCMATH_H 3 | 4 | #include 5 | #include 6 | 7 | #define SAFE_DIVIDE(a, b) ((b) != 0 ? (a)/(b) : 0) 8 | 9 | void BtMatrix_vimult(const btMatrix3x3 &matrix, const btVector3 &in, btVector3 &out); 10 | float AngDragIntegral(float invInertia, float l, float w, float h); 11 | 12 | #endif -------------------------------------------------------------------------------- /src/resource.h: -------------------------------------------------------------------------------- 1 | //{{NO_DEPENDENCIES}} 2 | // Microsoft Visual C++ generated include file. 3 | // Used by vphysics.rc 4 | 5 | // Next default values for new objects 6 | // 7 | #ifdef APSTUDIO_INVOKED 8 | #ifndef APSTUDIO_READONLY_SYMBOLS 9 | #define _APS_NEXT_RESOURCE_VALUE 101 10 | #define _APS_NEXT_COMMAND_VALUE 40001 11 | #define _APS_NEXT_CONTROL_VALUE 1001 12 | #define _APS_NEXT_SYMED_VALUE 101 13 | #endif 14 | #endif 15 | -------------------------------------------------------------------------------- /src/vphysics.rc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/48c575ff3ee2a72639000788def7612d88dcbfb3/src/vphysics.rc --------------------------------------------------------------------------------