├── .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 ├── 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: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/.gitignore -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/.gitmodules -------------------------------------------------------------------------------- /GMVPhy/GMVPhy.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/GMVPhy.vcxproj -------------------------------------------------------------------------------- /GMVPhy/GMVPhy.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/GMVPhy.vcxproj.filters -------------------------------------------------------------------------------- /GMVPhy/MiscFuncs.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/MiscFuncs.cpp -------------------------------------------------------------------------------- /GMVPhy/MiscFuncs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/MiscFuncs.h -------------------------------------------------------------------------------- /GMVPhy/PhysCollision.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysCollision.cpp -------------------------------------------------------------------------------- /GMVPhy/PhysCollision.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysCollision.h -------------------------------------------------------------------------------- /GMVPhy/PhysConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysConstraint.cpp -------------------------------------------------------------------------------- /GMVPhy/PhysConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysConstraint.h -------------------------------------------------------------------------------- /GMVPhy/PhysEnv.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysEnv.cpp -------------------------------------------------------------------------------- /GMVPhy/PhysEnv.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysEnv.h -------------------------------------------------------------------------------- /GMVPhy/PhysObj.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysObj.cpp -------------------------------------------------------------------------------- /GMVPhy/PhysObj.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysObj.h -------------------------------------------------------------------------------- /GMVPhy/PhysSoftBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysSoftBody.cpp -------------------------------------------------------------------------------- /GMVPhy/PhysSoftBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysSoftBody.h -------------------------------------------------------------------------------- /GMVPhy/PhysVehicle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysVehicle.cpp -------------------------------------------------------------------------------- /GMVPhy/PhysVehicle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/PhysVehicle.h -------------------------------------------------------------------------------- /GMVPhy/main.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/main.cpp -------------------------------------------------------------------------------- /GMVPhy/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/GMVPhy/premake4.lua -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/LICENSE -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/README.md -------------------------------------------------------------------------------- /bullet/license.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/license.txt -------------------------------------------------------------------------------- /bullet/make/Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/make/Makefile -------------------------------------------------------------------------------- /bullet/msvc/BulletCollision/BulletCollision.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletCollision/BulletCollision.vcxproj -------------------------------------------------------------------------------- /bullet/msvc/BulletCollision/BulletCollision.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletCollision/BulletCollision.vcxproj.filters -------------------------------------------------------------------------------- /bullet/msvc/BulletDynamics/BulletDynamics.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletDynamics/BulletDynamics.vcxproj -------------------------------------------------------------------------------- /bullet/msvc/BulletDynamics/BulletDynamics.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletDynamics/BulletDynamics.vcxproj.filters -------------------------------------------------------------------------------- /bullet/msvc/BulletMultiThreaded/BulletMultiThreaded.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletMultiThreaded/BulletMultiThreaded.vcxproj -------------------------------------------------------------------------------- /bullet/msvc/BulletMultiThreaded/BulletMultiThreaded.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletMultiThreaded/BulletMultiThreaded.vcxproj.filters -------------------------------------------------------------------------------- /bullet/msvc/BulletMultiThreaded/ThreadPool.cpp: -------------------------------------------------------------------------------- 1 | #include "ThreadPool.h" -------------------------------------------------------------------------------- /bullet/msvc/BulletMultiThreaded/ThreadPool.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletMultiThreaded/ThreadPool.h -------------------------------------------------------------------------------- /bullet/msvc/BulletSoftBody/BulletSoftBody.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletSoftBody/BulletSoftBody.vcxproj -------------------------------------------------------------------------------- /bullet/msvc/BulletSoftBody/BulletSoftBody.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/BulletSoftBody/BulletSoftBody.vcxproj.filters -------------------------------------------------------------------------------- /bullet/msvc/LinearMath/LinearMath.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/LinearMath/LinearMath.vcxproj -------------------------------------------------------------------------------- /bullet/msvc/LinearMath/LinearMath.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/msvc/LinearMath/LinearMath.vcxproj.filters -------------------------------------------------------------------------------- /bullet/proj/premake4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/proj/premake4 -------------------------------------------------------------------------------- /bullet/proj/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/proj/premake4.lua -------------------------------------------------------------------------------- /bullet/src/Bullet-C-Api.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/Bullet-C-Api.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btAxisSweep3.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btBroadphaseProxy.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDbvt.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btDbvt.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDbvt.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btDbvt.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btDbvtBroadphase.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btDispatcher.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btMultiSapBroadphase.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btMultiSapBroadphase.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btMultiSapBroadphase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btMultiSapBroadphase.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCache.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btQuantizedBvh.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/BroadphaseCollision/btSimpleBroadphase.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btBoxBoxDetector.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionObject.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCollisionWorld.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btGhostObject.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btGhostObject.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btGhostObject.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btGhostObject.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btHashedSimplePairCache.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btInternalEdgeUtility.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btManifoldResult.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSimulationIslandManager.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btUnionFind.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btUnionFind.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionDispatch/btUnionFind.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionDispatch/btUnionFind.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btBox2dShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btBox2dShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btBox2dShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btBox2dShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btBoxShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btBoxShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btBoxShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btBoxShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCapsuleShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCollisionMargin.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCollisionMargin.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCollisionShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCollisionShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCollisionShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCollisionShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCompoundShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCompoundShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCompoundShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConcaveShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConcaveShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConcaveShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConcaveShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConeShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConeShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConeShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConeShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvex2dShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvex2dShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvex2dShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvex2dShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexHullShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexInternalShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexInternalShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexInternalShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexInternalShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexPointCloudShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexPolyhedron.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btConvexTriangleMeshShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCylinderShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCylinderShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btCylinderShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btCylinderShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btEmptyShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btEmptyShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btEmptyShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btEmptyShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMaterial.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMaterial.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMinkowskiSumShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMultiSphereShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btOptimizedBvh.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btOptimizedBvh.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btOptimizedBvh.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btPolyhedralConvexShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btShapeHull.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btShapeHull.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btShapeHull.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btShapeHull.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btSphereShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btSphereShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btSphereShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btSphereShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btStaticPlaneShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btStridingMeshInterface.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btStridingMeshInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btStridingMeshInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTetrahedronShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTetrahedronShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTetrahedronShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTetrahedronShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleBuffer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleBuffer.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleBuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleBuffer.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleCallback.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleCallback.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleCallback.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleCallback.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleInfoMap.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleMesh.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleMesh.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleMesh.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleMesh.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleMeshShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleMeshShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleMeshShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btTriangleShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btTriangleShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btUniformScalingShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btUniformScalingShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/CollisionShapes/btUniformScalingShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/CollisionShapes/btUniformScalingShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btBoxCollision.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btBoxCollision.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btClipPolygon.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btClipPolygon.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btCompoundFromGimpact.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btCompoundFromGimpact.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btContactProcessing.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btContactProcessing.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btContactProcessing.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btContactProcessing.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactBvh.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactBvh.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactBvh.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactBvh.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactMassUtil.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactMassUtil.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactQuantizedBvh.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactShape.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactShape.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGImpactShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGImpactShape.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGenericPoolAllocator.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGenericPoolAllocator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGenericPoolAllocator.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btGeometryOperations.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btGeometryOperations.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btQuantization.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btQuantization.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btTriangleShapeEx.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btTriangleShapeEx.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/btTriangleShapeEx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/btTriangleShapeEx.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_array.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_array.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_basic_geometry_operations.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_basic_geometry_operations.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_bitset.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_bitset.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_box_collision.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_box_collision.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_box_set.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_box_set.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_box_set.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_box_set.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_clip_polygon.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_clip_polygon.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_contact.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_contact.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_contact.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_contact.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_geom_types.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_geom_types.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_geometry.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_geometry.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_hash_table.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_hash_table.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_linear_math.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_linear_math.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_math.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_math.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_memory.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_memory.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_memory.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_memory.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_radixsort.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_radixsort.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_tri_collision.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_tri_collision.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/Gimpact/gim_tri_collision.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/Gimpact/gim_tri_collision.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btConvexCast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btConvexCast.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpa2.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btManifoldPoint.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btPersistentManifold.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btPointCollector.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btRaycastCallback.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletCollision/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletCollision/premake4.lua -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Character/btCharacterControllerInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Character/btKinematicCharacterController.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Character/btKinematicCharacterController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Character/btKinematicCharacterController.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btConeTwistConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btConstraintSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btContactConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btContactConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btContactConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btContactSolverInfo.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btFixedConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btFixedConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btFixedConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btFixedConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGearConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btGearConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGearConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btGearConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btHingeConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btHingeConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btJacobianEntry.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btPoint2PointConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSliderConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSliderConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSliderConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSolverBody.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btSolverConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btSolverConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btTypedConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btTypedConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btUniversalConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btUniversalConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/ConstraintSolver/btUniversalConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/ConstraintSolver/btUniversalConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/Bullet-C-API.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/Bullet-C-API.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btActionInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btActionInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btDynamicsWorld.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btDynamicsWorld.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btRigidBody.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btRigidBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btRigidBody.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Dynamics/btSimpleDynamicsWorld.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBody.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBody.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyJointMotor.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyLink.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyLink.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodyPoint2Point.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Featherstone/btMultiBodySolverConstraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Featherstone/btMultiBodySolverConstraint.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btDantzigLCP.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btDantzigLCP.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btDantzigLCP.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btDantzigSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btDantzigSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btLemkeAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btLemkeSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolverInterface.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btMLCPSolverInterface.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btPATHSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btPATHSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btRaycastVehicle.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btVehicleRaycaster.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btVehicleRaycaster.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btWheelInfo.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btWheelInfo.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btWheelInfo.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btWheelInfo.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btWheeledVehicle.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btWheeledVehicle.cpp -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/Vehicle/btWheeledVehicle.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/Vehicle/btWheeledVehicle.h -------------------------------------------------------------------------------- /bullet/src/BulletDynamics/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletDynamics/premake4.lua -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/ApplyForces.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/ApplyForces.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/ComputeBounds.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/ComputeBounds.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/Integrate.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/Integrate.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/OutputToVertexArray.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/OutputToVertexArray.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/PrepareLinks.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/PrepareLinks.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/SolvePositions.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/SolvePositions.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/SolvePositionsSIMDBatched.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/SolvePositionsSIMDBatched.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateConstants.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateConstants.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateNodes.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateNodes.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateNormals.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateNormals.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositions.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositions.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositionsFromVelocities.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositionsFromVelocities.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/VSolveLinks.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/VSolveLinks.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/solveCollisionsAndUpdateVelocities.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/solveCollisionsAndUpdateVelocities.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/solveCollisionsAndUpdateVelocitiesSIMDBatched.hlsl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/solveCollisionsAndUpdateVelocitiesSIMDBatched.hlsl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverBuffer_DX11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverBuffer_DX11.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverLinkData_DX11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverLinkData_DX11.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverLinkData_DX11SIMDAware.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverLinkData_DX11SIMDAware.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverTriangleData_DX11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverTriangleData_DX11.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverVertexBuffer_DX11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverVertexBuffer_DX11.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverVertexData_DX11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolverVertexData_DX11.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11SIMDAware.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11SIMDAware.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11SIMDAware.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/DX11/btSoftBodySolver_DX11SIMDAware.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/MiniCL/MiniCLTaskWrap.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/MiniCL/MiniCLTaskWrap.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ApplyForces.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ApplyForces.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ComputeBounds.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ComputeBounds.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/Integrate.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/Integrate.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/OutputToVertexArray.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/OutputToVertexArray.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/PrepareLinks.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/PrepareLinks.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolveCollisionsAndUpdateVelocities.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolveCollisionsAndUpdateVelocities.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolveCollisionsAndUpdateVelocitiesSIMDBatched.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolveCollisionsAndUpdateVelocitiesSIMDBatched.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolvePositions.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolvePositions.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolvePositionsSIMDBatched.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolvePositionsSIMDBatched.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateConstants.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateConstants.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateFixedVertexPositions.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateFixedVertexPositions.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateNodes.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateNodes.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateNormals.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateNormals.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositions.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositions.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositionsFromVelocities.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositionsFromVelocities.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/VSolveLinks.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/VSolveLinks.cl -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverBuffer_OpenCL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverBuffer_OpenCL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverLinkData_OpenCL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverLinkData_OpenCL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverLinkData_OpenCLSIMDAware.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverLinkData_OpenCLSIMDAware.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverOutputCLtoGL.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverOutputCLtoGL.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverOutputCLtoGL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverOutputCLtoGL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverTriangleData_OpenCL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverTriangleData_OpenCL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverVertexBuffer_OpenGL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverVertexBuffer_OpenGL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverVertexData_OpenCL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverVertexData_OpenCL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCL.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCL.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCL.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCL.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCLSIMDAware.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCLSIMDAware.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCLSIMDAware.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolver_OpenCLSIMDAware.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/Shared/btSoftBodySolverData.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/GpuSoftBodySolvers/Shared/btSoftBodySolverData.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/HeapManager.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/HeapManager.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/PlatformDefinitions.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/PlatformDefinitions.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/PosixThreading.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/PosixThreading.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/PpuAddressSpace.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/PpuAddressSpace.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/TrbDynBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/TrbDynBody.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/TrbStateVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/TrbStateVec.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/Win32Threading.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/Win32Threading.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpu3DGridBroadphase.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpu3DGridBroadphase.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpu3DGridBroadphase.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpu3DGridBroadphase.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpu3DGridBroadphaseSharedCode.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpu3DGridBroadphaseSharedCode.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpu3DGridBroadphaseSharedDefs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpu3DGridBroadphaseSharedDefs.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpu3DGridBroadphaseSharedTypes.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpu3DGridBroadphaseSharedTypes.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpuDefines.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpuDefines.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpuUtilsSharedCode.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpuUtilsSharedCode.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btGpuUtilsSharedDefs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btGpuUtilsSharedDefs.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btParallelCollisionDispatcher.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btParallelCollisionDispatcher.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btParallelCollisionDispatcher.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btParallelCollisionDispatcher.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btParallelConstraintSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btParallelConstraintSolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btParallelConstraintSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btParallelConstraintSolver.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btThreadPool.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btThreadPool.cpp -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btThreadPool.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btThreadPool.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/btThreading.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/btThreading.h -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/premake4.lua -------------------------------------------------------------------------------- /bullet/src/BulletMultiThreaded/vectormath2bullet.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletMultiThreaded/vectormath2bullet.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btDefaultSoftBodySolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btDefaultSoftBodySolver.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btDefaultSoftBodySolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btDefaultSoftBodySolver.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBody.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBody.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyData.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyData.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyHelpers.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyHelpers.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyHelpers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyHelpers.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyInternals.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyInternals.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftBodySolvers.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftBodySolvers.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftRigidDynamicsWorld.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftRigidDynamicsWorld.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/btSparseSDF.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/btSparseSDF.h -------------------------------------------------------------------------------- /bullet/src/BulletSoftBody/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/BulletSoftBody/premake4.lua -------------------------------------------------------------------------------- /bullet/src/LinearMath/btAabbUtil2.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btAabbUtil2.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btAlignedAllocator.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btAlignedAllocator.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btAlignedAllocator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btAlignedAllocator.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btAlignedObjectArray.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btAlignedObjectArray.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btConvexHull.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btConvexHull.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btConvexHull.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btConvexHull.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btConvexHullComputer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btConvexHullComputer.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btConvexHullComputer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btConvexHullComputer.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDebug.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btDebug.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDebug.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btDebug.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDefaultMotionState.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btDefaultMotionState.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btDefines.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btDefines.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btGeometryUtil.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btGeometryUtil.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btGeometryUtil.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btGeometryUtil.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btGrahamScan2dConvexHull.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btGrahamScan2dConvexHull.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btHashMap.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btHashMap.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btIDebugDraw.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btIDebugDraw.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btList.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btList.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btMatrix3x3.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btMatrix3x3.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btMatrixX.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btMatrixX.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btMinMax.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btMinMax.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btMotionState.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btMotionState.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btPolarDecomposition.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btPolarDecomposition.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btPolarDecomposition.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btPolarDecomposition.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btPoolAllocator.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btPoolAllocator.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btQuadWord.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btQuadWord.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btQuaternion.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btQuaternion.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btQuickprof.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btQuickprof.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btQuickprof.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btQuickprof.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btRandom.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btRandom.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btScalar.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btScalar.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btSerializer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btSerializer.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btSerializer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btSerializer.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btStackAlloc.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btStackAlloc.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btTransform.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btTransform.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btTransformUtil.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btTransformUtil.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/btVector3.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btVector3.cpp -------------------------------------------------------------------------------- /bullet/src/LinearMath/btVector3.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/btVector3.h -------------------------------------------------------------------------------- /bullet/src/LinearMath/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/LinearMath/premake4.lua -------------------------------------------------------------------------------- /bullet/src/Makefile.am: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/Makefile.am -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCL.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/MiniCL.cpp -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCLTask/MiniCLTask.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/MiniCLTask/MiniCLTask.cpp -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCLTask/MiniCLTask.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/MiniCLTask/MiniCLTask.h -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCLTaskScheduler.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/MiniCLTaskScheduler.cpp -------------------------------------------------------------------------------- /bullet/src/MiniCL/MiniCLTaskScheduler.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/MiniCLTaskScheduler.h -------------------------------------------------------------------------------- /bullet/src/MiniCL/cl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/cl.h -------------------------------------------------------------------------------- /bullet/src/MiniCL/cl_MiniCL_Defs.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/cl_MiniCL_Defs.h -------------------------------------------------------------------------------- /bullet/src/MiniCL/cl_gl.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/cl_gl.h -------------------------------------------------------------------------------- /bullet/src/MiniCL/cl_platform.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/MiniCL/cl_platform.h -------------------------------------------------------------------------------- /bullet/src/btBulletCollisionCommon.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/btBulletCollisionCommon.h -------------------------------------------------------------------------------- /bullet/src/btBulletDynamicsCommon.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/btBulletDynamicsCommon.h -------------------------------------------------------------------------------- /bullet/src/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/premake4.lua -------------------------------------------------------------------------------- /bullet/src/vectormath/neon/boolInVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/neon/boolInVec.h -------------------------------------------------------------------------------- /bullet/src/vectormath/neon/floatInVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/neon/floatInVec.h -------------------------------------------------------------------------------- /bullet/src/vectormath/neon/mat_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/neon/mat_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/neon/quat_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/neon/quat_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/neon/vec_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/neon/vec_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/neon/vectormath_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/neon/vectormath_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/scalar/boolInVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/scalar/boolInVec.h -------------------------------------------------------------------------------- /bullet/src/vectormath/scalar/floatInVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/scalar/floatInVec.h -------------------------------------------------------------------------------- /bullet/src/vectormath/scalar/mat_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/scalar/mat_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/scalar/quat_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/scalar/quat_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/scalar/vec_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/scalar/vec_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/scalar/vectormath_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/scalar/vectormath_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/boolInVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/boolInVec.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/floatInVec.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/floatInVec.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/mat_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/mat_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/quat_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/quat_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/vec_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/vec_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/vecidx_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/vecidx_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/sse/vectormath_aos.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/sse/vectormath_aos.h -------------------------------------------------------------------------------- /bullet/src/vectormath/vmInclude.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/bullet/src/vectormath/vmInclude.h -------------------------------------------------------------------------------- /include/vphysics/constraintsV32.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/include/vphysics/constraintsV32.h -------------------------------------------------------------------------------- /include/vphysics/softbodyV32.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/include/vphysics/softbodyV32.h -------------------------------------------------------------------------------- /include/vphysics/vehiclesV32.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/include/vphysics/vehiclesV32.h -------------------------------------------------------------------------------- /include/vphysics_interfaceV32.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/include/vphysics_interfaceV32.h -------------------------------------------------------------------------------- /proj/gmake.sh: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/proj/gmake.sh -------------------------------------------------------------------------------- /proj/options.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/proj/options.lua -------------------------------------------------------------------------------- /proj/premake4: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/proj/premake4 -------------------------------------------------------------------------------- /proj/premake4.exe: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/proj/premake4.exe -------------------------------------------------------------------------------- /proj/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/proj/premake4.lua -------------------------------------------------------------------------------- /proj/readme.txt: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/proj/readme.txt -------------------------------------------------------------------------------- /proj/vs2010.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | 3 | premake4 vs2010 4 | -------------------------------------------------------------------------------- /src/DebugDrawer.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/DebugDrawer.cpp -------------------------------------------------------------------------------- /src/DebugDrawer.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/DebugDrawer.h -------------------------------------------------------------------------------- /src/IController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/IController.h -------------------------------------------------------------------------------- /src/Makefile: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Makefile -------------------------------------------------------------------------------- /src/Physics.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics.cpp -------------------------------------------------------------------------------- /src/Physics.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics.h -------------------------------------------------------------------------------- /src/Physics_Collision.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Collision.cpp -------------------------------------------------------------------------------- /src/Physics_Collision.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Collision.h -------------------------------------------------------------------------------- /src/Physics_CollisionSet.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_CollisionSet.cpp -------------------------------------------------------------------------------- /src/Physics_CollisionSet.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_CollisionSet.h -------------------------------------------------------------------------------- /src/Physics_Constraint.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Constraint.cpp -------------------------------------------------------------------------------- /src/Physics_Constraint.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Constraint.h -------------------------------------------------------------------------------- /src/Physics_DragController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_DragController.cpp -------------------------------------------------------------------------------- /src/Physics_DragController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_DragController.h -------------------------------------------------------------------------------- /src/Physics_Environment.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Environment.cpp -------------------------------------------------------------------------------- /src/Physics_Environment.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Environment.h -------------------------------------------------------------------------------- /src/Physics_FluidController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_FluidController.cpp -------------------------------------------------------------------------------- /src/Physics_FluidController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_FluidController.h -------------------------------------------------------------------------------- /src/Physics_FrictionSnapshot.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_FrictionSnapshot.cpp -------------------------------------------------------------------------------- /src/Physics_FrictionSnapshot.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_FrictionSnapshot.h -------------------------------------------------------------------------------- /src/Physics_KeyParser.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_KeyParser.cpp -------------------------------------------------------------------------------- /src/Physics_KeyParser.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_KeyParser.h -------------------------------------------------------------------------------- /src/Physics_MotionController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_MotionController.cpp -------------------------------------------------------------------------------- /src/Physics_MotionController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_MotionController.h -------------------------------------------------------------------------------- /src/Physics_Object.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Object.cpp -------------------------------------------------------------------------------- /src/Physics_Object.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_Object.h -------------------------------------------------------------------------------- /src/Physics_ObjectPairHash.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_ObjectPairHash.cpp -------------------------------------------------------------------------------- /src/Physics_ObjectPairHash.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_ObjectPairHash.h -------------------------------------------------------------------------------- /src/Physics_PlayerController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_PlayerController.cpp -------------------------------------------------------------------------------- /src/Physics_PlayerController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_PlayerController.h -------------------------------------------------------------------------------- /src/Physics_ShadowController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_ShadowController.cpp -------------------------------------------------------------------------------- /src/Physics_ShadowController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_ShadowController.h -------------------------------------------------------------------------------- /src/Physics_SoftBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_SoftBody.cpp -------------------------------------------------------------------------------- /src/Physics_SoftBody.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_SoftBody.h -------------------------------------------------------------------------------- /src/Physics_SurfaceProps.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_SurfaceProps.cpp -------------------------------------------------------------------------------- /src/Physics_SurfaceProps.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_SurfaceProps.h -------------------------------------------------------------------------------- /src/Physics_VehicleAirboat.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_VehicleAirboat.cpp -------------------------------------------------------------------------------- /src/Physics_VehicleAirboat.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_VehicleAirboat.h -------------------------------------------------------------------------------- /src/Physics_VehicleController.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_VehicleController.cpp -------------------------------------------------------------------------------- /src/Physics_VehicleController.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_VehicleController.h -------------------------------------------------------------------------------- /src/Physics_VehicleControllerCustom.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_VehicleControllerCustom.cpp -------------------------------------------------------------------------------- /src/Physics_VehicleControllerCustom.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/Physics_VehicleControllerCustom.h -------------------------------------------------------------------------------- /src/StdAfx.cpp: -------------------------------------------------------------------------------- 1 | #include "StdAfx.h" 2 | -------------------------------------------------------------------------------- /src/StdAfx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/StdAfx.h -------------------------------------------------------------------------------- /src/convert.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/convert.h -------------------------------------------------------------------------------- /src/miscmath.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/miscmath.cpp -------------------------------------------------------------------------------- /src/miscmath.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/miscmath.h -------------------------------------------------------------------------------- /src/phydata.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/phydata.h -------------------------------------------------------------------------------- /src/premake4.lua: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/premake4.lua -------------------------------------------------------------------------------- /src/resource.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/resource.h -------------------------------------------------------------------------------- /src/vphysics.rc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/src/vphysics.rc -------------------------------------------------------------------------------- /vphysics.sln: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/vphysics.sln -------------------------------------------------------------------------------- /vphysics.vcxproj: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/vphysics.vcxproj -------------------------------------------------------------------------------- /vphysics.vcxproj.filters: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/DrChat/Gmod-vphysics/HEAD/vphysics.vcxproj.filters --------------------------------------------------------------------------------