├── .gitignore ├── AwayPhysics ├── lib │ └── AwayPhysics.swc └── src │ ├── awayphysics │ ├── AWPBase.as │ ├── collision │ │ ├── dispatch │ │ │ ├── AWPCollisionObject.as │ │ │ ├── AWPCollisionWorld.as │ │ │ ├── AWPGhostObject.as │ │ │ ├── AWPManifoldPoint.as │ │ │ └── AWPRay.as │ │ └── shapes │ │ │ ├── AWPBoxShape.as │ │ │ ├── AWPBvhTriangleMeshShape.as │ │ │ ├── AWPCapsuleShape.as │ │ │ ├── AWPCollisionShape.as │ │ │ ├── AWPCompoundShape.as │ │ │ ├── AWPConeShape.as │ │ │ ├── AWPConvexHullShape.as │ │ │ ├── AWPCylinderShape.as │ │ │ ├── AWPHeightfieldTerrainShape.as │ │ │ ├── AWPSphereShape.as │ │ │ ├── AWPStaticPlaneShape.as │ │ │ └── AWPTriangleShape.as │ ├── data │ │ ├── AWPCollisionFilterGroups.as │ │ ├── AWPCollisionFlags.as │ │ ├── AWPCollisionObjectTypes.as │ │ ├── AWPCollisionShapeType.as │ │ └── AWPTypedConstraintType.as │ ├── debug │ │ └── AWPDebugDraw.as │ ├── dynamics │ │ ├── AWPDynamicsWorld.as │ │ ├── AWPRigidBody.as │ │ ├── character │ │ │ └── AWPKinematicCharacterController.as │ │ ├── constraintsolver │ │ │ ├── AWPAngularLimit.as │ │ │ ├── AWPConeTwistConstraint.as │ │ │ ├── AWPGeneric6DofConstraint.as │ │ │ ├── AWPHingeConstraint.as │ │ │ ├── AWPPoint2PointConstraint.as │ │ │ ├── AWPRotationalLimitMotor.as │ │ │ ├── AWPTranslationalLimitMotor.as │ │ │ └── AWPTypedConstraint.as │ │ └── vehicle │ │ │ ├── AWPRaycastInfo.as │ │ │ ├── AWPRaycastVehicle.as │ │ │ ├── AWPVehicleTuning.as │ │ │ └── AWPWheelInfo.as │ ├── events │ │ └── AWPEvent.as │ ├── extend │ │ └── AWPTerrain.as │ └── math │ │ ├── AWPMath.as │ │ ├── AWPMatrix3x3.as │ │ ├── AWPTransform.as │ │ └── AWPVector3.as │ └── com │ └── adobe │ └── flascc │ └── Console.as ├── Bullet ├── AwayPhysics.c ├── 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 │ ├── CMakeLists.txt │ ├── 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 │ │ ├── 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 │ │ ├── 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 │ ├── Doxyfile │ ├── Gimpact │ │ ├── btBoxCollision.h │ │ ├── btClipPolygon.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 │ ├── CMakeLists.txt │ ├── Character │ │ ├── btCharacterControllerInterface.h │ │ ├── btKinematicCharacterController.cpp │ │ └── btKinematicCharacterController.h │ ├── ConstraintSolver │ │ ├── btConeTwistConstraint.cpp │ │ ├── btConeTwistConstraint.h │ │ ├── btConstraintSolver.h │ │ ├── btContactConstraint.cpp │ │ ├── btContactConstraint.h │ │ ├── btContactSolverInfo.h │ │ ├── btGearConstraint.cpp │ │ ├── btGearConstraint.h │ │ ├── btGeneric6DofConstraint.cpp │ │ ├── btGeneric6DofConstraint.h │ │ ├── btGeneric6DofSpringConstraint.cpp │ │ ├── btGeneric6DofSpringConstraint.h │ │ ├── btHinge2Constraint.cpp │ │ ├── btHinge2Constraint.h │ │ ├── btHingeConstraint.cpp │ │ ├── btHingeConstraint.h │ │ ├── btJacobianEntry.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 │ ├── Vehicle │ │ ├── btRaycastVehicle.cpp │ │ ├── btRaycastVehicle.h │ │ ├── btVehicleRaycaster.h │ │ ├── btWheelInfo.cpp │ │ └── btWheelInfo.h │ └── premake4.lua ├── BulletMultiThreaded │ ├── CMakeLists.txt │ ├── GpuSoftBodySolvers │ │ ├── CMakeLists.txt │ │ ├── DX11 │ │ │ ├── CMakeLists.txt │ │ │ ├── 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 │ │ │ └── premake4.lua │ │ ├── OpenCL │ │ │ ├── AMD │ │ │ │ ├── CMakeLists.txt │ │ │ │ └── premake4.lua │ │ │ ├── Apple │ │ │ │ └── CMakeLists.txt │ │ │ ├── CMakeLists.txt │ │ │ ├── Intel │ │ │ │ ├── CMakeLists.txt │ │ │ │ └── premake4.lua │ │ │ ├── MiniCL │ │ │ │ ├── CMakeLists.txt │ │ │ │ └── MiniCLTaskWrap.cpp │ │ │ ├── NVidia │ │ │ │ ├── CMakeLists.txt │ │ │ │ └── premake4.lua │ │ │ ├── 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 │ ├── PosixThreadSupport.cpp │ ├── PosixThreadSupport.h │ ├── PpuAddressSpace.h │ ├── SequentialThreadSupport.cpp │ ├── SequentialThreadSupport.h │ ├── SpuCollisionObjectWrapper.cpp │ ├── SpuCollisionObjectWrapper.h │ ├── SpuCollisionTaskProcess.cpp │ ├── SpuCollisionTaskProcess.h │ ├── SpuContactManifoldCollisionAlgorithm.cpp │ ├── SpuContactManifoldCollisionAlgorithm.h │ ├── SpuDoubleBuffer.h │ ├── SpuFakeDma.cpp │ ├── SpuFakeDma.h │ ├── SpuGatheringCollisionDispatcher.cpp │ ├── SpuGatheringCollisionDispatcher.h │ ├── SpuLibspe2Support.cpp │ ├── SpuLibspe2Support.h │ ├── SpuNarrowPhaseCollisionTask │ │ ├── Box.h │ │ ├── SpuCollisionShapes.cpp │ │ ├── SpuCollisionShapes.h │ │ ├── SpuContactResult.cpp │ │ ├── SpuContactResult.h │ │ ├── SpuConvexPenetrationDepthSolver.h │ │ ├── SpuGatheringCollisionTask.cpp │ │ ├── SpuGatheringCollisionTask.h │ │ ├── SpuLocalSupport.h │ │ ├── SpuMinkowskiPenetrationDepthSolver.cpp │ │ ├── SpuMinkowskiPenetrationDepthSolver.h │ │ ├── SpuPreferredPenetrationDirections.h │ │ ├── boxBoxDistance.cpp │ │ ├── boxBoxDistance.h │ │ └── readme.txt │ ├── SpuSampleTask │ │ ├── SpuSampleTask.cpp │ │ ├── SpuSampleTask.h │ │ └── readme.txt │ ├── SpuSampleTaskProcess.cpp │ ├── SpuSampleTaskProcess.h │ ├── SpuSync.h │ ├── TrbDynBody.h │ ├── TrbStateVec.h │ ├── Win32ThreadSupport.cpp │ ├── Win32ThreadSupport.h │ ├── btGpu3DGridBroadphase.cpp │ ├── btGpu3DGridBroadphase.h │ ├── btGpu3DGridBroadphaseSharedCode.h │ ├── btGpu3DGridBroadphaseSharedDefs.h │ ├── btGpu3DGridBroadphaseSharedTypes.h │ ├── btGpuDefines.h │ ├── btGpuUtilsSharedCode.h │ ├── btGpuUtilsSharedDefs.h │ ├── btParallelConstraintSolver.cpp │ ├── btParallelConstraintSolver.h │ ├── btThreadSupportInterface.cpp │ ├── btThreadSupportInterface.h │ └── vectormath2bullet.h ├── BulletSoftBody │ ├── CMakeLists.txt │ ├── 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 │ ├── CMakeLists.txt │ ├── btAabbUtil2.h │ ├── btAlignedAllocator.cpp │ ├── btAlignedAllocator.h │ ├── btAlignedObjectArray.h │ ├── btConvexHull.cpp │ ├── btConvexHull.h │ ├── btConvexHullComputer.cpp │ ├── btConvexHullComputer.h │ ├── btDefaultMotionState.h │ ├── btGeometryUtil.cpp │ ├── btGeometryUtil.h │ ├── btGrahamScan2dConvexHull.h │ ├── btHashMap.h │ ├── btIDebugDraw.h │ ├── btList.h │ ├── btMatrix3x3.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 ├── MiniCL │ ├── CMakeLists.txt │ ├── 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 ├── bulletModification.txt ├── exports.txt ├── libbulletcollision.a ├── libbulletdynamics.a ├── libbulletmath.a └── 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 └── README.txt /.gitignore: -------------------------------------------------------------------------------- 1 | /bin 2 | /.settings 3 | /.project 4 | /away3d_core_fp11 -------------------------------------------------------------------------------- /AwayPhysics/lib/AwayPhysics.swc: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/AwayPhysics/lib/AwayPhysics.swc -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/AWPBase.as: -------------------------------------------------------------------------------- 1 | package awayphysics { 2 | public class AWPBase { 3 | /** 4 | * 1 visual units equal to 0.01 bullet meters by default, this value is inversely with physics world scaling 5 | * refer to http://www.bulletphysics.org/mediawiki-1.5.8/index.php?title=Scaling_The_World 6 | */ 7 | protected static var _scaling : Number = 100; 8 | protected var _cleanup:Boolean = false; 9 | public var pointer : uint; 10 | } 11 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/dispatch/AWPCollisionWorld.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.dispatch { 2 | import AWPC_Run.addCollisionObjectInC; 3 | import AWPC_Run.removeCollisionObjectInC; 4 | 5 | import awayphysics.AWPBase; 6 | import awayphysics.collision.dispatch.AWPCollisionObject; 7 | 8 | import flash.utils.Dictionary; 9 | 10 | public class AWPCollisionWorld extends AWPBase{ 11 | 12 | protected var m_collisionObjects:Dictionary; 13 | 14 | public function AWPCollisionWorld(){ 15 | m_collisionObjects = new Dictionary(true); 16 | } 17 | 18 | public function get collisionObjects() : Dictionary { 19 | return m_collisionObjects; 20 | } 21 | 22 | /** 23 | * add a collisionObject to collision world 24 | */ 25 | public function addCollisionObject(obj:AWPCollisionObject, group:int = 1, mask:int = -1):void{ 26 | if(!m_collisionObjects.hasOwnProperty(obj.pointer.toString())){ 27 | m_collisionObjects[obj.pointer.toString()] = obj; 28 | addCollisionObjectInC(obj.pointer, group, mask); 29 | } 30 | } 31 | 32 | /** 33 | * remove a collisionObject from collision world, if cleanup is true, release pointer in memory. 34 | */ 35 | public function removeCollisionObject(obj:AWPCollisionObject, cleanup:Boolean = false) : void { 36 | if(m_collisionObjects.hasOwnProperty(obj.pointer.toString())){ 37 | delete m_collisionObjects[obj.pointer.toString()]; 38 | removeCollisionObjectInC(obj.pointer); 39 | 40 | if (cleanup) { 41 | obj.dispose(); 42 | } 43 | } 44 | } 45 | } 46 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/dispatch/AWPGhostObject.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.dispatch { 2 | import AWPC_Run.createGhostObjectInC; 3 | import away3d.containers.ObjectContainer3D; 4 | import awayphysics.collision.shapes.AWPCollisionShape; 5 | 6 | /** 7 | *used for create the character controller 8 | */ 9 | public class AWPGhostObject extends AWPCollisionObject { 10 | public function AWPGhostObject(shape : AWPCollisionShape, skin : ObjectContainer3D = null) { 11 | pointer = createGhostObjectInC(shape.pointer); 12 | super(shape, skin, pointer); 13 | } 14 | } 15 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/dispatch/AWPManifoldPoint.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.dispatch { 2 | import AWPC_Run.CModule; 3 | import awayphysics.AWPBase; 4 | import awayphysics.math.AWPVector3; 5 | 6 | import flash.geom.Vector3D; 7 | 8 | public class AWPManifoldPoint extends AWPBase { 9 | private var m_localPointA : AWPVector3; 10 | private var m_localPointB : AWPVector3; 11 | private var m_normalWorldOnB : AWPVector3; 12 | 13 | public function AWPManifoldPoint(ptr : uint) { 14 | pointer = ptr; 15 | m_localPointA = new AWPVector3(ptr + 0); 16 | m_localPointB = new AWPVector3(ptr + 16); 17 | m_normalWorldOnB = new AWPVector3(ptr + 64); 18 | } 19 | 20 | /** 21 | *get the collision position in objectA's local coordinates 22 | */ 23 | public function get localPointA() : Vector3D { 24 | return m_localPointA.sv3d; 25 | } 26 | 27 | /** 28 | *get the collision position in objectB's local coordinates 29 | */ 30 | public function get localPointB() : Vector3D { 31 | return m_localPointB.sv3d; 32 | } 33 | 34 | /** 35 | *get the collision normal in world coordinates 36 | */ 37 | public function get normalWorldOnB() : Vector3D { 38 | return m_normalWorldOnB.v3d; 39 | } 40 | 41 | /** 42 | *get the value of collision impulse 43 | */ 44 | public function get appliedImpulse() : Number { 45 | return CModule.readFloat(pointer + 120); 46 | } 47 | } 48 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/dispatch/AWPRay.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.dispatch { 2 | import flash.geom.Vector3D; 3 | import awayphysics.AWPBase; 4 | public class AWPRay extends AWPBase { 5 | public var rayFrom:Vector3D; 6 | public var rayTo:Vector3D; 7 | 8 | public function AWPRay(from:Vector3D, to:Vector3D, ptr:uint = 0) { 9 | rayFrom = from; 10 | rayTo = to; 11 | pointer = ptr; 12 | } 13 | } 14 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPBoxShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import flash.geom.Vector3D; 3 | 4 | import AWPC_Run.createBoxShapeInC; 5 | import AWPC_Run.CModule; 6 | 7 | import awayphysics.math.AWPVector3; 8 | 9 | public class AWPBoxShape extends AWPCollisionShape { 10 | 11 | private var _dimensions:Vector3D; 12 | 13 | public function AWPBoxShape(width : Number = 100, height : Number = 100, depth : Number = 100) { 14 | _dimensions = new Vector3D(width, height, depth); 15 | var vec:AWPVector3 = new AWPVector3(); 16 | vec.sv3d = new Vector3D(width, height, depth); 17 | pointer = createBoxShapeInC(vec.pointer); 18 | CModule.free(vec.pointer); 19 | super(pointer, 0); 20 | } 21 | 22 | public function get dimensions():Vector3D { 23 | return new Vector3D(_dimensions.x * m_localScaling.x, _dimensions.y * m_localScaling.y, _dimensions.z * m_localScaling.z); 24 | } 25 | } 26 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPCapsuleShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import AWPC_Run.createCapsuleShapeInC; 3 | public class AWPCapsuleShape extends AWPCollisionShape { 4 | 5 | private var _radius:Number; 6 | private var _height:Number; 7 | 8 | public function AWPCapsuleShape(radius : Number = 50, height : Number = 100) { 9 | 10 | _radius = radius; 11 | _height = height; 12 | 13 | pointer = createCapsuleShapeInC(radius / _scaling, height / _scaling); 14 | super(pointer, 3); 15 | } 16 | 17 | public function get radius():Number { 18 | return _radius * m_localScaling.x; 19 | } 20 | 21 | public function get height():Number { 22 | return _height * m_localScaling.y; 23 | } 24 | } 25 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPCollisionShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import AWPC_Run.CModule; 3 | import AWPC_Run.setShapeScalingInC; 4 | import AWPC_Run.disposeCollisionShapeInC; 5 | 6 | import awayphysics.AWPBase; 7 | import awayphysics.math.AWPVector3; 8 | 9 | import flash.geom.Vector3D; 10 | 11 | public class AWPCollisionShape extends AWPBase { 12 | 13 | protected var m_shapeType:int; 14 | protected var m_localScaling:Vector3D; 15 | 16 | protected var m_counter:int = 0; 17 | 18 | public function AWPCollisionShape(ptr:uint, type:int) { 19 | pointer = ptr; 20 | m_shapeType = type; 21 | 22 | m_localScaling = new Vector3D(1, 1, 1); 23 | } 24 | 25 | /** 26 | * the values defined by AWPCollisionShapeType 27 | */ 28 | public function get shapeType():int { 29 | return m_shapeType; 30 | } 31 | 32 | public function get localScaling():Vector3D { 33 | return m_localScaling; 34 | } 35 | 36 | public function set localScaling(scale:Vector3D):void { 37 | m_localScaling.setTo(scale.x, scale.y, scale.z); 38 | if(scale.w == 0){ 39 | var vec:AWPVector3 = new AWPVector3(); 40 | vec.v3d = scale; 41 | setShapeScalingInC(pointer, vec.pointer); 42 | CModule.free(vec.pointer); 43 | } 44 | } 45 | 46 | /** 47 | * this function just called by internal 48 | */ 49 | public function retain():void { 50 | m_counter++; 51 | } 52 | 53 | /** 54 | * this function just called by internal 55 | */ 56 | public function dispose():void { 57 | m_counter--; 58 | if (m_counter > 0) { 59 | return; 60 | }else { 61 | m_counter = 0; 62 | } 63 | if (!_cleanup) { 64 | _cleanup = true; 65 | disposeCollisionShapeInC(pointer); 66 | } 67 | } 68 | } 69 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPConeShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import AWPC_Run.createConeShapeInC; 3 | public class AWPConeShape extends AWPCollisionShape { 4 | 5 | private var _radius:Number; 6 | private var _height:Number; 7 | 8 | public function AWPConeShape(radius : Number = 50, height : Number = 100) { 9 | 10 | _radius = radius; 11 | _height = height; 12 | 13 | pointer = createConeShapeInC(radius / _scaling, height / _scaling); 14 | super(pointer, 4); 15 | } 16 | 17 | public function get radius():Number { 18 | return _radius * m_localScaling.x; 19 | } 20 | 21 | public function get height():Number { 22 | return _height * m_localScaling.y; 23 | } 24 | } 25 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPConvexHullShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes 2 | { 3 | import AWPC_Run.CModule; 4 | import AWPC_Run.createTriangleVertexDataBufferInC; 5 | import AWPC_Run.removeTriangleVertexDataBufferInC; 6 | import AWPC_Run.createConvexHullShapeInC; 7 | import AWPC_Run.disposeCollisionShapeInC 8 | import away3d.core.base.Geometry; 9 | 10 | public class AWPConvexHullShape extends AWPCollisionShape 11 | { 12 | private var vertexDataPtr : uint; 13 | 14 | private var _geometry:Geometry; 15 | 16 | public function AWPConvexHullShape(geometry : Geometry) 17 | { 18 | _geometry = geometry; 19 | var vertexData : Vector. = geometry.subGeometries[0].vertexData; 20 | var vertexDataLen : int = vertexData.length/13; 21 | vertexDataPtr = createTriangleVertexDataBufferInC(vertexDataLen*3); 22 | 23 | for (var i:int = 0; i < vertexDataLen; i++ ) { 24 | CModule.writeFloat(vertexDataPtr+i*12,vertexData[i*13] / _scaling); 25 | CModule.writeFloat(vertexDataPtr+i*12+ 4,vertexData[i*13+1] / _scaling); 26 | CModule.writeFloat(vertexDataPtr+i*12 + 8,vertexData[i*13+2] / _scaling); 27 | } 28 | 29 | pointer = createConvexHullShapeInC(int(vertexDataLen), vertexDataPtr); 30 | super(pointer, 5); 31 | } 32 | 33 | override public function dispose() : void 34 | { 35 | m_counter--; 36 | if (m_counter > 0) { 37 | return; 38 | }else { 39 | m_counter = 0; 40 | } 41 | if (!_cleanup) { 42 | _cleanup = true; 43 | removeTriangleVertexDataBufferInC(vertexDataPtr); 44 | disposeCollisionShapeInC(pointer); 45 | } 46 | } 47 | 48 | public function get geometry():Geometry { 49 | return _geometry; 50 | } 51 | } 52 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPCylinderShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import flash.geom.Vector3D; 3 | import AWPC_Run.CModule; 4 | import AWPC_Run.createCylinderShapeInC; 5 | import awayphysics.math.AWPVector3; 6 | 7 | public class AWPCylinderShape extends AWPCollisionShape { 8 | 9 | private var _radius:Number; 10 | private var _height:Number; 11 | 12 | public function AWPCylinderShape(radius : Number = 50, height : Number = 100) { 13 | 14 | _radius = radius; 15 | _height = height; 16 | 17 | var vec:AWPVector3 = new AWPVector3(); 18 | vec.v3d = new Vector3D(radius * 2 / _scaling, height / _scaling, radius * 2 / _scaling) 19 | pointer = createCylinderShapeInC(vec.pointer); 20 | CModule.free(vec.pointer); 21 | super(pointer, 2); 22 | } 23 | 24 | public function get radius():Number { 25 | return _radius * m_localScaling.x; 26 | } 27 | 28 | public function get height():Number { 29 | return _height * m_localScaling.y; 30 | } 31 | } 32 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPHeightfieldTerrainShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import AWPC_Run.CModule; 3 | import AWPC_Run.createHeightmapDataBufferInC; 4 | import AWPC_Run.removeHeightmapDataBufferInC; 5 | import AWPC_Run.createTerrainShapeInC; 6 | import AWPC_Run.disposeCollisionShapeInC; 7 | 8 | import away3d.core.base.Geometry; 9 | import awayphysics.extend.AWPTerrain; 10 | 11 | public class AWPHeightfieldTerrainShape extends AWPCollisionShape { 12 | private var dataPtr : uint; 13 | 14 | private var _geometry:Geometry; 15 | 16 | /** 17 | * create terrain with the heightmap data 18 | */ 19 | public function AWPHeightfieldTerrainShape(terrain : AWPTerrain) { 20 | _geometry = terrain.geometry; 21 | var dataLen : int = terrain.sw * terrain.sh; 22 | dataPtr = createHeightmapDataBufferInC(dataLen); 23 | 24 | var data : Vector. = terrain.heights; 25 | for (var i : int = 0; i < dataLen; i++ ) { 26 | CModule.writeFloat(dataPtr+i*4,data[i] / _scaling); 27 | } 28 | 29 | pointer = createTerrainShapeInC(dataPtr, terrain.sw, terrain.sh, terrain.lw / _scaling, terrain.lh / _scaling, 1, -terrain.maxHeight / _scaling, terrain.maxHeight / _scaling, 1); 30 | super(pointer, 10); 31 | } 32 | 33 | override public function dispose() : void { 34 | m_counter--; 35 | if (m_counter > 0) { 36 | return; 37 | }else { 38 | m_counter = 0; 39 | } 40 | if (!_cleanup) { 41 | _cleanup = true; 42 | removeHeightmapDataBufferInC(dataPtr); 43 | disposeCollisionShapeInC(pointer); 44 | } 45 | } 46 | 47 | public function get geometry():Geometry { 48 | return _geometry; 49 | } 50 | } 51 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPSphereShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import AWPC_Run.createSphereShapeInC; 3 | public class AWPSphereShape extends AWPCollisionShape { 4 | 5 | private var _radius:Number; 6 | 7 | public function AWPSphereShape(radius : Number = 50) { 8 | _radius = radius; 9 | 10 | pointer = createSphereShapeInC(radius / _scaling); 11 | super(pointer, 1); 12 | } 13 | 14 | public function get radius():Number { 15 | return _radius * m_localScaling.x; 16 | } 17 | } 18 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPStaticPlaneShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes { 2 | import AWPC_Run.CModule; 3 | import AWPC_Run.createStaticPlaneShapeInC; 4 | 5 | import awayphysics.math.AWPVector3; 6 | 7 | import flash.geom.Vector3D; 8 | 9 | public class AWPStaticPlaneShape extends AWPCollisionShape { 10 | 11 | private var _normal:Vector3D; 12 | private var _constant:Number; 13 | 14 | public function AWPStaticPlaneShape(normal : Vector3D = null, constant : Number = 0) { 15 | if (!normal) { 16 | normal = new Vector3D(0, 1, 0); 17 | } 18 | _normal = normal; 19 | _constant = constant; 20 | 21 | var vec:AWPVector3 = new AWPVector3(); 22 | vec.v3d = normal; 23 | pointer = createStaticPlaneShapeInC(vec.pointer, constant / _scaling); 24 | CModule.free(vec.pointer); 25 | super(pointer, 8); 26 | } 27 | 28 | public function get normal():Vector3D { 29 | return _normal; 30 | } 31 | 32 | public function get constant():Number { 33 | return _constant; 34 | } 35 | } 36 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/collision/shapes/AWPTriangleShape.as: -------------------------------------------------------------------------------- 1 | package awayphysics.collision.shapes 2 | { 3 | import AWPC_Run.CModule; 4 | import AWPC_Run.createTriangleShapeInC; 5 | import awayphysics.math.AWPVector3; 6 | import flash.geom.Vector3D; 7 | 8 | public class AWPTriangleShape extends AWPCollisionShape 9 | { 10 | private var _point0:Vector3D; 11 | private var _point1:Vector3D; 12 | private var _point2:Vector3D; 13 | 14 | public function AWPTriangleShape(p0:Vector3D, p1:Vector3D, p2:Vector3D) 15 | { 16 | _point0 = p0.clone(); 17 | _point1 = p1.clone(); 18 | _point2 = p2.clone(); 19 | var vec1:AWPVector3 = new AWPVector3(); 20 | vec1.sv3d = p0; 21 | var vec2:AWPVector3 = new AWPVector3(); 22 | vec2.sv3d = p1; 23 | var vec3:AWPVector3 = new AWPVector3(); 24 | vec3.sv3d = p2; 25 | pointer = createTriangleShapeInC(vec1.pointer, vec2.pointer, vec3.pointer); 26 | CModule.free(vec1.pointer); 27 | CModule.free(vec2.pointer); 28 | CModule.free(vec3.pointer); 29 | super(pointer, 6); 30 | } 31 | 32 | public function get point0():Vector3D{ 33 | return _point0; 34 | } 35 | 36 | public function get point1():Vector3D{ 37 | return _point1; 38 | } 39 | 40 | public function get point2():Vector3D{ 41 | return _point2; 42 | } 43 | } 44 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/data/AWPCollisionFilterGroups.as: -------------------------------------------------------------------------------- 1 | package awayphysics.data { 2 | public class AWPCollisionFilterGroups { 3 | public static const DefaultFilter : int = 1; 4 | public static const StaticFilter : int = 2; 5 | public static const KinematicFilter : int = 4; 6 | public static const DebrisFilter : int = 8; 7 | public static const SensorTrigger : int = 16; 8 | public static const CharacterFilter : int = 32; 9 | public static const AllFilter : int = -1; 10 | // all bits sets: DefaultFilter | StaticFilter | KinematicFilter | DebrisFilter | SensorTrigger 11 | } 12 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/data/AWPCollisionFlags.as: -------------------------------------------------------------------------------- 1 | package awayphysics.data { 2 | public class AWPCollisionFlags { 3 | public static const CF_STATIC_OBJECT : int = 1; 4 | public static const CF_KINEMATIC_OBJECT : int = 2; 5 | public static const CF_NO_CONTACT_RESPONSE : int = 4; 6 | public static const CF_CUSTOM_MATERIAL_CALLBACK : int = 8; 7 | public static const CF_CHARACTER_OBJECT : int = 16; 8 | public static const CF_DISABLE_VISUALIZE_OBJECT : int = 32; 9 | } 10 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/data/AWPCollisionObjectTypes.as: -------------------------------------------------------------------------------- 1 | package awayphysics.data { 2 | public class AWPCollisionObjectTypes { 3 | public static const CO_COLLISION_OBJECT : int = 1; 4 | public static const CO_RIGID_BODY : int = 2; 5 | public static const CO_GHOST_OBJECT : int = 4; 6 | public static const CO_SOFT_BODY : int = 8; 7 | public static const CO_HF_FLUID : int = 16; 8 | public static const CO_USER_TYPE : int = 32; 9 | } 10 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/data/AWPCollisionShapeType.as: -------------------------------------------------------------------------------- 1 | package awayphysics.data { 2 | public class AWPCollisionShapeType { 3 | public static const BOX_SHAPE : int = 0; 4 | public static const SPHERE_SHAPE : int = 1; 5 | public static const CYLINDER_SHAPE : int = 2; 6 | public static const CAPSULE_SHAPE : int = 3; 7 | public static const CONE_SHAPE : int = 4; 8 | public static const CONVEX_HULL_SHAPE : int = 5; 9 | public static const TRIANGLE_SHAPE : int = 6; 10 | public static const COMPOUND_SHAPE : int = 7; 11 | public static const STATIC_PLANE : int = 8; 12 | public static const TRIANGLE_MESH_SHAPE : int = 9; 13 | public static const HEIGHT_FIELD_TERRAIN : int = 10; 14 | } 15 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/data/AWPTypedConstraintType.as: -------------------------------------------------------------------------------- 1 | package awayphysics.data 2 | { 3 | public class AWPTypedConstraintType 4 | { 5 | public static const POINT2POINT_CONSTRAINT_TYPE : int = 0; 6 | public static const HINGE_CONSTRAINT_TYPE : int = 1; 7 | public static const CONETWIST_CONSTRAINT_TYPE : int = 2; 8 | public static const D6_CONSTRAINT_TYPE : int = 3; 9 | } 10 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/dynamics/constraintsolver/AWPPoint2PointConstraint.as: -------------------------------------------------------------------------------- 1 | package awayphysics.dynamics.constraintsolver { 2 | import AWPC_Run.CModule; 3 | import AWPC_Run.createP2PConstraint1InC; 4 | import AWPC_Run.createP2PConstraint2InC; 5 | import awayphysics.dynamics.AWPRigidBody; 6 | import awayphysics.math.AWPVector3; 7 | 8 | import flash.geom.Vector3D; 9 | 10 | public class AWPPoint2PointConstraint extends AWPTypedConstraint { 11 | 12 | private var _pivotInA:Vector3D; 13 | private var _pivotInB:Vector3D; 14 | 15 | public function AWPPoint2PointConstraint(rbA : AWPRigidBody, pivotInA : Vector3D, rbB : AWPRigidBody = null, pivotInB : Vector3D = null) { 16 | super(0); 17 | m_rbA = rbA; 18 | m_rbB = rbB; 19 | 20 | _pivotInA = pivotInA; 21 | _pivotInB = pivotInB; 22 | 23 | if (rbB) { 24 | var vec1:AWPVector3 = new AWPVector3(); 25 | vec1.sv3d = _pivotInA; 26 | var vec2:AWPVector3 = new AWPVector3(); 27 | vec2.sv3d = _pivotInB; 28 | pointer = createP2PConstraint2InC(rbA.pointer, rbB.pointer, vec1.pointer, vec2.pointer); 29 | CModule.free(vec1.pointer); 30 | CModule.free(vec2.pointer); 31 | } else { 32 | vec1 = new AWPVector3(); 33 | vec1.sv3d = _pivotInA; 34 | pointer = createP2PConstraint1InC(rbA.pointer, vec1.pointer); 35 | CModule.free(vec1.pointer); 36 | } 37 | } 38 | 39 | public function get pivotInA():Vector3D { 40 | return _pivotInA; 41 | } 42 | 43 | public function get pivotInB():Vector3D { 44 | return _pivotInB; 45 | } 46 | } 47 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/dynamics/constraintsolver/AWPTypedConstraint.as: -------------------------------------------------------------------------------- 1 | package awayphysics.dynamics.constraintsolver { 2 | import AWPC_Run.disposeConstraintInC; 3 | 4 | import awayphysics.AWPBase; 5 | import awayphysics.dynamics.AWPRigidBody; 6 | 7 | public class AWPTypedConstraint extends AWPBase { 8 | protected var m_rbA : AWPRigidBody; 9 | protected var m_rbB : AWPRigidBody; 10 | 11 | protected var m_constraintType:int; 12 | 13 | public function AWPTypedConstraint(type:int) { 14 | m_constraintType = type; 15 | } 16 | 17 | public function get rigidBodyA() : AWPRigidBody { 18 | return m_rbA; 19 | } 20 | 21 | public function get rigidBodyB() : AWPRigidBody { 22 | return m_rbB; 23 | } 24 | 25 | public function get constraintType():int { 26 | return m_constraintType; 27 | } 28 | 29 | public function dispose():void { 30 | if (!_cleanup) { 31 | _cleanup = true; 32 | disposeConstraintInC(pointer); 33 | } 34 | } 35 | } 36 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/dynamics/vehicle/AWPRaycastInfo.as: -------------------------------------------------------------------------------- 1 | package awayphysics.dynamics.vehicle { 2 | import AWPC_Run.CModule; 3 | import awayphysics.AWPBase; 4 | import awayphysics.math.AWPVector3; 5 | 6 | import flash.geom.Vector3D; 7 | 8 | public class AWPRaycastInfo extends AWPBase { 9 | private var m_contactNormalWS : AWPVector3; 10 | private var m_contactPointWS : AWPVector3; 11 | private var m_hardPointWS : AWPVector3; 12 | private var m_wheelDirectionWS : AWPVector3; 13 | private var m_wheelAxleWS : AWPVector3; 14 | 15 | public function AWPRaycastInfo(ptr : uint) { 16 | pointer = ptr; 17 | 18 | m_contactNormalWS = new AWPVector3(ptr + 0); 19 | m_contactPointWS = new AWPVector3(ptr + 16); 20 | m_hardPointWS = new AWPVector3(ptr + 36); 21 | m_wheelDirectionWS = new AWPVector3(ptr + 52); 22 | m_wheelAxleWS = new AWPVector3(ptr + 68); 23 | } 24 | 25 | public function get contactNormalWS() : Vector3D { 26 | return m_contactNormalWS.v3d; 27 | } 28 | 29 | public function get contactPointWS() : Vector3D { 30 | return m_contactPointWS.sv3d; 31 | } 32 | 33 | public function get hardPointWS() : Vector3D { 34 | return m_hardPointWS.sv3d; 35 | } 36 | 37 | public function get wheelDirectionWS() : Vector3D { 38 | return m_wheelDirectionWS.v3d; 39 | } 40 | 41 | public function get wheelAxleWS() : Vector3D { 42 | return m_wheelAxleWS.v3d; 43 | } 44 | 45 | public function get suspensionLength() : Number { 46 | return CModule.readFloat(pointer + 32) * _scaling; 47 | } 48 | 49 | public function get isInContact() : Boolean { 50 | return CModule.read8(pointer + 84) == 1; 51 | } 52 | } 53 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/dynamics/vehicle/AWPVehicleTuning.as: -------------------------------------------------------------------------------- 1 | package awayphysics.dynamics.vehicle { 2 | public class AWPVehicleTuning { 3 | public var suspensionStiffness : Number; 4 | public var suspensionCompression : Number; 5 | public var suspensionDamping : Number; 6 | public var maxSuspensionTravelCm : Number; 7 | public var frictionSlip : Number; 8 | public var maxSuspensionForce : Number; 9 | 10 | public function AWPVehicleTuning() { 11 | suspensionStiffness = 5.88; 12 | suspensionCompression = 0.83; 13 | suspensionDamping = 0.88; 14 | maxSuspensionTravelCm = 500; 15 | frictionSlip = 10.5; 16 | maxSuspensionForce = 6000; 17 | } 18 | } 19 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/events/AWPEvent.as: -------------------------------------------------------------------------------- 1 | package awayphysics.events { 2 | import awayphysics.collision.dispatch.AWPCollisionObject; 3 | import awayphysics.collision.dispatch.AWPManifoldPoint; 4 | 5 | import flash.events.Event; 6 | 7 | public class AWPEvent extends Event { 8 | /** 9 | * Dispatched when the body occur collision 10 | */ 11 | public static const COLLISION_ADDED : String = "collisionAdded"; 12 | /** 13 | * Dispatched when ray collide 14 | */ 15 | public static const RAY_CAST : String = "rayCast"; 16 | /** 17 | * stored which object is collide with target object 18 | */ 19 | public var collisionObject : AWPCollisionObject; 20 | /** 21 | * stored collision point, normal, impulse etc. 22 | */ 23 | public var manifoldPoint : AWPManifoldPoint; 24 | 25 | public function AWPEvent(type : String) { 26 | super(type); 27 | } 28 | } 29 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/extend/AWPTerrain.as: -------------------------------------------------------------------------------- 1 | package awayphysics.extend { 2 | import away3d.extrusions.Elevation; 3 | import away3d.materials.MaterialBase; 4 | 5 | import flash.display.BitmapData; 6 | 7 | public class AWPTerrain extends Elevation { 8 | private var _segmentsW : int; 9 | private var _segmentsH : int; 10 | private var _maxHeight : Number; 11 | private var _heights : Vector.; 12 | 13 | public function AWPTerrain(material : MaterialBase, heightMap : BitmapData, width : Number = 1000, height : Number = 100, depth : Number = 1000, segmentsW : uint = 30, segmentsH : uint = 30, maxElevation : uint = 255, minElevation : uint = 0, smoothMap : Boolean = false) { 14 | super(material, heightMap, width, height, depth, segmentsW, segmentsH, maxElevation, minElevation, smoothMap); 15 | 16 | _segmentsW = segmentsW; 17 | _segmentsH = segmentsH; 18 | _maxHeight = maxElevation; 19 | 20 | var _minW : Number = -width / 2; 21 | var _minH : Number = -depth / 2; 22 | var _dw : Number = width / segmentsW; 23 | var _dh : Number = depth / segmentsH; 24 | 25 | _heights = new Vector.(); 26 | for ( var iy : int = 0; iy < _segmentsH; iy++ ) { 27 | for ( var ix : int = 0; ix < _segmentsW; ix++ ) { 28 | _heights.push(this.getHeightAt(_minW + (_dw * ix), _minH + (_dh * iy))); 29 | } 30 | } 31 | } 32 | 33 | public function get sw() : int { 34 | return _segmentsW; 35 | } 36 | 37 | public function get sh() : int { 38 | return _segmentsH; 39 | } 40 | 41 | public function get lw() : Number { 42 | return this.width; 43 | } 44 | 45 | public function get lh() : Number { 46 | return this.depth; 47 | } 48 | 49 | public function get maxHeight() : Number { 50 | return _maxHeight; 51 | } 52 | 53 | public function get heights() : Vector. { 54 | return _heights; 55 | } 56 | } 57 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/math/AWPMath.as: -------------------------------------------------------------------------------- 1 | package awayphysics.math 2 | { 3 | import flash.geom.Matrix3D; 4 | import flash.geom.Vector3D; 5 | 6 | public class AWPMath 7 | { 8 | public static const RADIANS_TO_DEGREES : Number = 180 / Math.PI; 9 | public static const DEGREES_TO_RADIANS : Number = Math.PI / 180; 10 | 11 | public static function matrix2euler( m:Matrix3D ) : Vector3D 12 | { 13 | return m.decompose()[1]; 14 | } 15 | 16 | public static function euler2matrix( ang:Vector3D ) : Matrix3D 17 | { 18 | var m:Matrix3D = new Matrix3D(); 19 | var data:Vector. = Vector.([new Vector3D(), ang, new Vector3D(1, 1, 1)]); 20 | m.recompose(data); 21 | return m; 22 | } 23 | 24 | public static function vectorMultiply(v1:Vector3D, v2:Vector3D):Vector3D { 25 | return new Vector3D(v1.x * v2.x, v1.y * v2.y, v1.z * v2.z); 26 | } 27 | 28 | public static function degrees2radiansV3D(degrees:Vector3D):Vector3D { 29 | var deg:Vector3D = degrees.clone(); 30 | deg.x *= AWPMath.DEGREES_TO_RADIANS; 31 | deg.y *= AWPMath.DEGREES_TO_RADIANS; 32 | deg.z *= AWPMath.DEGREES_TO_RADIANS; 33 | return deg; 34 | } 35 | public static function radians2degreesV3D(radians:Vector3D):Vector3D { 36 | var rad:Vector3D = radians.clone(); 37 | rad.x *= AWPMath.RADIANS_TO_DEGREES; 38 | rad.y *= AWPMath.RADIANS_TO_DEGREES; 39 | rad.z *= AWPMath.RADIANS_TO_DEGREES; 40 | return rad; 41 | } 42 | } 43 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/math/AWPMatrix3x3.as: -------------------------------------------------------------------------------- 1 | package awayphysics.math { 2 | import flash.geom.Matrix3D; 3 | import flash.geom.Vector3D; 4 | import AWPC_Run.matrix3x3; 5 | import awayphysics.AWPBase; 6 | 7 | public class AWPMatrix3x3 extends AWPBase { 8 | private var _row1 : AWPVector3; 9 | private var _row2 : AWPVector3; 10 | private var _row3 : AWPVector3; 11 | 12 | private var _m3d : Matrix3D = new Matrix3D(); 13 | private var _v3d : Vector3D = new Vector3D(); 14 | 15 | public function AWPMatrix3x3(ptr : uint = 0) { 16 | if(ptr>0){ 17 | pointer = ptr; 18 | }else{ 19 | pointer = matrix3x3(); 20 | } 21 | _row1 = new AWPVector3(pointer + 0); 22 | _row2 = new AWPVector3(pointer + 16); 23 | _row3 = new AWPVector3(pointer + 32); 24 | } 25 | 26 | public function get row1():Vector3D { 27 | return _row1.v3d; 28 | } 29 | 30 | public function get row2():Vector3D { 31 | return _row2.v3d; 32 | } 33 | 34 | public function get row3():Vector3D { 35 | return _row3.v3d; 36 | } 37 | 38 | public function get column1():Vector3D { 39 | return new Vector3D(_row1.x, _row2.x, _row3.x); 40 | } 41 | 42 | public function get column2():Vector3D { 43 | return new Vector3D(_row1.y, _row2.y, _row3.y); 44 | } 45 | 46 | public function get column3():Vector3D { 47 | return new Vector3D(_row1.z, _row2.z, _row3.z); 48 | } 49 | 50 | public function get m3d() : Matrix3D { 51 | _m3d.copyRowFrom(0, _row1.v3d); 52 | _m3d.copyRowFrom(1, _row2.v3d); 53 | _m3d.copyRowFrom(2, _row3.v3d); 54 | return _m3d; 55 | } 56 | 57 | public function set m3d(m : Matrix3D) : void { 58 | _v3d.setTo(m.rawData[0], m.rawData[4], m.rawData[8]); 59 | _row1.v3d = _v3d; 60 | _v3d.setTo(m.rawData[1], m.rawData[5], m.rawData[9]); 61 | _row2.v3d = _v3d; 62 | _v3d.setTo(m.rawData[2], m.rawData[6], m.rawData[10]); 63 | _row3.v3d = _v3d; 64 | } 65 | } 66 | } -------------------------------------------------------------------------------- /AwayPhysics/src/awayphysics/math/AWPVector3.as: -------------------------------------------------------------------------------- 1 | package awayphysics.math { 2 | import AWPC_Run.vector3; 3 | import AWPC_Run.CModule; 4 | import awayphysics.AWPBase; 5 | import flash.geom.Vector3D; 6 | 7 | public class AWPVector3 extends AWPBase { 8 | private var _v3d : Vector3D = new Vector3D(); 9 | 10 | public function AWPVector3(ptr : uint = 0) { 11 | if(ptr>0){ 12 | pointer = ptr; 13 | }else{ 14 | pointer = vector3(); 15 | this.x=0; 16 | this.y=0; 17 | this.z=0; 18 | } 19 | } 20 | 21 | public function get x() : Number { 22 | return CModule.readFloat(pointer + 0); 23 | } 24 | 25 | public function set x(v : Number) : void { 26 | CModule.writeFloat(pointer + 0, v); 27 | } 28 | 29 | public function get y() : Number { 30 | return CModule.readFloat(pointer + 4); 31 | } 32 | 33 | public function set y(v : Number) : void { 34 | CModule.writeFloat(pointer + 4, v); 35 | } 36 | 37 | public function get z() : Number { 38 | return CModule.readFloat(pointer + 8); 39 | } 40 | 41 | public function set z(v : Number) : void { 42 | CModule.writeFloat(pointer + 8, v); 43 | } 44 | 45 | public function get v3d() : Vector3D { 46 | _v3d.setTo(x, y, z); 47 | return _v3d; 48 | } 49 | 50 | public function set v3d(v : Vector3D) : void { 51 | x = v.x; 52 | y = v.y; 53 | z = v.z; 54 | } 55 | 56 | public function get sv3d() : Vector3D { 57 | _v3d.setTo(x, y, z); 58 | _v3d.scaleBy(_scaling); 59 | return _v3d; 60 | } 61 | 62 | public function set sv3d(v : Vector3D) : void { 63 | x = v.x / _scaling; 64 | y = v.y / _scaling; 65 | z = v.z / _scaling; 66 | } 67 | } 68 | } -------------------------------------------------------------------------------- /AwayPhysics/src/com/adobe/flascc/Console.as: -------------------------------------------------------------------------------- 1 | package com.adobe.flascc 2 | { 3 | import flash.display.Sprite; 4 | 5 | import AWPC_Run.CModule; 6 | 7 | import awayphysics.collision.dispatch.AWPCollisionObject; 8 | import awayphysics.dynamics.AWPDynamicsWorld; 9 | 10 | public class Console extends Sprite 11 | { 12 | private var _physicsWorld:AWPDynamicsWorld; 13 | 14 | public function Console(physicsWorld:AWPDynamicsWorld) 15 | { 16 | CModule.rootSprite = this; 17 | _physicsWorld = physicsWorld; 18 | } 19 | public function collisionCallback(obj1:uint, mpt:uint, obj2:uint) : void { 20 | var obj:AWPCollisionObject = _physicsWorld.collisionObjects[obj1.toString()]; 21 | if(obj) obj.collisionCallback(mpt,_physicsWorld.collisionObjects[obj2.toString()]); 22 | } 23 | public function rayCastCallback(obj1:uint, mpt:uint, obj2:uint) : void { 24 | var obj:AWPCollisionObject = _physicsWorld.collisionObjects[obj1.toString()]; 25 | if(obj) obj.rayCastCallback(mpt,_physicsWorld.collisionObjects[obj2.toString()]); 26 | } 27 | } 28 | } -------------------------------------------------------------------------------- /Bullet/BulletCollision/BroadphaseCollision/btAxisSweep3.cpp: -------------------------------------------------------------------------------- 1 | 2 | //Bullet Continuous Collision Detection and Physics Library 3 | //Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | 6 | // 7 | // btAxisSweep3 8 | // 9 | // Copyright (c) 2006 Simon Hobbs 10 | // 11 | // This software is provided 'as-is', without any express or implied warranty. In no event will the authors be held liable for any damages arising from the use of this software. 12 | // 13 | // Permission is granted to anyone to use this software for any purpose, including commercial applications, and to alter it and redistribute it freely, subject to the following restrictions: 14 | // 15 | // 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 16 | // 17 | // 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 18 | // 19 | // 3. This notice may not be removed or altered from any source distribution. 20 | #include "btAxisSweep3.h" 21 | 22 | 23 | btAxisSweep3::btAxisSweep3(const btVector3& worldAabbMin,const btVector3& worldAabbMax, unsigned short int maxHandles, btOverlappingPairCache* pairCache, bool disableRaycastAccelerator) 24 | :btAxisSweep3Internal(worldAabbMin,worldAabbMax,0xfffe,0xffff,maxHandles,pairCache,disableRaycastAccelerator) 25 | { 26 | // 1 handle is reserved as sentinel 27 | btAssert(maxHandles > 1 && maxHandles < 32767); 28 | 29 | } 30 | 31 | 32 | bt32BitAxisSweep3::bt32BitAxisSweep3(const btVector3& worldAabbMin,const btVector3& worldAabbMax, unsigned int maxHandles , btOverlappingPairCache* pairCache , bool disableRaycastAccelerator) 33 | :btAxisSweep3Internal(worldAabbMin,worldAabbMax,0xfffffffe,0x7fffffff,maxHandles,pairCache,disableRaycastAccelerator) 34 | { 35 | // 1 handle is reserved as sentinel 36 | btAssert(maxHandles > 1 && maxHandles < 2147483647); 37 | } 38 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btBroadphaseProxy.h" 17 | 18 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btCollisionAlgorithm.h" 17 | #include "btDispatcher.h" 18 | 19 | btCollisionAlgorithm::btCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci) 20 | { 21 | m_dispatcher = ci.m_dispatcher1; 22 | } 23 | 24 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/BroadphaseCollision/btDispatcher.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btDispatcher.h" 17 | 18 | btDispatcher::~btDispatcher() 19 | { 20 | 21 | } 22 | 23 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/BroadphaseCollision/btOverlappingPairCallback.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | Bullet Continuous Collision Detection and Physics Library 4 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 5 | 6 | This software is provided 'as-is', without any express or implied warranty. 7 | In no event will the authors be held liable for any damages arising from the use of this software. 8 | Permission is granted to anyone to use this software for any purpose, 9 | including commercial applications, and to alter it and redistribute it freely, 10 | subject to the following restrictions: 11 | 12 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 13 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 14 | 3. This notice may not be removed or altered from any source distribution. 15 | */ 16 | 17 | #ifndef OVERLAPPING_PAIR_CALLBACK_H 18 | #define OVERLAPPING_PAIR_CALLBACK_H 19 | 20 | class btDispatcher; 21 | struct btBroadphasePair; 22 | 23 | ///The btOverlappingPairCallback class is an additional optional broadphase user callback for adding/removing overlapping pairs, similar interface to btOverlappingPairCache. 24 | class btOverlappingPairCallback 25 | { 26 | public: 27 | virtual ~btOverlappingPairCallback() 28 | { 29 | 30 | } 31 | 32 | virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) = 0; 33 | 34 | virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1,btDispatcher* dispatcher) = 0; 35 | 36 | virtual void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy0,btDispatcher* dispatcher) = 0; 37 | 38 | }; 39 | 40 | #endif //OVERLAPPING_PAIR_CALLBACK_H 41 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/SphereTriangleDetector.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SPHERE_TRIANGLE_DETECTOR_H 17 | #define BT_SPHERE_TRIANGLE_DETECTOR_H 18 | 19 | #include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" 20 | 21 | 22 | 23 | class btSphereShape; 24 | class btTriangleShape; 25 | 26 | 27 | 28 | /// sphere-triangle to match the btDiscreteCollisionDetectorInterface 29 | struct SphereTriangleDetector : public btDiscreteCollisionDetectorInterface 30 | { 31 | virtual void getClosestPoints(const ClosestPointInput& input,Result& output,class btIDebugDraw* debugDraw,bool swapResults=false); 32 | 33 | SphereTriangleDetector(btSphereShape* sphere,btTriangleShape* triangle, btScalar contactBreakingThreshold); 34 | 35 | virtual ~SphereTriangleDetector() {}; 36 | 37 | bool collide(const btVector3& sphereCenter,btVector3 &point, btVector3& resultNormal, btScalar& depth, btScalar &timeOfImpact, btScalar contactBreakingThreshold); 38 | 39 | private: 40 | 41 | 42 | bool pointInTriangle(const btVector3 vertices[], const btVector3 &normal, btVector3 *p ); 43 | bool facecontains(const btVector3 &p,const btVector3* vertices,btVector3& normal); 44 | 45 | btSphereShape* m_sphere; 46 | btTriangleShape* m_triangle; 47 | btScalar m_contactBreakingThreshold; 48 | 49 | }; 50 | #endif //BT_SPHERE_TRIANGLE_DETECTOR_H 51 | 52 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btActivatingCollisionAlgorithm.h" 17 | #include "btCollisionDispatcher.h" 18 | #include "btCollisionObject.h" 19 | 20 | btActivatingCollisionAlgorithm::btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci) 21 | :btCollisionAlgorithm(ci) 22 | //, 23 | //m_colObj0(0), 24 | //m_colObj1(0) 25 | { 26 | } 27 | btActivatingCollisionAlgorithm::btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* ,const btCollisionObjectWrapper* ) 28 | :btCollisionAlgorithm(ci) 29 | //, 30 | //m_colObj0(0), 31 | //m_colObj1(0) 32 | { 33 | // if (ci.m_dispatcher1->needsCollision(colObj0,colObj1)) 34 | // { 35 | // m_colObj0 = colObj0; 36 | // m_colObj1 = colObj1; 37 | // 38 | // m_colObj0->activate(); 39 | // m_colObj1->activate(); 40 | // } 41 | } 42 | 43 | btActivatingCollisionAlgorithm::~btActivatingCollisionAlgorithm() 44 | { 45 | // m_colObj0->activate(); 46 | // m_colObj1->activate(); 47 | } 48 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef __BT_ACTIVATING_COLLISION_ALGORITHM_H 17 | #define __BT_ACTIVATING_COLLISION_ALGORITHM_H 18 | 19 | #include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h" 20 | 21 | ///This class is not enabled yet (work-in-progress) to more aggressively activate objects. 22 | class btActivatingCollisionAlgorithm : public btCollisionAlgorithm 23 | { 24 | // btCollisionObject* m_colObj0; 25 | // btCollisionObject* m_colObj1; 26 | 27 | public: 28 | 29 | btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci); 30 | 31 | btActivatingCollisionAlgorithm (const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap); 32 | 33 | virtual ~btActivatingCollisionAlgorithm(); 34 | 35 | }; 36 | #endif //__BT_ACTIVATING_COLLISION_ALGORITHM_H 37 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btBoxBoxDetector.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Box-Box collision detection re-distributed under the ZLib license with permission from Russell L. Smith 3 | * Original version is from Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. 4 | * All rights reserved. Email: russ@q12.org Web: www.q12.org 5 | 6 | Bullet Continuous Collision Detection and Physics Library 7 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 8 | 9 | This software is provided 'as-is', without any express or implied warranty. 10 | In no event will the authors be held liable for any damages arising from the use of this software. 11 | Permission is granted to anyone to use this software for any purpose, 12 | including commercial applications, and to alter it and redistribute it freely, 13 | subject to the following restrictions: 14 | 15 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 16 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 17 | 3. This notice may not be removed or altered from any source distribution. 18 | */ 19 | #ifndef BT_BOX_BOX_DETECTOR_H 20 | #define BT_BOX_BOX_DETECTOR_H 21 | 22 | 23 | class btBoxShape; 24 | #include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h" 25 | 26 | 27 | /// btBoxBoxDetector wraps the ODE box-box collision detector 28 | /// re-distributed under the Zlib license with permission from Russell L. Smith 29 | struct btBoxBoxDetector : public btDiscreteCollisionDetectorInterface 30 | { 31 | const btBoxShape* m_box1; 32 | const btBoxShape* m_box2; 33 | 34 | public: 35 | 36 | btBoxBoxDetector(const btBoxShape* box1,const btBoxShape* box2); 37 | 38 | virtual ~btBoxBoxDetector() {}; 39 | 40 | virtual void getClosestPoints(const ClosestPointInput& input,Result& output,class btIDebugDraw* debugDraw,bool swapResults=false); 41 | 42 | }; 43 | 44 | #endif //BT_BOX_BOX_DETECTOR_H 45 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btCollisionConfiguration.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_COLLISION_CONFIGURATION 17 | #define BT_COLLISION_CONFIGURATION 18 | 19 | struct btCollisionAlgorithmCreateFunc; 20 | 21 | class btStackAlloc; 22 | class btPoolAllocator; 23 | 24 | ///btCollisionConfiguration allows to configure Bullet collision detection 25 | ///stack allocator size, default collision algorithms and persistent manifold pool size 26 | ///@todo: describe the meaning 27 | class btCollisionConfiguration 28 | { 29 | 30 | public: 31 | 32 | virtual ~btCollisionConfiguration() 33 | { 34 | } 35 | 36 | ///memory pools 37 | virtual btPoolAllocator* getPersistentManifoldPool() = 0; 38 | 39 | virtual btPoolAllocator* getCollisionAlgorithmPool() = 0; 40 | 41 | virtual btStackAlloc* getStackAllocator() = 0; 42 | 43 | virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1) =0; 44 | 45 | }; 46 | 47 | #endif //BT_COLLISION_CONFIGURATION 48 | 49 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btCollisionCreateFunc.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_COLLISION_CREATE_FUNC 17 | #define BT_COLLISION_CREATE_FUNC 18 | 19 | #include "LinearMath/btAlignedObjectArray.h" 20 | class btCollisionAlgorithm; 21 | class btCollisionObject; 22 | struct btCollisionObjectWrapper; 23 | struct btCollisionAlgorithmConstructionInfo; 24 | 25 | ///Used by the btCollisionDispatcher to register and create instances for btCollisionAlgorithm 26 | struct btCollisionAlgorithmCreateFunc 27 | { 28 | bool m_swapped; 29 | 30 | btCollisionAlgorithmCreateFunc() 31 | :m_swapped(false) 32 | { 33 | } 34 | virtual ~btCollisionAlgorithmCreateFunc(){}; 35 | 36 | virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& , const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap) 37 | { 38 | 39 | (void)body0Wrap; 40 | (void)body1Wrap; 41 | return 0; 42 | } 43 | }; 44 | #endif //BT_COLLISION_CREATE_FUNC 45 | 46 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_COLLISION_OBJECT_WRAPPER_H 2 | #define BT_COLLISION_OBJECT_WRAPPER_H 3 | 4 | ///btCollisionObjectWrapperis an internal data structure. 5 | ///Most users can ignore this and use btCollisionObject and btCollisionShape instead 6 | class btCollisionShape; 7 | class btCollisionObject; 8 | class btTransform; 9 | #include "LinearMath/btScalar.h" // for SIMD_FORCE_INLINE definition 10 | 11 | #define BT_DECLARE_STACK_ONLY_OBJECT \ 12 | private: \ 13 | void* operator new(size_t size); \ 14 | void operator delete(void*); 15 | 16 | struct btCollisionObjectWrapper; 17 | struct btCollisionObjectWrapper 18 | { 19 | BT_DECLARE_STACK_ONLY_OBJECT 20 | 21 | private: 22 | btCollisionObjectWrapper(const btCollisionObjectWrapper&); // not implemented. Not allowed. 23 | btCollisionObjectWrapper* operator=(const btCollisionObjectWrapper&); 24 | 25 | public: 26 | const btCollisionObjectWrapper* m_parent; 27 | const btCollisionShape* m_shape; 28 | const btCollisionObject* m_collisionObject; 29 | const btTransform& m_worldTransform; 30 | 31 | btCollisionObjectWrapper(const btCollisionObjectWrapper* parent, const btCollisionShape* shape, const btCollisionObject* collisionObject, const btTransform& worldTransform) 32 | : m_parent(parent), m_shape(shape), m_collisionObject(collisionObject), m_worldTransform(worldTransform) 33 | {} 34 | 35 | SIMD_FORCE_INLINE const btTransform& getWorldTransform() const { return m_worldTransform; } 36 | SIMD_FORCE_INLINE const btCollisionObject* getCollisionObject() const { return m_collisionObject; } 37 | SIMD_FORCE_INLINE const btCollisionShape* getCollisionShape() const { return m_shape; } 38 | }; 39 | 40 | #endif //BT_COLLISION_OBJECT_WRAPPER_H 41 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btEmptyCollisionAlgorithm.h" 17 | 18 | 19 | 20 | btEmptyAlgorithm::btEmptyAlgorithm(const btCollisionAlgorithmConstructionInfo& ci) 21 | : btCollisionAlgorithm(ci) 22 | { 23 | } 24 | 25 | void btEmptyAlgorithm::processCollision (const btCollisionObjectWrapper* ,const btCollisionObjectWrapper* ,const btDispatcherInfo& ,btManifoldResult* ) 26 | { 27 | } 28 | 29 | btScalar btEmptyAlgorithm::calculateTimeOfImpact(btCollisionObject* ,btCollisionObject* ,const btDispatcherInfo& ,btManifoldResult* ) 30 | { 31 | return btScalar(1.); 32 | } 33 | 34 | 35 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionDispatch/btInternalEdgeUtility.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef BT_INTERNAL_EDGE_UTILITY_H 3 | #define BT_INTERNAL_EDGE_UTILITY_H 4 | 5 | #include "LinearMath/btHashMap.h" 6 | #include "LinearMath/btVector3.h" 7 | 8 | #include "BulletCollision/CollisionShapes/btTriangleInfoMap.h" 9 | 10 | ///The btInternalEdgeUtility helps to avoid or reduce artifacts due to wrong collision normals caused by internal edges. 11 | ///See also http://code.google.com/p/bullet/issues/detail?id=27 12 | 13 | class btBvhTriangleMeshShape; 14 | class btCollisionObject; 15 | struct btCollisionObjectWrapper; 16 | class btManifoldPoint; 17 | class btIDebugDraw; 18 | 19 | 20 | 21 | enum btInternalEdgeAdjustFlags 22 | { 23 | BT_TRIANGLE_CONVEX_BACKFACE_MODE = 1, 24 | BT_TRIANGLE_CONCAVE_DOUBLE_SIDED = 2, //double sided options are experimental, single sided is recommended 25 | BT_TRIANGLE_CONVEX_DOUBLE_SIDED = 4 26 | }; 27 | 28 | 29 | ///Call btGenerateInternalEdgeInfo to create triangle info, store in the shape 'userInfo' 30 | void btGenerateInternalEdgeInfo (btBvhTriangleMeshShape*trimeshShape, btTriangleInfoMap* triangleInfoMap); 31 | 32 | 33 | ///Call the btFixMeshNormal to adjust the collision normal, using the triangle info map (generated using btGenerateInternalEdgeInfo) 34 | ///If this info map is missing, or the triangle is not store in this map, nothing will be done 35 | void btAdjustInternalEdgeContacts(btManifoldPoint& cp, const btCollisionObjectWrapper* trimeshColObj0Wrap,const btCollisionObjectWrapper* otherColObj1Wrap, int partId0, int index0, int normalAdjustFlags = 0); 36 | 37 | ///Enable the BT_INTERNAL_EDGE_DEBUG_DRAW define and call btSetDebugDrawer, to get visual info to see if the internal edge utility works properly. 38 | ///If the utility doesn't work properly, you might have to adjust the threshold values in btTriangleInfoMap 39 | //#define BT_INTERNAL_EDGE_DEBUG_DRAW 40 | 41 | #ifdef BT_INTERNAL_EDGE_DEBUG_DRAW 42 | void btSetDebugDrawer(btIDebugDraw* debugDrawer); 43 | #endif //BT_INTERNAL_EDGE_DEBUG_DRAW 44 | 45 | 46 | #endif //BT_INTERNAL_EDGE_UTILITY_H 47 | 48 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btBox2dShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btBox2dShape.h" 17 | 18 | 19 | //{ 20 | 21 | 22 | void btBox2dShape::getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const 23 | { 24 | btTransformAabb(getHalfExtentsWithoutMargin(),getMargin(),t,aabbMin,aabbMax); 25 | } 26 | 27 | 28 | void btBox2dShape::calculateLocalInertia(btScalar mass,btVector3& inertia) const 29 | { 30 | //btScalar margin = btScalar(0.); 31 | btVector3 halfExtents = getHalfExtentsWithMargin(); 32 | 33 | btScalar lx=btScalar(2.)*(halfExtents.x()); 34 | btScalar ly=btScalar(2.)*(halfExtents.y()); 35 | btScalar lz=btScalar(2.)*(halfExtents.z()); 36 | 37 | inertia.setValue(mass/(btScalar(12.0)) * (ly*ly + lz*lz), 38 | mass/(btScalar(12.0)) * (lx*lx + lz*lz), 39 | mass/(btScalar(12.0)) * (lx*lx + ly*ly)); 40 | 41 | } 42 | 43 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btBoxShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | #include "btBoxShape.h" 16 | 17 | btBoxShape::btBoxShape( const btVector3& boxHalfExtents) 18 | : btPolyhedralConvexShape() 19 | { 20 | m_shapeType = BOX_SHAPE_PROXYTYPE; 21 | 22 | setSafeMargin(boxHalfExtents); 23 | 24 | btVector3 margin(getMargin(),getMargin(),getMargin()); 25 | m_implicitShapeDimensions = (boxHalfExtents * m_localScaling) - margin; 26 | }; 27 | 28 | 29 | 30 | 31 | void btBoxShape::getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const 32 | { 33 | btTransformAabb(getHalfExtentsWithoutMargin(),getMargin(),t,aabbMin,aabbMax); 34 | } 35 | 36 | 37 | void btBoxShape::calculateLocalInertia(btScalar mass,btVector3& inertia) const 38 | { 39 | //btScalar margin = btScalar(0.); 40 | btVector3 halfExtents = getHalfExtentsWithMargin(); 41 | 42 | btScalar lx=btScalar(2.)*(halfExtents.x()); 43 | btScalar ly=btScalar(2.)*(halfExtents.y()); 44 | btScalar lz=btScalar(2.)*(halfExtents.z()); 45 | 46 | inertia.setValue(mass/(btScalar(12.0)) * (ly*ly + lz*lz), 47 | mass/(btScalar(12.0)) * (lx*lx + lz*lz), 48 | mass/(btScalar(12.0)) * (lx*lx + ly*ly)); 49 | 50 | } 51 | 52 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btCollisionMargin.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_COLLISION_MARGIN_H 17 | #define BT_COLLISION_MARGIN_H 18 | 19 | ///The CONVEX_DISTANCE_MARGIN is a default collision margin for convex collision shapes derived from btConvexInternalShape. 20 | ///This collision margin is used by Gjk and some other algorithms 21 | ///Note that when creating small objects, you need to make sure to set a smaller collision margin, using the 'setMargin' API 22 | #define CONVEX_DISTANCE_MARGIN btScalar(0.04)// btScalar(0.1)//;//btScalar(0.01) 23 | 24 | 25 | 26 | #endif //BT_COLLISION_MARGIN_H 27 | 28 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btConcaveShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #include "btConcaveShape.h" 18 | 19 | btConcaveShape::btConcaveShape() : m_collisionMargin(btScalar(0.)) 20 | { 21 | 22 | } 23 | 24 | btConcaveShape::~btConcaveShape() 25 | { 26 | 27 | } 28 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btConcaveShape.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_CONCAVE_SHAPE_H 17 | #define BT_CONCAVE_SHAPE_H 18 | 19 | #include "btCollisionShape.h" 20 | #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" // for the types 21 | #include "btTriangleCallback.h" 22 | 23 | /// PHY_ScalarType enumerates possible scalar types. 24 | /// See the btStridingMeshInterface or btHeightfieldTerrainShape for its use 25 | typedef enum PHY_ScalarType { 26 | PHY_FLOAT, 27 | PHY_DOUBLE, 28 | PHY_INTEGER, 29 | PHY_SHORT, 30 | PHY_FIXEDPOINT88, 31 | PHY_UCHAR 32 | } PHY_ScalarType; 33 | 34 | ///The btConcaveShape class provides an interface for non-moving (static) concave shapes. 35 | ///It has been implemented by the btStaticPlaneShape, btBvhTriangleMeshShape and btHeightfieldTerrainShape. 36 | ATTRIBUTE_ALIGNED16(class) btConcaveShape : public btCollisionShape 37 | { 38 | protected: 39 | btScalar m_collisionMargin; 40 | 41 | public: 42 | BT_DECLARE_ALIGNED_ALLOCATOR(); 43 | 44 | btConcaveShape(); 45 | 46 | virtual ~btConcaveShape(); 47 | 48 | virtual void processAllTriangles(btTriangleCallback* callback,const btVector3& aabbMin,const btVector3& aabbMax) const = 0; 49 | 50 | virtual btScalar getMargin() const { 51 | return m_collisionMargin; 52 | } 53 | virtual void setMargin(btScalar collisionMargin) 54 | { 55 | m_collisionMargin = collisionMargin; 56 | } 57 | 58 | 59 | 60 | }; 61 | 62 | #endif //BT_CONCAVE_SHAPE_H 63 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btConvexPolyhedron.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2011 Advanced Micro Devices, Inc. http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | ///This file was written by Erwin Coumans 18 | 19 | 20 | #ifndef _BT_POLYHEDRAL_FEATURES_H 21 | #define _BT_POLYHEDRAL_FEATURES_H 22 | 23 | #include "LinearMath/btTransform.h" 24 | #include "LinearMath/btAlignedObjectArray.h" 25 | 26 | #define TEST_INTERNAL_OBJECTS 1 27 | 28 | 29 | struct btFace 30 | { 31 | btAlignedObjectArray m_indices; 32 | // btAlignedObjectArray m_connectedFaces; 33 | btScalar m_plane[4]; 34 | }; 35 | 36 | 37 | ATTRIBUTE_ALIGNED16(class) btConvexPolyhedron 38 | { 39 | public: 40 | 41 | BT_DECLARE_ALIGNED_ALLOCATOR(); 42 | 43 | btConvexPolyhedron(); 44 | virtual ~btConvexPolyhedron(); 45 | 46 | btAlignedObjectArray m_vertices; 47 | btAlignedObjectArray m_faces; 48 | btAlignedObjectArray m_uniqueEdges; 49 | 50 | btVector3 m_localCenter; 51 | btVector3 m_extents; 52 | btScalar m_radius; 53 | btVector3 mC; 54 | btVector3 mE; 55 | 56 | void initialize(); 57 | bool testContainment() const; 58 | 59 | void project(const btTransform& trans, const btVector3& dir, btScalar& minProj, btScalar& maxProj, btVector3& witnesPtMin,btVector3& witnesPtMax) const; 60 | }; 61 | 62 | 63 | #endif //_BT_POLYHEDRAL_FEATURES_H 64 | 65 | 66 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btEmptyShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btEmptyShape.h" 17 | 18 | 19 | #include "btCollisionShape.h" 20 | 21 | 22 | btEmptyShape::btEmptyShape() : btConcaveShape () 23 | { 24 | m_shapeType = EMPTY_SHAPE_PROXYTYPE; 25 | } 26 | 27 | 28 | btEmptyShape::~btEmptyShape() 29 | { 30 | } 31 | 32 | 33 | ///getAabb's default implementation is brute force, expected derived classes to implement a fast dedicated version 34 | void btEmptyShape::getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const 35 | { 36 | btVector3 margin(getMargin(),getMargin(),getMargin()); 37 | 38 | aabbMin = t.getOrigin() - margin; 39 | 40 | aabbMax = t.getOrigin() + margin; 41 | 42 | } 43 | 44 | void btEmptyShape::calculateLocalInertia(btScalar ,btVector3& ) const 45 | { 46 | btAssert(0); 47 | } 48 | 49 | 50 | 51 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btMaterial.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | /// This file was created by Alex Silverman 17 | 18 | #ifndef BT_MATERIAL_H 19 | #define BT_MATERIAL_H 20 | 21 | // Material class to be used by btMultimaterialTriangleMeshShape to store triangle properties 22 | class btMaterial 23 | { 24 | // public members so that materials can change due to world events 25 | public: 26 | btScalar m_friction; 27 | btScalar m_restitution; 28 | int pad[2]; 29 | 30 | btMaterial(){} 31 | btMaterial(btScalar fric, btScalar rest) { m_friction = fric; m_restitution = rest; } 32 | }; 33 | 34 | #endif // BT_MATERIAL_H 35 | 36 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #include "btMinkowskiSumShape.h" 18 | 19 | 20 | btMinkowskiSumShape::btMinkowskiSumShape(const btConvexShape* shapeA,const btConvexShape* shapeB) 21 | : btConvexInternalShape (), 22 | m_shapeA(shapeA), 23 | m_shapeB(shapeB) 24 | { 25 | m_shapeType = MINKOWSKI_DIFFERENCE_SHAPE_PROXYTYPE; 26 | m_transA.setIdentity(); 27 | m_transB.setIdentity(); 28 | } 29 | 30 | btVector3 btMinkowskiSumShape::localGetSupportingVertexWithoutMargin(const btVector3& vec)const 31 | { 32 | btVector3 supVertexA = m_transA(m_shapeA->localGetSupportingVertexWithoutMargin(vec*m_transA.getBasis())); 33 | btVector3 supVertexB = m_transB(m_shapeB->localGetSupportingVertexWithoutMargin(-vec*m_transB.getBasis())); 34 | return supVertexA - supVertexB; 35 | } 36 | 37 | void btMinkowskiSumShape::batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const 38 | { 39 | ///@todo: could make recursive use of batching. probably this shape is not used frequently. 40 | for (int i=0;igetMargin() + m_shapeB->getMargin(); 52 | } 53 | 54 | 55 | void btMinkowskiSumShape::calculateLocalInertia(btScalar mass,btVector3& inertia) const 56 | { 57 | (void)mass; 58 | btAssert(0); 59 | inertia.setValue(0,0,0); 60 | } 61 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btShapeHull.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | ///btShapeHull implemented by John McCutchan. 17 | 18 | #ifndef BT_SHAPE_HULL_H 19 | #define BT_SHAPE_HULL_H 20 | 21 | #include "LinearMath/btAlignedObjectArray.h" 22 | #include "BulletCollision/CollisionShapes/btConvexShape.h" 23 | 24 | 25 | ///The btShapeHull class takes a btConvexShape, builds a simplified convex hull using btConvexHull and provides triangle indices and vertices. 26 | ///It can be useful for to simplify a complex convex object and for visualization of a non-polyhedral convex object. 27 | ///It approximates the convex hull using the supporting vertex of 42 directions. 28 | ATTRIBUTE_ALIGNED16(class) btShapeHull 29 | { 30 | protected: 31 | 32 | btAlignedObjectArray m_vertices; 33 | btAlignedObjectArray m_indices; 34 | unsigned int m_numIndices; 35 | const btConvexShape* m_shape; 36 | 37 | static btVector3* getUnitSpherePoints(); 38 | 39 | public: 40 | BT_DECLARE_ALIGNED_ALLOCATOR(); 41 | 42 | btShapeHull (const btConvexShape* shape); 43 | ~btShapeHull (); 44 | 45 | bool buildHull (btScalar margin); 46 | 47 | int numTriangles () const; 48 | int numVertices () const; 49 | int numIndices () const; 50 | 51 | const btVector3* getVertexPointer() const 52 | { 53 | return &m_vertices[0]; 54 | } 55 | const unsigned int* getIndexPointer() const 56 | { 57 | return &m_indices[0]; 58 | } 59 | }; 60 | 61 | #endif //BT_SHAPE_HULL_H 62 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btTriangleBuffer.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btTriangleBuffer.h" 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | void btTriangleBuffer::processTriangle(btVector3* triangle,int partId,int triangleIndex) 25 | { 26 | btTriangle tri; 27 | tri.m_vertex0 = triangle[0]; 28 | tri.m_vertex1 = triangle[1]; 29 | tri.m_vertex2 = triangle[2]; 30 | tri.m_partId = partId; 31 | tri.m_triangleIndex = triangleIndex; 32 | 33 | m_triangleBuffer.push_back(tri); 34 | } 35 | 36 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btTriangleBuffer.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_TRIANGLE_BUFFER_H 17 | #define BT_TRIANGLE_BUFFER_H 18 | 19 | #include "btTriangleCallback.h" 20 | #include "LinearMath/btAlignedObjectArray.h" 21 | 22 | struct btTriangle 23 | { 24 | btVector3 m_vertex0; 25 | btVector3 m_vertex1; 26 | btVector3 m_vertex2; 27 | int m_partId; 28 | int m_triangleIndex; 29 | }; 30 | 31 | ///The btTriangleBuffer callback can be useful to collect and store overlapping triangles between AABB and concave objects that support 'processAllTriangles' 32 | ///Example usage of this class: 33 | /// btTriangleBuffer triBuf; 34 | /// concaveShape->processAllTriangles(&triBuf,aabbMin, aabbMax); 35 | /// for (int i=0;i m_triangleBuffer; 44 | 45 | public: 46 | 47 | 48 | virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex); 49 | 50 | int getNumTriangles() const 51 | { 52 | return int(m_triangleBuffer.size()); 53 | } 54 | 55 | const btTriangle& getTriangle(int index) const 56 | { 57 | return m_triangleBuffer[index]; 58 | } 59 | 60 | void clearBuffer() 61 | { 62 | m_triangleBuffer.clear(); 63 | } 64 | 65 | }; 66 | 67 | 68 | #endif //BT_TRIANGLE_BUFFER_H 69 | 70 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btTriangleCallback.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btTriangleCallback.h" 17 | 18 | btTriangleCallback::~btTriangleCallback() 19 | { 20 | 21 | } 22 | 23 | 24 | btInternalTriangleIndexCallback::~btInternalTriangleIndexCallback() 25 | { 26 | 27 | } 28 | 29 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/CollisionShapes/btTriangleCallback.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2009 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_TRIANGLE_CALLBACK_H 17 | #define BT_TRIANGLE_CALLBACK_H 18 | 19 | #include "LinearMath/btVector3.h" 20 | 21 | 22 | ///The btTriangleCallback provides a callback for each overlapping triangle when calling processAllTriangles. 23 | ///This callback is called by processAllTriangles for all btConcaveShape derived class, such as btBvhTriangleMeshShape, btStaticPlaneShape and btHeightfieldTerrainShape. 24 | class btTriangleCallback 25 | { 26 | public: 27 | 28 | virtual ~btTriangleCallback(); 29 | virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex) = 0; 30 | }; 31 | 32 | class btInternalTriangleIndexCallback 33 | { 34 | public: 35 | 36 | virtual ~btInternalTriangleIndexCallback(); 37 | virtual void internalProcessTriangleIndex(btVector3* triangle,int partId,int triangleIndex) = 0; 38 | }; 39 | 40 | 41 | 42 | #endif //BT_TRIANGLE_CALLBACK_H 43 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp -------------------------------------------------------------------------------- /Bullet/BulletCollision/Gimpact/btGImpactMassUtil.h: -------------------------------------------------------------------------------- 1 | /*! \file btGImpactMassUtil.h 2 | \author Francisco Leon Najera 3 | */ 4 | /* 5 | This source file is part of GIMPACT Library. 6 | 7 | For the latest info, see http://gimpact.sourceforge.net/ 8 | 9 | Copyright (c) 2007 Francisco Leon Najera. C.C. 80087371. 10 | email: projectileman@yahoo.com 11 | 12 | 13 | This software is provided 'as-is', without any express or implied warranty. 14 | In no event will the authors be held liable for any damages arising from the use of this software. 15 | Permission is granted to anyone to use this software for any purpose, 16 | including commercial applications, and to alter it and redistribute it freely, 17 | subject to the following restrictions: 18 | 19 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 20 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 21 | 3. This notice may not be removed or altered from any source distribution. 22 | */ 23 | 24 | 25 | #ifndef GIMPACT_MASS_UTIL_H 26 | #define GIMPACT_MASS_UTIL_H 27 | 28 | #include "LinearMath/btTransform.h" 29 | 30 | 31 | 32 | SIMD_FORCE_INLINE btVector3 gim_inertia_add_transformed( 33 | const btVector3 & source_inertia, const btVector3 & added_inertia, const btTransform & transform) 34 | { 35 | btMatrix3x3 rotatedTensor = transform.getBasis().scaled(added_inertia) * transform.getBasis().transpose(); 36 | 37 | btScalar x2 = transform.getOrigin()[0]; 38 | x2*= x2; 39 | btScalar y2 = transform.getOrigin()[1]; 40 | y2*= y2; 41 | btScalar z2 = transform.getOrigin()[2]; 42 | z2*= z2; 43 | 44 | btScalar ix = rotatedTensor[0][0]*(y2+z2); 45 | btScalar iy = rotatedTensor[1][1]*(x2+z2); 46 | btScalar iz = rotatedTensor[2][2]*(x2+y2); 47 | 48 | return btVector3(source_inertia[0]+ix,source_inertia[1]+iy,source_inertia[2] + iz); 49 | } 50 | 51 | SIMD_FORCE_INLINE btVector3 gim_get_point_inertia(const btVector3 & point, btScalar mass) 52 | { 53 | btScalar x2 = point[0]*point[0]; 54 | btScalar y2 = point[1]*point[1]; 55 | btScalar z2 = point[2]*point[2]; 56 | return btVector3(mass*(y2+z2),mass*(x2+z2),mass*(x2+y2)); 57 | } 58 | 59 | 60 | #endif //GIMPACT_MESH_SHAPE_H 61 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/Gimpact/btGImpactShape.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletCollision/Gimpact/btGImpactShape.h -------------------------------------------------------------------------------- /Bullet/BulletCollision/Gimpact/gim_geometry.h: -------------------------------------------------------------------------------- 1 | #ifndef GIM_GEOMETRY_H_INCLUDED 2 | #define GIM_GEOMETRY_H_INCLUDED 3 | 4 | /*! \file gim_geometry.h 5 | \author Francisco Leon Najera 6 | */ 7 | /* 8 | ----------------------------------------------------------------------------- 9 | This source file is part of GIMPACT Library. 10 | 11 | For the latest info, see http://gimpact.sourceforge.net/ 12 | 13 | Copyright (c) 2006 Francisco Leon Najera. C.C. 80087371. 14 | email: projectileman@yahoo.com 15 | 16 | This library is free software; you can redistribute it and/or 17 | modify it under the terms of EITHER: 18 | (1) The GNU Lesser General Public License as published by the Free 19 | Software Foundation; either version 2.1 of the License, or (at 20 | your option) any later version. The text of the GNU Lesser 21 | General Public License is included with this library in the 22 | file GIMPACT-LICENSE-LGPL.TXT. 23 | (2) The BSD-style license that is included with this library in 24 | the file GIMPACT-LICENSE-BSD.TXT. 25 | (3) The zlib/libpng license that is included with this library in 26 | the file GIMPACT-LICENSE-ZLIB.TXT. 27 | 28 | This library is distributed in the hope that it will be useful, 29 | but WITHOUT ANY WARRANTY; without even the implied warranty of 30 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files 31 | GIMPACT-LICENSE-LGPL.TXT, GIMPACT-LICENSE-ZLIB.TXT and GIMPACT-LICENSE-BSD.TXT for more details. 32 | 33 | ----------------------------------------------------------------------------- 34 | */ 35 | 36 | ///Additional Headers for Collision 37 | #include "gim_basic_geometry_operations.h" 38 | #include "gim_clip_polygon.h" 39 | #include "gim_box_collision.h" 40 | #include "gim_tri_collision.h" 41 | 42 | #endif // GIM_VECTOR_H_INCLUDED 43 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btConvexCast.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btConvexCast.h" 17 | 18 | btConvexCast::~btConvexCast() 19 | { 20 | } 21 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #ifndef BT_CONVEX_PENETRATION_DEPTH_H 18 | #define BT_CONVEX_PENETRATION_DEPTH_H 19 | 20 | class btStackAlloc; 21 | class btVector3; 22 | #include "btSimplexSolverInterface.h" 23 | class btConvexShape; 24 | class btTransform; 25 | 26 | ///ConvexPenetrationDepthSolver provides an interface for penetration depth calculation. 27 | class btConvexPenetrationDepthSolver 28 | { 29 | public: 30 | 31 | virtual ~btConvexPenetrationDepthSolver() {}; 32 | virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 33 | const btConvexShape* convexA,const btConvexShape* convexB, 34 | const btTransform& transA,const btTransform& transB, 35 | btVector3& v, btVector3& pa, btVector3& pb, 36 | class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc 37 | ) = 0; 38 | 39 | 40 | }; 41 | #endif //BT_CONVEX_PENETRATION_DEPTH_H 42 | 43 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | 18 | #ifndef BT_GJK_CONVEX_CAST_H 19 | #define BT_GJK_CONVEX_CAST_H 20 | 21 | #include "BulletCollision/CollisionShapes/btCollisionMargin.h" 22 | 23 | #include "LinearMath/btVector3.h" 24 | #include "btConvexCast.h" 25 | class btConvexShape; 26 | class btMinkowskiSumShape; 27 | #include "btSimplexSolverInterface.h" 28 | 29 | ///GjkConvexCast performs a raycast on a convex object using support mapping. 30 | class btGjkConvexCast : public btConvexCast 31 | { 32 | btSimplexSolverInterface* m_simplexSolver; 33 | const btConvexShape* m_convexA; 34 | const btConvexShape* m_convexB; 35 | 36 | public: 37 | 38 | btGjkConvexCast(const btConvexShape* convexA,const btConvexShape* convexB,btSimplexSolverInterface* simplexSolver); 39 | 40 | /// cast a convex against another convex object 41 | virtual bool calcTimeOfImpact( 42 | const btTransform& fromA, 43 | const btTransform& toA, 44 | const btTransform& fromB, 45 | const btTransform& toB, 46 | CastResult& result); 47 | 48 | }; 49 | 50 | #endif //BT_GJK_CONVEX_CAST_H 51 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | EPA Copyright (c) Ricardo Padrela 2006 6 | 7 | This software is provided 'as-is', without any express or implied warranty. 8 | In no event will the authors be held liable for any damages arising from the use of this software. 9 | Permission is granted to anyone to use this software for any purpose, 10 | including commercial applications, and to alter it and redistribute it freely, 11 | subject to the following restrictions: 12 | 13 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 14 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 15 | 3. This notice may not be removed or altered from any source distribution. 16 | */ 17 | #ifndef BT_GJP_EPA_PENETRATION_DEPTH_H 18 | #define BT_GJP_EPA_PENETRATION_DEPTH_H 19 | 20 | #include "btConvexPenetrationDepthSolver.h" 21 | 22 | ///EpaPenetrationDepthSolver uses the Expanding Polytope Algorithm to 23 | ///calculate the penetration depth between two convex shapes. 24 | class btGjkEpaPenetrationDepthSolver : public btConvexPenetrationDepthSolver 25 | { 26 | public : 27 | 28 | btGjkEpaPenetrationDepthSolver() 29 | { 30 | } 31 | 32 | bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 33 | const btConvexShape* pConvexA, const btConvexShape* pConvexB, 34 | const btTransform& transformA, const btTransform& transformB, 35 | btVector3& v, btVector3& wWitnessOnA, btVector3& wWitnessOnB, 36 | class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc ); 37 | 38 | private : 39 | 40 | }; 41 | 42 | #endif // BT_GJP_EPA_PENETRATION_DEPTH_H 43 | 44 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 17 | #define BT_MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 18 | 19 | #include "btConvexPenetrationDepthSolver.h" 20 | 21 | ///MinkowskiPenetrationDepthSolver implements bruteforce penetration depth estimation. 22 | ///Implementation is based on sampling the depth using support mapping, and using GJK step to get the witness points. 23 | class btMinkowskiPenetrationDepthSolver : public btConvexPenetrationDepthSolver 24 | { 25 | protected: 26 | 27 | static btVector3* getPenetrationDirections(); 28 | 29 | public: 30 | 31 | virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 32 | const btConvexShape* convexA,const btConvexShape* convexB, 33 | const btTransform& transA,const btTransform& transB, 34 | btVector3& v, btVector3& pa, btVector3& pb, 35 | class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc 36 | ); 37 | }; 38 | 39 | #endif //BT_MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 40 | 41 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btPointCollector.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_POINT_COLLECTOR_H 17 | #define BT_POINT_COLLECTOR_H 18 | 19 | #include "btDiscreteCollisionDetectorInterface.h" 20 | 21 | 22 | 23 | struct btPointCollector : public btDiscreteCollisionDetectorInterface::Result 24 | { 25 | 26 | 27 | btVector3 m_normalOnBInWorld; 28 | btVector3 m_pointInWorld; 29 | btScalar m_distance;//negative means penetration 30 | 31 | bool m_hasResult; 32 | 33 | btPointCollector () 34 | : m_distance(btScalar(BT_LARGE_FLOAT)),m_hasResult(false) 35 | { 36 | } 37 | 38 | virtual void setShapeIdentifiersA(int partId0,int index0) 39 | { 40 | (void)partId0; 41 | (void)index0; 42 | 43 | } 44 | virtual void setShapeIdentifiersB(int partId1,int index1) 45 | { 46 | (void)partId1; 47 | (void)index1; 48 | } 49 | 50 | virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth) 51 | { 52 | if (depth< m_distance) 53 | { 54 | m_hasResult = true; 55 | m_normalOnBInWorld = normalOnBInWorld; 56 | m_pointInWorld = pointInWorld; 57 | //negative means penetration 58 | m_distance = depth; 59 | } 60 | } 61 | }; 62 | 63 | #endif //BT_POINT_COLLECTOR_H 64 | 65 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2011 Advanced Micro Devices, Inc. http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | ///This file was written by Erwin Coumans 18 | 19 | 20 | #ifndef BT_POLYHEDRAL_CONTACT_CLIPPING_H 21 | #define BT_POLYHEDRAL_CONTACT_CLIPPING_H 22 | 23 | 24 | #include "LinearMath/btAlignedObjectArray.h" 25 | #include "LinearMath/btTransform.h" 26 | #include "btDiscreteCollisionDetectorInterface.h" 27 | 28 | class btConvexPolyhedron; 29 | 30 | typedef btAlignedObjectArray btVertexArray; 31 | 32 | // Clips a face to the back of a plane 33 | struct btPolyhedralContactClipping 34 | { 35 | static void clipHullAgainstHull(const btVector3& separatingNormal, const btConvexPolyhedron& hullA, const btConvexPolyhedron& hullB, const btTransform& transA,const btTransform& transB, const btScalar minDist, btScalar maxDist, btDiscreteCollisionDetectorInterface::Result& resultOut); 36 | static void clipFaceAgainstHull(const btVector3& separatingNormal, const btConvexPolyhedron& hullA, const btTransform& transA, btVertexArray& worldVertsB1, const btScalar minDist, btScalar maxDist,btDiscreteCollisionDetectorInterface::Result& resultOut); 37 | 38 | static bool findSeparatingAxis( const btConvexPolyhedron& hullA, const btConvexPolyhedron& hullB, const btTransform& transA,const btTransform& transB, btVector3& sep, btDiscreteCollisionDetectorInterface::Result& resultOut); 39 | 40 | ///the clipFace method is used internally 41 | static void clipFace(const btVertexArray& pVtxIn, btVertexArray& ppVtxOut, const btVector3& planeNormalWS,btScalar planeEqWS); 42 | 43 | }; 44 | 45 | #endif // BT_POLYHEDRAL_CONTACT_CLIPPING_H 46 | 47 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | 18 | #ifndef BT_SIMPLEX_SOLVER_INTERFACE_H 19 | #define BT_SIMPLEX_SOLVER_INTERFACE_H 20 | 21 | #include "LinearMath/btVector3.h" 22 | 23 | #define NO_VIRTUAL_INTERFACE 1 24 | #ifdef NO_VIRTUAL_INTERFACE 25 | #include "btVoronoiSimplexSolver.h" 26 | #define btSimplexSolverInterface btVoronoiSimplexSolver 27 | #else 28 | 29 | /// btSimplexSolverInterface can incrementally calculate distance between origin and up to 4 vertices 30 | /// Used by GJK or Linear Casting. Can be implemented by the Johnson-algorithm or alternative approaches based on 31 | /// voronoi regions or barycentric coordinates 32 | class btSimplexSolverInterface 33 | { 34 | public: 35 | virtual ~btSimplexSolverInterface() {}; 36 | 37 | virtual void reset() = 0; 38 | 39 | virtual void addVertex(const btVector3& w, const btVector3& p, const btVector3& q) = 0; 40 | 41 | virtual bool closest(btVector3& v) = 0; 42 | 43 | virtual btScalar maxVertex() = 0; 44 | 45 | virtual bool fullSimplex() const = 0; 46 | 47 | virtual int getSimplex(btVector3 *pBuf, btVector3 *qBuf, btVector3 *yBuf) const = 0; 48 | 49 | virtual bool inSimplex(const btVector3& w) = 0; 50 | 51 | virtual void backup_closest(btVector3& v) = 0; 52 | 53 | virtual bool emptySimplex() const = 0; 54 | 55 | virtual void compute_points(btVector3& p1, btVector3& p2) = 0; 56 | 57 | virtual int numVertices() const =0; 58 | 59 | 60 | }; 61 | #endif 62 | #endif //BT_SIMPLEX_SOLVER_INTERFACE_H 63 | 64 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #ifndef BT_SUBSIMPLEX_CONVEX_CAST_H 18 | #define BT_SUBSIMPLEX_CONVEX_CAST_H 19 | 20 | #include "btConvexCast.h" 21 | #include "btSimplexSolverInterface.h" 22 | class btConvexShape; 23 | 24 | /// btSubsimplexConvexCast implements Gino van den Bergens' paper 25 | ///"Ray Casting against bteral Convex Objects with Application to Continuous Collision Detection" 26 | /// GJK based Ray Cast, optimized version 27 | /// Objects should not start in overlap, otherwise results are not defined. 28 | class btSubsimplexConvexCast : public btConvexCast 29 | { 30 | btSimplexSolverInterface* m_simplexSolver; 31 | const btConvexShape* m_convexA; 32 | const btConvexShape* m_convexB; 33 | 34 | public: 35 | 36 | btSubsimplexConvexCast (const btConvexShape* shapeA,const btConvexShape* shapeB,btSimplexSolverInterface* simplexSolver); 37 | 38 | //virtual ~btSubsimplexConvexCast(); 39 | ///SimsimplexConvexCast calculateTimeOfImpact calculates the time of impact+normal for the linear cast (sweep) between two moving objects. 40 | ///Precondition is that objects should not penetration/overlap at the start from the interval. Overlap can be tested using btGjkPairDetector. 41 | virtual bool calcTimeOfImpact( 42 | const btTransform& fromA, 43 | const btTransform& toA, 44 | const btTransform& fromB, 45 | const btTransform& toB, 46 | CastResult& result); 47 | 48 | }; 49 | 50 | #endif //BT_SUBSIMPLEX_CONVEX_CAST_H 51 | -------------------------------------------------------------------------------- /Bullet/BulletCollision/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletCollision" 2 | 3 | kind "StaticLib" 4 | targetdir "../../lib" 5 | includedirs { 6 | "..", 7 | } 8 | files { 9 | "**.cpp", 10 | "**.h" 11 | } -------------------------------------------------------------------------------- /Bullet/BulletDynamics/Character/btCharacterControllerInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2008 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_CHARACTER_CONTROLLER_INTERFACE_H 17 | #define BT_CHARACTER_CONTROLLER_INTERFACE_H 18 | 19 | #include "LinearMath/btVector3.h" 20 | #include "BulletDynamics/Dynamics/btActionInterface.h" 21 | 22 | class btCollisionShape; 23 | class btRigidBody; 24 | class btCollisionWorld; 25 | 26 | class btCharacterControllerInterface : public btActionInterface 27 | { 28 | public: 29 | btCharacterControllerInterface () {}; 30 | virtual ~btCharacterControllerInterface () {}; 31 | 32 | virtual void setWalkDirection(const btVector3& walkDirection) = 0; 33 | virtual void setVelocityForTimeInterval(const btVector3& velocity, btScalar timeInterval) = 0; 34 | virtual void reset () = 0; 35 | virtual void warp (const btVector3& origin) = 0; 36 | 37 | virtual void preStep ( btCollisionWorld* collisionWorld) = 0; 38 | virtual void playerStep (btCollisionWorld* collisionWorld, btScalar dt) = 0; 39 | virtual bool canJump () const = 0; 40 | virtual void jump () = 0; 41 | 42 | virtual bool onGround () const = 0; 43 | }; 44 | 45 | #endif //BT_CHARACTER_CONTROLLER_INTERFACE_H 46 | 47 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/ConstraintSolver/btConstraintSolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_CONSTRAINT_SOLVER_H 17 | #define BT_CONSTRAINT_SOLVER_H 18 | 19 | #include "LinearMath/btScalar.h" 20 | 21 | class btPersistentManifold; 22 | class btRigidBody; 23 | class btCollisionObject; 24 | class btTypedConstraint; 25 | struct btContactSolverInfo; 26 | struct btBroadphaseProxy; 27 | class btIDebugDraw; 28 | class btStackAlloc; 29 | class btDispatcher; 30 | /// btConstraintSolver provides solver interface 31 | class btConstraintSolver 32 | { 33 | 34 | public: 35 | 36 | virtual ~btConstraintSolver() {} 37 | 38 | virtual void prepareSolve (int /* numBodies */, int /* numManifolds */) {;} 39 | 40 | ///solve a group of constraints 41 | virtual btScalar solveGroup(btCollisionObject** bodies,int numBodies,btPersistentManifold** manifold,int numManifolds,btTypedConstraint** constraints,int numConstraints, const btContactSolverInfo& info,class btIDebugDraw* debugDrawer, btStackAlloc* stackAlloc,btDispatcher* dispatcher) = 0; 42 | 43 | virtual void allSolved (const btContactSolverInfo& /* info */,class btIDebugDraw* /* debugDrawer */, btStackAlloc* /* stackAlloc */) {;} 44 | 45 | ///clear internal cached data and reset random seed 46 | virtual void reset() = 0; 47 | }; 48 | 49 | 50 | 51 | 52 | #endif //BT_CONSTRAINT_SOLVER_H 53 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/ConstraintSolver/btGearConstraint.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2012 Advanced Micro Devices, Inc. http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | /// Implemented by Erwin Coumans. The idea for the constraint comes from Dimitris Papavasiliou. 17 | 18 | #include "btGearConstraint.h" 19 | 20 | btGearConstraint::btGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio) 21 | :btTypedConstraint(GEAR_CONSTRAINT_TYPE,rbA,rbB), 22 | m_axisInA(axisInA), 23 | m_axisInB(axisInB), 24 | m_ratio(ratio) 25 | { 26 | } 27 | 28 | btGearConstraint::~btGearConstraint () 29 | { 30 | } 31 | 32 | void btGearConstraint::getInfo1 (btConstraintInfo1* info) 33 | { 34 | info->m_numConstraintRows = 1; 35 | info->nub = 1; 36 | } 37 | 38 | void btGearConstraint::getInfo2 (btConstraintInfo2* info) 39 | { 40 | btVector3 globalAxisA, globalAxisB; 41 | 42 | globalAxisA = m_rbA.getWorldTransform().getBasis()*this->m_axisInA; 43 | globalAxisB = m_rbB.getWorldTransform().getBasis()*this->m_axisInB; 44 | 45 | info->m_J1angularAxis[0] = globalAxisA[0]; 46 | info->m_J1angularAxis[1] = globalAxisA[1]; 47 | info->m_J1angularAxis[2] = globalAxisA[2]; 48 | 49 | info->m_J2angularAxis[0] = m_ratio*globalAxisB[0]; 50 | info->m_J2angularAxis[1] = m_ratio*globalAxisB[1]; 51 | info->m_J2angularAxis[2] = m_ratio*globalAxisB[2]; 52 | 53 | } 54 | 55 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/ConstraintSolver/btGearConstraint.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2012 Advanced Micro Devices, Inc. http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | 18 | #ifndef BT_GEAR_CONSTRAINT_H 19 | #define BT_GEAR_CONSTRAINT_H 20 | 21 | #include "BulletDynamics/ConstraintSolver/btTypedConstraint.h" 22 | ///The btGeatConstraint will couple the angular velocity for two bodies around given local axis and ratio. 23 | ///See Bullet/Demos/ConstraintDemo for an example use. 24 | class btGearConstraint : public btTypedConstraint 25 | { 26 | protected: 27 | btVector3 m_axisInA; 28 | btVector3 m_axisInB; 29 | bool m_useFrameA; 30 | btScalar m_ratio; 31 | 32 | public: 33 | btGearConstraint(btRigidBody& rbA, btRigidBody& rbB, const btVector3& axisInA,const btVector3& axisInB, btScalar ratio=1.f); 34 | virtual ~btGearConstraint (); 35 | 36 | ///internal method used by the constraint solver, don't use them directly 37 | virtual void getInfo1 (btConstraintInfo1* info); 38 | 39 | ///internal method used by the constraint solver, don't use them directly 40 | virtual void getInfo2 (btConstraintInfo2* info); 41 | 42 | virtual void setParam(int num, btScalar value, int axis = -1) 43 | { 44 | btAssert(0); 45 | }; 46 | 47 | ///return the local value of parameter 48 | virtual btScalar getParam(int num, int axis = -1) const 49 | { 50 | btAssert(0); 51 | return 0.f; 52 | } 53 | 54 | }; 55 | 56 | #endif //BT_GEAR_CONSTRAINT_H 57 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/Dynamics/btActionInterface.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef _BT_ACTION_INTERFACE_H 17 | #define _BT_ACTION_INTERFACE_H 18 | 19 | class btIDebugDraw; 20 | class btCollisionWorld; 21 | 22 | #include "LinearMath/btScalar.h" 23 | #include "btRigidBody.h" 24 | 25 | ///Basic interface to allow actions such as vehicles and characters to be updated inside a btDynamicsWorld 26 | class btActionInterface 27 | { 28 | protected: 29 | 30 | static btRigidBody& getFixedBody(); 31 | 32 | 33 | public: 34 | 35 | virtual ~btActionInterface() 36 | { 37 | } 38 | 39 | virtual void updateAction( btCollisionWorld* collisionWorld, btScalar deltaTimeStep)=0; 40 | 41 | virtual void debugDraw(btIDebugDraw* debugDrawer) = 0; 42 | 43 | }; 44 | 45 | #endif //_BT_ACTION_INTERFACE_H 46 | 47 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/Vehicle/btVehicleRaycaster.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2005 Erwin Coumans http://bulletphysics.org 3 | * 4 | * Permission to use, copy, modify, distribute and sell this software 5 | * and its documentation for any purpose is hereby granted without fee, 6 | * provided that the above copyright notice appear in all copies. 7 | * Erwin Coumans makes no representations about the suitability 8 | * of this software for any purpose. 9 | * It is provided "as is" without express or implied warranty. 10 | */ 11 | #ifndef BT_VEHICLE_RAYCASTER_H 12 | #define BT_VEHICLE_RAYCASTER_H 13 | 14 | #include "LinearMath/btVector3.h" 15 | 16 | /// btVehicleRaycaster is provides interface for between vehicle simulation and raycasting 17 | struct btVehicleRaycaster 18 | { 19 | virtual ~btVehicleRaycaster() 20 | { 21 | } 22 | struct btVehicleRaycasterResult 23 | { 24 | btVehicleRaycasterResult() :m_distFraction(btScalar(-1.)){}; 25 | btVector3 m_hitPointInWorld; 26 | btVector3 m_hitNormalInWorld; 27 | btScalar m_distFraction; 28 | }; 29 | 30 | virtual void* castRay(const btVector3& from,const btVector3& to, btVehicleRaycasterResult& result) = 0; 31 | 32 | }; 33 | 34 | #endif //BT_VEHICLE_RAYCASTER_H 35 | 36 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/Vehicle/btWheelInfo.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Copyright (c) 2005 Erwin Coumans http://continuousphysics.com/Bullet/ 3 | * 4 | * Permission to use, copy, modify, distribute and sell this software 5 | * and its documentation for any purpose is hereby granted without fee, 6 | * provided that the above copyright notice appear in all copies. 7 | * Erwin Coumans makes no representations about the suitability 8 | * of this software for any purpose. 9 | * It is provided "as is" without express or implied warranty. 10 | */ 11 | #include "btWheelInfo.h" 12 | #include "BulletDynamics/Dynamics/btRigidBody.h" // for pointvelocity 13 | 14 | 15 | btScalar btWheelInfo::getSuspensionRestLength() const 16 | { 17 | 18 | return m_suspensionRestLength1; 19 | 20 | } 21 | 22 | void btWheelInfo::updateWheel(const btRigidBody& chassis,RaycastInfo& raycastInfo) 23 | { 24 | (void)raycastInfo; 25 | 26 | 27 | if (m_raycastInfo.m_isInContact) 28 | 29 | { 30 | btScalar project= m_raycastInfo.m_contactNormalWS.dot( m_raycastInfo.m_wheelDirectionWS ); 31 | btVector3 chassis_velocity_at_contactPoint; 32 | btVector3 relpos = m_raycastInfo.m_contactPointWS - chassis.getCenterOfMassPosition(); 33 | chassis_velocity_at_contactPoint = chassis.getVelocityInLocalPoint( relpos ); 34 | btScalar projVel = m_raycastInfo.m_contactNormalWS.dot( chassis_velocity_at_contactPoint ); 35 | if ( project >= btScalar(-0.1)) 36 | { 37 | m_suspensionRelativeVelocity = btScalar(0.0); 38 | m_clippedInvContactDotSuspension = btScalar(1.0) / btScalar(0.1); 39 | } 40 | else 41 | { 42 | btScalar inv = btScalar(-1.) / project; 43 | m_suspensionRelativeVelocity = projVel * inv; 44 | m_clippedInvContactDotSuspension = inv; 45 | } 46 | 47 | } 48 | 49 | else // Not in contact : position wheel in a nice (rest length) position 50 | { 51 | m_raycastInfo.m_suspensionLength = this->getSuspensionRestLength(); 52 | m_suspensionRelativeVelocity = btScalar(0.0); 53 | m_raycastInfo.m_contactNormalWS = -m_raycastInfo.m_wheelDirectionWS; 54 | m_clippedInvContactDotSuspension = btScalar(1.0); 55 | } 56 | } 57 | -------------------------------------------------------------------------------- /Bullet/BulletDynamics/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletDynamics" 2 | 3 | kind "StaticLib" 4 | targetdir "../../lib" 5 | includedirs { 6 | "..", 7 | } 8 | files { 9 | "**.cpp", 10 | "**.h" 11 | } -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | INCLUDE_DIRECTORIES( 3 | ${BULLET_PHYSICS_SOURCE_DIR}/src 4 | ) 5 | 6 | 7 | SUBDIRS ( 8 | OpenCL 9 | ) 10 | 11 | IF( USE_DX11 ) 12 | SUBDIRS( DX11 ) 13 | ENDIF( USE_DX11 ) 14 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/Integrate.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer IntegrateCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float solverdt; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_vertexInverseMasses : register( t0 ); 13 | 14 | RWStructuredBuffer g_vertexPositions : register( u0 ); 15 | RWStructuredBuffer g_vertexVelocity : register( u1 ); 16 | RWStructuredBuffer g_vertexPreviousPositions : register( u2 ); 17 | RWStructuredBuffer g_vertexForceAccumulator : register( u3 ); 18 | 19 | [numthreads(128, 1, 1)] 20 | void 21 | IntegrateKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 22 | { 23 | int nodeID = DTid.x; 24 | if( nodeID < numNodes ) 25 | { 26 | float3 position = g_vertexPositions[nodeID].xyz; 27 | float3 velocity = g_vertexVelocity[nodeID].xyz; 28 | float3 force = g_vertexForceAccumulator[nodeID].xyz; 29 | float inverseMass = g_vertexInverseMasses[nodeID]; 30 | 31 | g_vertexPreviousPositions[nodeID] = float4(position, 0.f); 32 | velocity += force * inverseMass * solverdt; 33 | position += velocity * solverdt; 34 | 35 | g_vertexForceAccumulator[nodeID] = float4(0.f, 0.f, 0.f, 0.0f); 36 | g_vertexPositions[nodeID] = float4(position, 0.f); 37 | g_vertexVelocity[nodeID] = float4(velocity, 0.f); 38 | } 39 | } 40 | 41 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/OutputToVertexArray.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer OutputToVertexArrayCB : register( b0 ) 4 | { 5 | int startNode; 6 | int numNodes; 7 | int positionOffset; 8 | int positionStride; 9 | 10 | int normalOffset; 11 | int normalStride; 12 | int padding1; 13 | int padding2; 14 | }; 15 | 16 | 17 | StructuredBuffer g_vertexPositions : register( t0 ); 18 | StructuredBuffer g_vertexNormals : register( t1 ); 19 | 20 | RWBuffer g_vertexBuffer : register( u0 ); 21 | 22 | 23 | [numthreads(128, 1, 1)] 24 | void 25 | OutputToVertexArrayWithNormalsKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 26 | { 27 | int nodeID = DTid.x; 28 | if( nodeID < numNodes ) 29 | { 30 | float4 position = g_vertexPositions[nodeID + startNode]; 31 | float4 normal = g_vertexNormals[nodeID + startNode]; 32 | 33 | // Stride should account for the float->float4 conversion 34 | int positionDestination = nodeID * positionStride + positionOffset; 35 | g_vertexBuffer[positionDestination] = position.x; 36 | g_vertexBuffer[positionDestination+1] = position.y; 37 | g_vertexBuffer[positionDestination+2] = position.z; 38 | 39 | int normalDestination = nodeID * normalStride + normalOffset; 40 | g_vertexBuffer[normalDestination] = normal.x; 41 | g_vertexBuffer[normalDestination+1] = normal.y; 42 | g_vertexBuffer[normalDestination+2] = normal.z; 43 | } 44 | } 45 | 46 | [numthreads(128, 1, 1)] 47 | void 48 | OutputToVertexArrayWithoutNormalsKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 49 | { 50 | int nodeID = DTid.x; 51 | if( nodeID < numNodes ) 52 | { 53 | float4 position = g_vertexPositions[nodeID + startNode]; 54 | float4 normal = g_vertexNormals[nodeID + startNode]; 55 | 56 | // Stride should account for the float->float4 conversion 57 | int positionDestination = nodeID * positionStride + positionOffset; 58 | g_vertexBuffer[positionDestination] = position.x; 59 | g_vertexBuffer[positionDestination+1] = position.y; 60 | g_vertexBuffer[positionDestination+2] = position.z; 61 | } 62 | } 63 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/PrepareLinks.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer PrepareLinksCB : register( b0 ) 4 | { 5 | int numLinks; 6 | int padding0; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | StructuredBuffer g_linksMassLSC : register( t1 ); 14 | StructuredBuffer g_nodesPreviousPosition : register( t2 ); 15 | 16 | RWStructuredBuffer g_linksLengthRatio : register( u0 ); 17 | RWStructuredBuffer g_linksCurrentLength : register( u1 ); 18 | 19 | [numthreads(128, 1, 1)] 20 | void 21 | PrepareLinksKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 22 | { 23 | int linkID = DTid.x; 24 | if( linkID < numLinks ) 25 | { 26 | int2 nodeIndices = g_linksVertexIndices[linkID]; 27 | int node0 = nodeIndices.x; 28 | int node1 = nodeIndices.y; 29 | 30 | float4 nodePreviousPosition0 = g_nodesPreviousPosition[node0]; 31 | float4 nodePreviousPosition1 = g_nodesPreviousPosition[node1]; 32 | 33 | float massLSC = g_linksMassLSC[linkID]; 34 | 35 | float4 linkCurrentLength = nodePreviousPosition1 - nodePreviousPosition0; 36 | 37 | float linkLengthRatio = dot(linkCurrentLength, linkCurrentLength)*massLSC; 38 | linkLengthRatio = 1./linkLengthRatio; 39 | 40 | g_linksCurrentLength[linkID] = linkCurrentLength; 41 | g_linksLengthRatio[linkID] = linkLengthRatio; 42 | } 43 | } 44 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/SolvePositions.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer SolvePositionsFromLinksKernelCB : register( b0 ) 4 | { 5 | int startLink; 6 | int numLinks; 7 | float kst; 8 | float ti; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | 14 | StructuredBuffer g_linksMassLSC : register( t1 ); 15 | StructuredBuffer g_linksRestLengthSquared : register( t2 ); 16 | StructuredBuffer g_verticesInverseMass : register( t3 ); 17 | 18 | RWStructuredBuffer g_vertexPositions : register( u0 ); 19 | 20 | [numthreads(128, 1, 1)] 21 | void 22 | SolvePositionsFromLinksKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 23 | { 24 | int linkID = DTid.x + startLink; 25 | if( DTid.x < numLinks ) 26 | { 27 | float massLSC = g_linksMassLSC[linkID]; 28 | float restLengthSquared = g_linksRestLengthSquared[linkID]; 29 | 30 | if( massLSC > 0.0f ) 31 | { 32 | int2 nodeIndices = g_linksVertexIndices[linkID]; 33 | int node0 = nodeIndices.x; 34 | int node1 = nodeIndices.y; 35 | 36 | float3 position0 = g_vertexPositions[node0].xyz; 37 | float3 position1 = g_vertexPositions[node1].xyz; 38 | 39 | float inverseMass0 = g_verticesInverseMass[node0]; 40 | float inverseMass1 = g_verticesInverseMass[node1]; 41 | 42 | float3 del = position1 - position0; 43 | float len = dot(del, del); 44 | float k = ((restLengthSquared - len)/(massLSC*(restLengthSquared+len)))*kst; 45 | position0 = position0 - del*(k*inverseMass0); 46 | position1 = position1 + del*(k*inverseMass1); 47 | 48 | g_vertexPositions[node0] = float4(position0, 0.f); 49 | g_vertexPositions[node1] = float4(position1, 0.f); 50 | 51 | } 52 | } 53 | } 54 | 55 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateConstants.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdateConstantsCB : register( b0 ) 4 | { 5 | int numLinks; 6 | int padding0; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | StructuredBuffer g_vertexPositions : register( t1 ); 14 | StructuredBuffer g_vertexInverseMasses : register( t2 ); 15 | StructuredBuffer g_linksMaterialLSC : register( t3 ); 16 | 17 | RWStructuredBuffer g_linksMassLSC : register( u0 ); 18 | RWStructuredBuffer g_linksRestLengthSquared : register( u1 ); 19 | RWStructuredBuffer g_linksRestLengths : register( u2 ); 20 | 21 | [numthreads(128, 1, 1)] 22 | void 23 | UpdateConstantsKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 24 | { 25 | int linkID = DTid.x; 26 | if( linkID < numLinks ) 27 | { 28 | int2 nodeIndices = g_linksVertexIndices[linkID]; 29 | int node0 = nodeIndices.x; 30 | int node1 = nodeIndices.y; 31 | float linearStiffnessCoefficient = g_linksMaterialLSC[ linkID ]; 32 | 33 | float3 position0 = g_vertexPositions[node0].xyz; 34 | float3 position1 = g_vertexPositions[node1].xyz; 35 | float inverseMass0 = g_vertexInverseMasses[node0]; 36 | float inverseMass1 = g_vertexInverseMasses[node1]; 37 | 38 | float3 difference = position0 - position1; 39 | float length2 = dot(difference, difference); 40 | float length = sqrt(length2); 41 | 42 | g_linksRestLengths[linkID] = length; 43 | g_linksMassLSC[linkID] = (inverseMass0 + inverseMass1)/linearStiffnessCoefficient; 44 | g_linksRestLengthSquared[linkID] = length*length; 45 | } 46 | } 47 | 48 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdateNodes.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdateVelocitiesFromPositionsWithVelocitiesCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float isolverdt; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | 12 | StructuredBuffer g_vertexPositions : register( t0 ); 13 | StructuredBuffer g_vertexPreviousPositions : register( t1 ); 14 | StructuredBuffer g_vertexClothIndices : register( t2 ); 15 | StructuredBuffer g_clothVelocityCorrectionCoefficients : register( t3 ); 16 | StructuredBuffer g_clothDampingFactor : register( t4 ); 17 | 18 | RWStructuredBuffer g_vertexVelocities : register( u0 ); 19 | RWStructuredBuffer g_vertexForces : register( u1 ); 20 | 21 | 22 | [numthreads(128, 1, 1)] 23 | void 24 | updateVelocitiesFromPositionsWithVelocitiesKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 25 | { 26 | int nodeID = DTid.x; 27 | if( nodeID < numNodes ) 28 | { 29 | float3 position = g_vertexPositions[nodeID].xyz; 30 | float3 previousPosition = g_vertexPreviousPositions[nodeID].xyz; 31 | float3 velocity = g_vertexVelocities[nodeID].xyz; 32 | int clothIndex = g_vertexClothIndices[nodeID]; 33 | float velocityCorrectionCoefficient = g_clothVelocityCorrectionCoefficients[clothIndex]; 34 | float dampingFactor = g_clothDampingFactor[clothIndex]; 35 | float velocityCoefficient = (1.f - dampingFactor); 36 | 37 | float3 difference = position - previousPosition; 38 | 39 | velocity += difference*velocityCorrectionCoefficient*isolverdt; 40 | 41 | // Damp the velocity 42 | velocity *= velocityCoefficient; 43 | 44 | g_vertexVelocities[nodeID] = float4(velocity, 0.f); 45 | g_vertexForces[nodeID] = float4(0.f, 0.f, 0.f, 0.f); 46 | } 47 | } 48 | 49 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositions.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdateVelocitiesFromPositionsWithoutVelocitiesCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float isolverdt; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | 12 | StructuredBuffer g_vertexPositions : register( t0 ); 13 | StructuredBuffer g_vertexPreviousPositions : register( t1 ); 14 | StructuredBuffer g_vertexClothIndices : register( t2 ); 15 | StructuredBuffer g_clothDampingFactor : register( t3 ); 16 | 17 | RWStructuredBuffer g_vertexVelocities : register( u0 ); 18 | RWStructuredBuffer g_vertexForces : register( u1 ); 19 | 20 | 21 | [numthreads(128, 1, 1)] 22 | void 23 | updateVelocitiesFromPositionsWithoutVelocitiesKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 24 | { 25 | int nodeID = DTid.x; 26 | if( nodeID < numNodes ) 27 | { 28 | float3 position = g_vertexPositions[nodeID].xyz; 29 | float3 previousPosition = g_vertexPreviousPositions[nodeID].xyz; 30 | float3 velocity = g_vertexVelocities[nodeID].xyz; 31 | int clothIndex = g_vertexClothIndices[nodeID]; 32 | float dampingFactor = g_clothDampingFactor[clothIndex]; 33 | float velocityCoefficient = (1.f - dampingFactor); 34 | 35 | float3 difference = position - previousPosition; 36 | 37 | velocity = difference*velocityCoefficient*isolverdt; 38 | 39 | g_vertexVelocities[nodeID] = float4(velocity, 0.f); 40 | g_vertexForces[nodeID] = float4(0.f, 0.f, 0.f, 0.f); 41 | } 42 | } 43 | 44 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/UpdatePositionsFromVelocities.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer UpdatePositionsFromVelocitiesCB : register( b0 ) 4 | { 5 | int numNodes; 6 | float solverSDT; 7 | int padding1; 8 | int padding2; 9 | }; 10 | 11 | 12 | StructuredBuffer g_vertexVelocities : register( t0 ); 13 | 14 | RWStructuredBuffer g_vertexPreviousPositions : register( u0 ); 15 | RWStructuredBuffer g_vertexCurrentPosition : register( u1 ); 16 | 17 | 18 | [numthreads(128, 1, 1)] 19 | void 20 | UpdatePositionsFromVelocitiesKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 21 | { 22 | int vertexID = DTid.x; 23 | if( vertexID < numNodes ) 24 | { 25 | float3 previousPosition = g_vertexPreviousPositions[vertexID].xyz; 26 | float3 velocity = g_vertexVelocities[vertexID].xyz; 27 | 28 | float3 newPosition = previousPosition + velocity*solverSDT; 29 | 30 | g_vertexCurrentPosition[vertexID] = float4(newPosition, 0.f); 31 | g_vertexPreviousPositions[vertexID] = float4(newPosition, 0.f); 32 | } 33 | } 34 | 35 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/HLSL/VSolveLinks.hlsl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | cbuffer VSolveLinksCB : register( b0 ) 4 | { 5 | int startLink; 6 | int numLinks; 7 | float kst; 8 | int padding; 9 | }; 10 | 11 | // Node indices for each link 12 | StructuredBuffer g_linksVertexIndices : register( t0 ); 13 | 14 | StructuredBuffer g_linksLengthRatio : register( t1 ); 15 | StructuredBuffer g_linksCurrentLength : register( t2 ); 16 | StructuredBuffer g_vertexInverseMass : register( t3 ); 17 | 18 | RWStructuredBuffer g_vertexVelocity : register( u0 ); 19 | 20 | [numthreads(128, 1, 1)] 21 | void 22 | VSolveLinksKernel( uint3 Gid : SV_GroupID, uint3 DTid : SV_DispatchThreadID, uint3 GTid : SV_GroupThreadID, uint GI : SV_GroupIndex ) 23 | { 24 | int linkID = DTid.x + startLink; 25 | if( DTid.x < numLinks ) 26 | { 27 | int2 nodeIndices = g_linksVertexIndices[linkID]; 28 | int node0 = nodeIndices.x; 29 | int node1 = nodeIndices.y; 30 | 31 | float linkLengthRatio = g_linksLengthRatio[linkID]; 32 | float3 linkCurrentLength = g_linksCurrentLength[linkID].xyz; 33 | 34 | float3 vertexVelocity0 = g_vertexVelocity[node0].xyz; 35 | float3 vertexVelocity1 = g_vertexVelocity[node1].xyz; 36 | 37 | float vertexInverseMass0 = g_vertexInverseMass[node0]; 38 | float vertexInverseMass1 = g_vertexInverseMass[node1]; 39 | 40 | float3 nodeDifference = vertexVelocity0 - vertexVelocity1; 41 | float dotResult = dot(linkCurrentLength, nodeDifference); 42 | float j = -dotResult*linkLengthRatio*kst; 43 | 44 | float3 velocityChange0 = linkCurrentLength*(j*vertexInverseMass0); 45 | float3 velocityChange1 = linkCurrentLength*(j*vertexInverseMass1); 46 | 47 | vertexVelocity0 += velocityChange0; 48 | vertexVelocity1 -= velocityChange1; 49 | 50 | g_vertexVelocity[node0] = float4(vertexVelocity0, 0.f); 51 | g_vertexVelocity[node1] = float4(vertexVelocity1, 0.f); 52 | } 53 | } 54 | 55 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/DX11/premake4.lua: -------------------------------------------------------------------------------- 1 | 2 | hasDX11 = findDirectX11() 3 | 4 | if (hasDX11) then 5 | 6 | project "BulletSoftBodyDX11Solvers" 7 | 8 | initDirectX11() 9 | 10 | kind "StaticLib" 11 | 12 | targetdir "../../../../lib" 13 | 14 | includedirs { 15 | ".", 16 | "../../.." 17 | } 18 | files { 19 | "**.cpp", 20 | "**.h" 21 | } 22 | 23 | end 24 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/AMD/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | INCLUDE_DIRECTORIES( 3 | ${BULLET_PHYSICS_SOURCE_DIR}/src 4 | ${AMD_OPENCL_INCLUDES} 5 | ) 6 | 7 | ADD_DEFINITIONS(-DUSE_AMD_OPENCL) 8 | ADD_DEFINITIONS(-DCL_PLATFORM_AMD) 9 | 10 | 11 | 12 | SET(BulletSoftBodyOpenCLSolvers_SRCS 13 | ../btSoftBodySolver_OpenCL.cpp 14 | ../btSoftBodySolver_OpenCLSIMDAware.cpp 15 | ../btSoftBodySolverOutputCLtoGL.cpp 16 | ) 17 | 18 | SET(BulletSoftBodyOpenCLSolvers_HDRS 19 | ../btSoftBodySolver_OpenCL.h 20 | ../btSoftBodySolver_OpenCLSIMDAware.h 21 | ../../Shared/btSoftBodySolverData.h 22 | ../btSoftBodySolverVertexData_OpenCL.h 23 | ../btSoftBodySolverTriangleData_OpenCL.h 24 | ../btSoftBodySolverLinkData_OpenCL.h 25 | ../btSoftBodySolverLinkData_OpenCLSIMDAware.h 26 | ../btSoftBodySolverBuffer_OpenCL.h 27 | ../btSoftBodySolverVertexBuffer_OpenGL.h 28 | ../btSoftBodySolverOutputCLtoGL.h 29 | ) 30 | 31 | 32 | 33 | 34 | ADD_LIBRARY(BulletSoftBodySolvers_OpenCL_AMD 35 | ${BulletSoftBodyOpenCLSolvers_SRCS} 36 | ${BulletSoftBodyOpenCLSolvers_HDRS} 37 | ) 38 | 39 | SET_TARGET_PROPERTIES(BulletSoftBodySolvers_OpenCL_AMD PROPERTIES VERSION ${BULLET_VERSION}) 40 | SET_TARGET_PROPERTIES(BulletSoftBodySolvers_OpenCL_AMD PROPERTIES SOVERSION ${BULLET_VERSION}) 41 | IF (BUILD_SHARED_LIBS) 42 | TARGET_LINK_LIBRARIES(BulletSoftBodySolvers_OpenCL_AMD BulletSoftBody) 43 | ENDIF (BUILD_SHARED_LIBS) 44 | 45 | 46 | IF (INSTALL_LIBS) 47 | IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 48 | IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 49 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 50 | INSTALL(TARGETS BulletSoftBodySolvers_OpenCL_AMD DESTINATION .) 51 | ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 52 | INSTALL(TARGETS BulletSoftBodySolvers_OpenCL_AMD DESTINATION lib${LIB_SUFFIX}) 53 | #headers are already installed by BulletMultiThreaded library 54 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 55 | ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 56 | 57 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 58 | SET_TARGET_PROPERTIES(BulletSoftBodySolvers_OpenCL_AMD PROPERTIES FRAMEWORK true) 59 | SET_TARGET_PROPERTIES(BulletSoftBodySolvers_OpenCL_AMD PROPERTIES PUBLIC_HEADER "${BulletSoftBodyOpenCLSolvers_HDRS}") 60 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 61 | ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 62 | ENDIF (INSTALL_LIBS) 63 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/AMD/premake4.lua: -------------------------------------------------------------------------------- 1 | 2 | hasCL = findOpenCL_AMD() 3 | 4 | if (hasCL) then 5 | 6 | project "BulletSoftBodySolvers_OpenCL_AMD" 7 | 8 | defines { "USE_AMD_OPENCL","CL_PLATFORM_AMD"} 9 | 10 | initOpenCL_AMD() 11 | 12 | kind "StaticLib" 13 | 14 | targetdir "../../../../../lib" 15 | 16 | includedirs { 17 | ".", 18 | "../../../..", 19 | "../../../../../Glut" 20 | } 21 | files { 22 | "../btSoftBodySolver_OpenCL.cpp", 23 | "../btSoftBodySolver_OpenCLSIMDAware.cpp", 24 | "../btSoftBodySolverOutputCLtoGL.cpp" 25 | } 26 | 27 | end 28 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | SUBDIRS( MiniCL ) 2 | 3 | IF(BUILD_INTEL_OPENCL_DEMOS) 4 | SUBDIRS(Intel) 5 | ENDIF() 6 | 7 | IF(BUILD_AMD_OPENCL_DEMOS) 8 | SUBDIRS(AMD) 9 | ENDIF() 10 | 11 | IF(BUILD_NVIDIA_OPENCL_DEMOS) 12 | SUBDIRS(NVidia) 13 | ENDIF() 14 | 15 | IF(APPLE AND OPENCL_LIBRARY) 16 | SUBDIRS(Apple) 17 | ENDIF() 18 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/Intel/premake4.lua: -------------------------------------------------------------------------------- 1 | 2 | hasCL = findOpenCL_Intel() 3 | 4 | if (hasCL) then 5 | 6 | project "BulletSoftBodySolvers_OpenCL_Intel" 7 | 8 | defines { "USE_INTEL_OPENCL","CL_PLATFORM_INTEL"} 9 | 10 | initOpenCL_Intel() 11 | 12 | kind "StaticLib" 13 | 14 | targetdir "../../../../../lib" 15 | 16 | includedirs { 17 | ".", 18 | "../../../..", 19 | "../../../../../Glut" 20 | } 21 | files { 22 | "../btSoftBodySolver_OpenCL.cpp", 23 | "../btSoftBodySolver_OpenCLSIMDAware.cpp", 24 | "../btSoftBodySolverOutputCLtoGL.cpp" 25 | } 26 | 27 | end 28 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/NVidia/premake4.lua: -------------------------------------------------------------------------------- 1 | 2 | hasCL = findOpenCL_NVIDIA() 3 | 4 | if (hasCL) then 5 | 6 | project "BulletSoftBodySolvers_OpenCL_NVIDIA" 7 | 8 | defines { "USE_NVIDIA_OPENCL","CL_PLATFORM_NVIDIA"} 9 | 10 | initOpenCL_NVIDIA() 11 | 12 | kind "StaticLib" 13 | 14 | targetdir "../../../../../lib" 15 | 16 | includedirs { 17 | ".", 18 | "../../../..", 19 | "../../../../../Glut" 20 | } 21 | files { 22 | "../btSoftBodySolver_OpenCL.cpp", 23 | "../btSoftBodySolver_OpenCLSIMDAware.cpp", 24 | "../btSoftBodySolverOutputCLtoGL.cpp" 25 | } 26 | 27 | end 28 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ApplyForces.cl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/ApplyForces.cl -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/Integrate.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | // Node indices for each link 4 | 5 | 6 | 7 | __kernel void 8 | IntegrateKernel( 9 | const int numNodes, 10 | const float solverdt, 11 | __global float * g_vertexInverseMasses, 12 | __global float4 * g_vertexPositions, 13 | __global float4 * g_vertexVelocity, 14 | __global float4 * g_vertexPreviousPositions, 15 | __global float4 * g_vertexForceAccumulator GUID_ARG) 16 | { 17 | int nodeID = get_global_id(0); 18 | if( nodeID < numNodes ) 19 | { 20 | float4 position = g_vertexPositions[nodeID]; 21 | float4 velocity = g_vertexVelocity[nodeID]; 22 | float4 force = g_vertexForceAccumulator[nodeID]; 23 | float inverseMass = g_vertexInverseMasses[nodeID]; 24 | 25 | g_vertexPreviousPositions[nodeID] = position; 26 | velocity += force * inverseMass * solverdt; 27 | position += velocity * solverdt; 28 | 29 | g_vertexForceAccumulator[nodeID] = (float4)(0.f, 0.f, 0.f, 0.0f); 30 | g_vertexPositions[nodeID] = position; 31 | g_vertexVelocity[nodeID] = velocity; 32 | } 33 | } 34 | 35 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/OutputToVertexArray.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | OutputToVertexArrayWithNormalsKernel( 5 | const int startNode, const int numNodes, __global float *g_vertexBuffer, 6 | const int positionOffset, const int positionStride, const __global float4* g_vertexPositions, 7 | const int normalOffset, const int normalStride, const __global float4* g_vertexNormals ) 8 | { 9 | int nodeID = get_global_id(0); 10 | if( nodeID < numNodes ) 11 | { 12 | float4 position = g_vertexPositions[nodeID + startNode]; 13 | float4 normal = g_vertexNormals[nodeID + startNode]; 14 | 15 | // Stride should account for the float->float4 conversion 16 | int positionDestination = nodeID * positionStride + positionOffset; 17 | g_vertexBuffer[positionDestination] = position.x; 18 | g_vertexBuffer[positionDestination+1] = position.y; 19 | g_vertexBuffer[positionDestination+2] = position.z; 20 | 21 | int normalDestination = nodeID * normalStride + normalOffset; 22 | g_vertexBuffer[normalDestination] = normal.x; 23 | g_vertexBuffer[normalDestination+1] = normal.y; 24 | g_vertexBuffer[normalDestination+2] = normal.z; 25 | } 26 | } 27 | 28 | __kernel void 29 | OutputToVertexArrayWithoutNormalsKernel( 30 | const int startNode, const int numNodes, __global float *g_vertexBuffer, 31 | const int positionOffset, const int positionStride, const __global float4* g_vertexPositions ) 32 | { 33 | int nodeID = get_global_id(0); 34 | if( nodeID < numNodes ) 35 | { 36 | float4 position = g_vertexPositions[nodeID + startNode]; 37 | 38 | // Stride should account for the float->float4 conversion 39 | int positionDestination = nodeID * positionStride + positionOffset; 40 | g_vertexBuffer[positionDestination] = position.x; 41 | g_vertexBuffer[positionDestination+1] = position.y; 42 | g_vertexBuffer[positionDestination+2] = position.z; 43 | } 44 | } 45 | 46 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/PrepareLinks.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | 4 | 5 | __kernel void 6 | PrepareLinksKernel( 7 | const int numLinks, 8 | __global int2 * g_linksVertexIndices, 9 | __global float * g_linksMassLSC, 10 | __global float4 * g_nodesPreviousPosition, 11 | __global float * g_linksLengthRatio, 12 | __global float4 * g_linksCurrentLength GUID_ARG) 13 | { 14 | int linkID = get_global_id(0); 15 | if( linkID < numLinks ) 16 | { 17 | 18 | int2 nodeIndices = g_linksVertexIndices[linkID]; 19 | int node0 = nodeIndices.x; 20 | int node1 = nodeIndices.y; 21 | 22 | float4 nodePreviousPosition0 = g_nodesPreviousPosition[node0]; 23 | float4 nodePreviousPosition1 = g_nodesPreviousPosition[node1]; 24 | 25 | float massLSC = g_linksMassLSC[linkID]; 26 | 27 | float4 linkCurrentLength = nodePreviousPosition1 - nodePreviousPosition0; 28 | linkCurrentLength.w = 0.f; 29 | 30 | float linkLengthRatio = dot(linkCurrentLength, linkCurrentLength)*massLSC; 31 | linkLengthRatio = 1.0f/linkLengthRatio; 32 | 33 | g_linksCurrentLength[linkID] = linkCurrentLength; 34 | g_linksLengthRatio[linkID] = linkLengthRatio; 35 | } 36 | } 37 | 38 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/SolvePositions.cl: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | MSTRINGIFY( 5 | 6 | 7 | float mydot3(float4 a, float4 b) 8 | { 9 | return a.x*b.x + a.y*b.y + a.z*b.z; 10 | } 11 | 12 | 13 | __kernel void 14 | SolvePositionsFromLinksKernel( 15 | const int startLink, 16 | const int numLinks, 17 | const float kst, 18 | const float ti, 19 | __global int2 * g_linksVertexIndices, 20 | __global float * g_linksMassLSC, 21 | __global float * g_linksRestLengthSquared, 22 | __global float * g_verticesInverseMass, 23 | __global float4 * g_vertexPositions GUID_ARG) 24 | 25 | { 26 | int linkID = get_global_id(0) + startLink; 27 | if( get_global_id(0) < numLinks ) 28 | { 29 | float massLSC = g_linksMassLSC[linkID]; 30 | float restLengthSquared = g_linksRestLengthSquared[linkID]; 31 | 32 | if( massLSC > 0.0f ) 33 | { 34 | int2 nodeIndices = g_linksVertexIndices[linkID]; 35 | int node0 = nodeIndices.x; 36 | int node1 = nodeIndices.y; 37 | 38 | float4 position0 = g_vertexPositions[node0]; 39 | float4 position1 = g_vertexPositions[node1]; 40 | 41 | float inverseMass0 = g_verticesInverseMass[node0]; 42 | float inverseMass1 = g_verticesInverseMass[node1]; 43 | 44 | float4 del = position1 - position0; 45 | float len = mydot3(del, del); 46 | float k = ((restLengthSquared - len)/(massLSC*(restLengthSquared+len)))*kst; 47 | position0 = position0 - del*(k*inverseMass0); 48 | position1 = position1 + del*(k*inverseMass1); 49 | 50 | g_vertexPositions[node0] = position0; 51 | g_vertexPositions[node1] = position1; 52 | 53 | } 54 | } 55 | } 56 | 57 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateConstants.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | /*#define float3 float4 4 | 5 | float dot3(float3 a, float3 b) 6 | { 7 | return a.x*b.x + a.y*b.y + a.z*b.z; 8 | }*/ 9 | 10 | __kernel void 11 | UpdateConstantsKernel( 12 | const int numLinks, 13 | __global int2 * g_linksVertexIndices, 14 | __global float4 * g_vertexPositions, 15 | __global float * g_vertexInverseMasses, 16 | __global float * g_linksMaterialLSC, 17 | __global float * g_linksMassLSC, 18 | __global float * g_linksRestLengthSquared, 19 | __global float * g_linksRestLengths) 20 | { 21 | int linkID = get_global_id(0); 22 | if( linkID < numLinks ) 23 | { 24 | int2 nodeIndices = g_linksVertexIndices[linkID]; 25 | int node0 = nodeIndices.x; 26 | int node1 = nodeIndices.y; 27 | float linearStiffnessCoefficient = g_linksMaterialLSC[ linkID ]; 28 | 29 | float3 position0 = g_vertexPositions[node0].xyz; 30 | float3 position1 = g_vertexPositions[node1].xyz; 31 | float inverseMass0 = g_vertexInverseMasses[node0]; 32 | float inverseMass1 = g_vertexInverseMasses[node1]; 33 | 34 | float3 difference = position0 - position1; 35 | float length2 = dot(difference, difference); 36 | float length = sqrt(length2); 37 | 38 | g_linksRestLengths[linkID] = length; 39 | g_linksMassLSC[linkID] = (inverseMass0 + inverseMass1)/linearStiffnessCoefficient; 40 | g_linksRestLengthSquared[linkID] = length*length; 41 | } 42 | } 43 | 44 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateFixedVertexPositions.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | UpdateFixedVertexPositions( 5 | const uint numNodes, 6 | __global int * g_anchorIndex, 7 | __global float4 * g_vertexPositions, 8 | __global float4 * g_anchorPositions GUID_ARG) 9 | { 10 | unsigned int nodeID = get_global_id(0); 11 | 12 | if( nodeID < numNodes ) 13 | { 14 | int anchorIndex = g_anchorIndex[nodeID]; 15 | float4 position = g_vertexPositions[nodeID]; 16 | 17 | if ( anchorIndex >= 0 ) 18 | { 19 | float4 anchorPosition = g_anchorPositions[anchorIndex]; 20 | g_vertexPositions[nodeID] = anchorPosition; 21 | } 22 | } 23 | } 24 | 25 | ); 26 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdateNodes.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | 4 | __kernel void 5 | updateVelocitiesFromPositionsWithVelocitiesKernel( 6 | int numNodes, 7 | float isolverdt, 8 | __global float4 * g_vertexPositions, 9 | __global float4 * g_vertexPreviousPositions, 10 | __global int * g_vertexClothIndices, 11 | __global float *g_clothVelocityCorrectionCoefficients, 12 | __global float * g_clothDampingFactor, 13 | __global float4 * g_vertexVelocities, 14 | __global float4 * g_vertexForces GUID_ARG) 15 | { 16 | int nodeID = get_global_id(0); 17 | if( nodeID < numNodes ) 18 | { 19 | float4 position = g_vertexPositions[nodeID]; 20 | float4 previousPosition = g_vertexPreviousPositions[nodeID]; 21 | float4 velocity = g_vertexVelocities[nodeID]; 22 | int clothIndex = g_vertexClothIndices[nodeID]; 23 | float velocityCorrectionCoefficient = g_clothVelocityCorrectionCoefficients[clothIndex]; 24 | float dampingFactor = g_clothDampingFactor[clothIndex]; 25 | float velocityCoefficient = (1.f - dampingFactor); 26 | 27 | float4 difference = position - previousPosition; 28 | 29 | velocity += difference*velocityCorrectionCoefficient*isolverdt; 30 | 31 | // Damp the velocity 32 | velocity *= velocityCoefficient; 33 | 34 | g_vertexVelocities[nodeID] = velocity; 35 | g_vertexForces[nodeID] = (float4)(0.f, 0.f, 0.f, 0.f); 36 | } 37 | } 38 | 39 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositions.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | updateVelocitiesFromPositionsWithoutVelocitiesKernel( 5 | const int numNodes, 6 | const float isolverdt, 7 | __global float4 * g_vertexPositions, 8 | __global float4 * g_vertexPreviousPositions, 9 | __global int * g_vertexClothIndices, 10 | __global float * g_clothDampingFactor, 11 | __global float4 * g_vertexVelocities, 12 | __global float4 * g_vertexForces GUID_ARG) 13 | 14 | { 15 | int nodeID = get_global_id(0); 16 | if( nodeID < numNodes ) 17 | { 18 | float4 position = g_vertexPositions[nodeID]; 19 | float4 previousPosition = g_vertexPreviousPositions[nodeID]; 20 | float4 velocity = g_vertexVelocities[nodeID]; 21 | int clothIndex = g_vertexClothIndices[nodeID]; 22 | float dampingFactor = g_clothDampingFactor[clothIndex]; 23 | float velocityCoefficient = (1.f - dampingFactor); 24 | 25 | float4 difference = position - previousPosition; 26 | 27 | velocity = difference*velocityCoefficient*isolverdt; 28 | 29 | g_vertexVelocities[nodeID] = velocity; 30 | g_vertexForces[nodeID] = (float4)(0.f, 0.f, 0.f, 0.f); 31 | } 32 | } 33 | 34 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/UpdatePositionsFromVelocities.cl: -------------------------------------------------------------------------------- 1 | 2 | MSTRINGIFY( 3 | 4 | 5 | 6 | 7 | __kernel void 8 | UpdatePositionsFromVelocitiesKernel( 9 | const int numNodes, 10 | const float solverSDT, 11 | __global float4 * g_vertexVelocities, 12 | __global float4 * g_vertexPreviousPositions, 13 | __global float4 * g_vertexCurrentPosition GUID_ARG) 14 | { 15 | int vertexID = get_global_id(0); 16 | if( vertexID < numNodes ) 17 | { 18 | float4 previousPosition = g_vertexPreviousPositions[vertexID]; 19 | float4 velocity = g_vertexVelocities[vertexID]; 20 | 21 | float4 newPosition = previousPosition + velocity*solverSDT; 22 | 23 | g_vertexCurrentPosition[vertexID] = newPosition; 24 | g_vertexPreviousPositions[vertexID] = newPosition; 25 | } 26 | } 27 | 28 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/OpenCLC10/VSolveLinks.cl: -------------------------------------------------------------------------------- 1 | MSTRINGIFY( 2 | 3 | __kernel void 4 | VSolveLinksKernel( 5 | int startLink, 6 | int numLinks, 7 | float kst, 8 | __global int2 * g_linksVertexIndices, 9 | __global float * g_linksLengthRatio, 10 | __global float4 * g_linksCurrentLength, 11 | __global float * g_vertexInverseMass, 12 | __global float4 * g_vertexVelocity GUID_ARG) 13 | { 14 | int linkID = get_global_id(0) + startLink; 15 | if( get_global_id(0) < numLinks ) 16 | { 17 | int2 nodeIndices = g_linksVertexIndices[linkID]; 18 | int node0 = nodeIndices.x; 19 | int node1 = nodeIndices.y; 20 | 21 | float linkLengthRatio = g_linksLengthRatio[linkID]; 22 | float3 linkCurrentLength = g_linksCurrentLength[linkID].xyz; 23 | 24 | float3 vertexVelocity0 = g_vertexVelocity[node0].xyz; 25 | float3 vertexVelocity1 = g_vertexVelocity[node1].xyz; 26 | 27 | float vertexInverseMass0 = g_vertexInverseMass[node0]; 28 | float vertexInverseMass1 = g_vertexInverseMass[node1]; 29 | 30 | float3 nodeDifference = vertexVelocity0 - vertexVelocity1; 31 | float dotResult = dot(linkCurrentLength, nodeDifference); 32 | float j = -dotResult*linkLengthRatio*kst; 33 | 34 | float3 velocityChange0 = linkCurrentLength*(j*vertexInverseMass0); 35 | float3 velocityChange1 = linkCurrentLength*(j*vertexInverseMass1); 36 | 37 | vertexVelocity0 += velocityChange0; 38 | vertexVelocity1 -= velocityChange1; 39 | 40 | g_vertexVelocity[node0] = (float4)(vertexVelocity0, 0.f); 41 | g_vertexVelocity[node1] = (float4)(vertexVelocity1, 0.f); 42 | } 43 | } 44 | 45 | ); -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/GpuSoftBodySolvers/OpenCL/btSoftBodySolverVertexData_OpenCL.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "BulletMultiThreaded/GpuSoftBodySolvers/Shared/btSoftBodySolverData.h" 17 | #include "btSoftBodySolverBuffer_OpenCL.h" 18 | 19 | #ifndef BT_SOFT_BODY_SOLVER_VERTEX_DATA_OPENCL_H 20 | #define BT_SOFT_BODY_SOLVER_VERTEX_DATA_OPENCL_H 21 | 22 | 23 | class btSoftBodyVertexDataOpenCL : public btSoftBodyVertexData 24 | { 25 | protected: 26 | bool m_onGPU; 27 | cl_command_queue m_queue; 28 | 29 | public: 30 | btOpenCLBuffer m_clClothIdentifier; 31 | btOpenCLBuffer m_clVertexPosition; 32 | btOpenCLBuffer m_clVertexPreviousPosition; 33 | btOpenCLBuffer m_clVertexVelocity; 34 | btOpenCLBuffer m_clVertexForceAccumulator; 35 | btOpenCLBuffer m_clVertexNormal; 36 | btOpenCLBuffer m_clVertexInverseMass; 37 | btOpenCLBuffer m_clVertexArea; 38 | btOpenCLBuffer m_clVertexTriangleCount; 39 | public: 40 | btSoftBodyVertexDataOpenCL( cl_command_queue queue, cl_context ctx); 41 | 42 | virtual ~btSoftBodyVertexDataOpenCL(); 43 | 44 | virtual bool onAccelerator(); 45 | 46 | virtual bool moveToAccelerator(); 47 | 48 | virtual bool moveFromAccelerator(bool bCopy = false, bool bCopyMinimum = true); 49 | }; 50 | 51 | 52 | #endif // #ifndef BT_SOFT_BODY_SOLVER_VERTEX_DATA_OPENCL_H 53 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/PpuAddressSpace.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2010 Erwin Coumans http://bulletphysics.org 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | #ifndef BT_PPU_ADDRESS_SPACE_H 18 | #define BT_PPU_ADDRESS_SPACE_H 19 | 20 | 21 | #ifdef _WIN32 22 | //stop those casting warnings until we have a better solution for ppu_address_t / void* / uint64 conversions 23 | #pragma warning (disable: 4311) 24 | #pragma warning (disable: 4312) 25 | #endif //_WIN32 26 | 27 | 28 | #if defined(_WIN64) 29 | typedef unsigned __int64 ppu_address_t; 30 | #elif defined(__LP64__) || defined(__x86_64__) 31 | typedef uint64_t ppu_address_t; 32 | #else 33 | typedef uint32_t ppu_address_t; 34 | #endif //defined(_WIN64) 35 | 36 | #endif //BT_PPU_ADDRESS_SPACE_H 37 | 38 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuCollisionObjectWrapper.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2007 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "SpuCollisionObjectWrapper.h" 17 | #include "BulletCollision/CollisionShapes/btCollisionShape.h" 18 | 19 | SpuCollisionObjectWrapper::SpuCollisionObjectWrapper () 20 | { 21 | } 22 | 23 | #ifndef __SPU__ 24 | SpuCollisionObjectWrapper::SpuCollisionObjectWrapper (const btCollisionObject* collisionObject) 25 | { 26 | m_shapeType = collisionObject->getCollisionShape()->getShapeType (); 27 | m_collisionObjectPtr = (ppu_address_t)collisionObject; 28 | m_margin = collisionObject->getCollisionShape()->getMargin (); 29 | } 30 | #endif 31 | 32 | int 33 | SpuCollisionObjectWrapper::getShapeType () const 34 | { 35 | return m_shapeType; 36 | } 37 | 38 | float 39 | SpuCollisionObjectWrapper::getCollisionMargin () const 40 | { 41 | return m_margin; 42 | } 43 | 44 | ppu_address_t 45 | SpuCollisionObjectWrapper::getCollisionObjectPtr () const 46 | { 47 | return m_collisionObjectPtr; 48 | } 49 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuCollisionObjectWrapper.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2007 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SPU_COLLISION_OBJECT_WRAPPER_H 17 | #define BT_SPU_COLLISION_OBJECT_WRAPPER_H 18 | 19 | #include "PlatformDefinitions.h" 20 | #include "BulletCollision/CollisionDispatch/btCollisionObject.h" 21 | 22 | ATTRIBUTE_ALIGNED16(class) SpuCollisionObjectWrapper 23 | { 24 | protected: 25 | int m_shapeType; 26 | float m_margin; 27 | ppu_address_t m_collisionObjectPtr; 28 | 29 | public: 30 | SpuCollisionObjectWrapper (); 31 | 32 | SpuCollisionObjectWrapper (const btCollisionObject* collisionObject); 33 | 34 | int getShapeType () const; 35 | float getCollisionMargin () const; 36 | ppu_address_t getCollisionObjectPtr () const; 37 | }; 38 | 39 | 40 | #endif //BT_SPU_COLLISION_OBJECT_WRAPPER_H 41 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/SpuConvexPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | Bullet Continuous Collision Detection and Physics Library 4 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 5 | 6 | This software is provided 'as-is', without any express or implied warranty. 7 | In no event will the authors be held liable for any damages arising from the use of this software. 8 | Permission is granted to anyone to use this software for any purpose, 9 | including commercial applications, and to alter it and redistribute it freely, 10 | subject to the following restrictions: 11 | 12 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 13 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 14 | 3. This notice may not be removed or altered from any source distribution. 15 | */ 16 | 17 | 18 | #ifndef SPU_CONVEX_PENETRATION_DEPTH_H 19 | #define SPU_CONVEX_PENETRATION_DEPTH_H 20 | 21 | 22 | 23 | class btStackAlloc; 24 | class btIDebugDraw; 25 | #include "BulletCollision/NarrowphaseCollision/btConvexPenetrationDepthSolver.h" 26 | 27 | #include "LinearMath/btTransform.h" 28 | 29 | 30 | ///ConvexPenetrationDepthSolver provides an interface for penetration depth calculation. 31 | class SpuConvexPenetrationDepthSolver : public btConvexPenetrationDepthSolver 32 | { 33 | public: 34 | 35 | virtual ~SpuConvexPenetrationDepthSolver() {}; 36 | virtual bool calcPenDepth( SpuVoronoiSimplexSolver& simplexSolver, 37 | void* convexA,void* convexB,int shapeTypeA, int shapeTypeB, float marginA, float marginB, 38 | btTransform& transA,const btTransform& transB, 39 | btVector3& v, btVector3& pa, btVector3& pb, 40 | class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc, 41 | struct SpuConvexPolyhedronVertexData* convexVertexDataA, 42 | struct SpuConvexPolyhedronVertexData* convexVertexDataB 43 | ) const = 0; 44 | 45 | 46 | }; 47 | 48 | 49 | 50 | #endif //SPU_CONVEX_PENETRATION_DEPTH_H 51 | 52 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/SpuLocalSupport.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/SpuMinkowskiPenetrationDepthSolver.h: -------------------------------------------------------------------------------- 1 | 2 | /* 3 | Bullet Continuous Collision Detection and Physics Library 4 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 5 | 6 | This software is provided 'as-is', without any express or implied warranty. 7 | In no event will the authors be held liable for any damages arising from the use of this software. 8 | Permission is granted to anyone to use this software for any purpose, 9 | including commercial applications, and to alter it and redistribute it freely, 10 | subject to the following restrictions: 11 | 12 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 13 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 14 | 3. This notice may not be removed or altered from any source distribution. 15 | */ 16 | 17 | #ifndef MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 18 | #define MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 19 | 20 | 21 | #include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h" 22 | 23 | class btStackAlloc; 24 | class btIDebugDraw; 25 | class btVoronoiSimplexSolver; 26 | class btConvexShape; 27 | 28 | ///MinkowskiPenetrationDepthSolver implements bruteforce penetration depth estimation. 29 | ///Implementation is based on sampling the depth using support mapping, and using GJK step to get the witness points. 30 | class SpuMinkowskiPenetrationDepthSolver : public btConvexPenetrationDepthSolver 31 | { 32 | public: 33 | SpuMinkowskiPenetrationDepthSolver() {} 34 | virtual ~SpuMinkowskiPenetrationDepthSolver() {}; 35 | 36 | virtual bool calcPenDepth( btSimplexSolverInterface& simplexSolver, 37 | const btConvexShape* convexA,const btConvexShape* convexB, 38 | const btTransform& transA,const btTransform& transB, 39 | btVector3& v, btVector3& pa, btVector3& pb, 40 | class btIDebugDraw* debugDraw,btStackAlloc* stackAlloc 41 | ); 42 | 43 | 44 | }; 45 | 46 | 47 | #endif //MINKOWSKI_PENETRATION_DEPTH_SOLVER_H 48 | 49 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/SpuPreferredPenetrationDirections.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2007 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef _SPU_PREFERRED_PENETRATION_DIRECTIONS_H 17 | #define _SPU_PREFERRED_PENETRATION_DIRECTIONS_H 18 | 19 | 20 | #include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h" 21 | 22 | int spuGetNumPreferredPenetrationDirections(int shapeType, void* shape) 23 | { 24 | switch (shapeType) 25 | { 26 | case TRIANGLE_SHAPE_PROXYTYPE: 27 | { 28 | return 2; 29 | //spu_printf("2\n"); 30 | break; 31 | } 32 | default: 33 | { 34 | #if __ASSERT 35 | spu_printf("spuGetNumPreferredPenetrationDirections() - Unsupported bound type: %d.\n", shapeType); 36 | #endif // __ASSERT 37 | } 38 | } 39 | 40 | return 0; 41 | } 42 | 43 | void spuGetPreferredPenetrationDirection(int shapeType, void* shape, int index, btVector3& penetrationVector) 44 | { 45 | 46 | 47 | switch (shapeType) 48 | { 49 | case TRIANGLE_SHAPE_PROXYTYPE: 50 | { 51 | btVector3* vertices = (btVector3*)shape; 52 | ///calcNormal 53 | penetrationVector = (vertices[1]-vertices[0]).cross(vertices[2]-vertices[0]); 54 | penetrationVector.normalize(); 55 | if (index) 56 | penetrationVector *= btScalar(-1.); 57 | break; 58 | } 59 | default: 60 | { 61 | 62 | #if __ASSERT 63 | spu_printf("spuGetNumPreferredPenetrationDirections() - Unsupported bound type: %d.\n", shapeType); 64 | #endif // __ASSERT 65 | } 66 | } 67 | 68 | } 69 | 70 | #endif //_SPU_PREFERRED_PENETRATION_DIRECTIONS_H 71 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/boxBoxDistance.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/boxBoxDistance.cpp -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuNarrowPhaseCollisionTask/readme.txt: -------------------------------------------------------------------------------- 1 | Empty placeholder for future Libspe2 SPU task 2 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuSampleTask/SpuSampleTask.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, Copyright (c) 2007 Erwin Coumans 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | 14 | */ 15 | 16 | #ifndef SPU_SAMPLE_TASK_H 17 | #define SPU_SAMPLE_TASK_H 18 | 19 | #include "../PlatformDefinitions.h" 20 | #include "LinearMath/btScalar.h" 21 | #include "LinearMath/btVector3.h" 22 | #include "LinearMath/btMatrix3x3.h" 23 | 24 | #include "LinearMath/btAlignedAllocator.h" 25 | 26 | 27 | enum 28 | { 29 | CMD_SAMPLE_INTEGRATE_BODIES = 1, 30 | CMD_SAMPLE_PREDICT_MOTION_BODIES 31 | }; 32 | 33 | 34 | 35 | ATTRIBUTE_ALIGNED16(struct) SpuSampleTaskDesc 36 | { 37 | BT_DECLARE_ALIGNED_ALLOCATOR(); 38 | 39 | uint32_t m_sampleCommand; 40 | uint32_t m_taskId; 41 | 42 | uint64_t m_mainMemoryPtr; 43 | int m_sampleValue; 44 | 45 | 46 | }; 47 | 48 | 49 | void processSampleTask(void* userPtr, void* lsMemory); 50 | void* createSampleLocalStoreMemory(); 51 | 52 | 53 | #endif //SPU_SAMPLE_TASK_H 54 | 55 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/SpuSampleTask/readme.txt: -------------------------------------------------------------------------------- 1 | Empty placeholder for future Libspe2 SPU task 2 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/btGpuUtilsSharedCode.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, http://bulletphysics.org 3 | Copyright (C) 2006, 2009 Sony Computer Entertainment Inc. 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | //---------------------------------------------------------------------------------------- 17 | 18 | // Shared code for GPU-based utilities 19 | 20 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 21 | // Keep this file free from Bullet headers 22 | // will be compiled by both CPU and CUDA compilers 23 | // file with definitions of BT_GPU_xxx should be included first 24 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 25 | 26 | //---------------------------------------------------------------------------------------- 27 | 28 | #include "btGpuUtilsSharedDefs.h" 29 | 30 | //---------------------------------------------------------------------------------------- 31 | 32 | extern "C" 33 | { 34 | 35 | //---------------------------------------------------------------------------------------- 36 | 37 | //Round a / b to nearest higher integer value 38 | int BT_GPU_PREF(iDivUp)(int a, int b) 39 | { 40 | return (a % b != 0) ? (a / b + 1) : (a / b); 41 | } // iDivUp() 42 | 43 | //---------------------------------------------------------------------------------------- 44 | 45 | // compute grid and thread block size for a given number of elements 46 | void BT_GPU_PREF(computeGridSize)(int n, int blockSize, int &numBlocks, int &numThreads) 47 | { 48 | numThreads = BT_GPU_min(blockSize, n); 49 | numBlocks = BT_GPU_PREF(iDivUp)(n, numThreads); 50 | } // computeGridSize() 51 | 52 | //---------------------------------------------------------------------------------------- 53 | 54 | } // extern "C" 55 | 56 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/btGpuUtilsSharedDefs.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, http://bulletphysics.org 3 | Copyright (C) 2006, 2007 Sony Computer Entertainment Inc. 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | // Shared definitions for GPU-based utilities 17 | 18 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 19 | // Keep this file free from Bullet headers 20 | // it is included into both CUDA and CPU code 21 | // file with definitions of BT_GPU_xxx should be included first 22 | //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 23 | 24 | 25 | #ifndef BTGPUUTILSDHAREDDEFS_H 26 | #define BTGPUUTILSDHAREDDEFS_H 27 | 28 | 29 | extern "C" 30 | { 31 | 32 | 33 | //Round a / b to nearest higher integer value 34 | int BT_GPU_PREF(iDivUp)(int a, int b); 35 | 36 | // compute grid and thread block size for a given number of elements 37 | void BT_GPU_PREF(computeGridSize)(int n, int blockSize, int &numBlocks, int &numThreads); 38 | 39 | void BT_GPU_PREF(allocateArray)(void** devPtr, unsigned int size); 40 | void BT_GPU_PREF(freeArray)(void* devPtr); 41 | void BT_GPU_PREF(copyArrayFromDevice)(void* host, const void* device, unsigned int size); 42 | void BT_GPU_PREF(copyArrayToDevice)(void* device, const void* host, unsigned int size); 43 | void BT_GPU_PREF(registerGLBufferObject(unsigned int vbo)); 44 | void* BT_GPU_PREF(mapGLBufferObject(unsigned int vbo)); 45 | void BT_GPU_PREF(unmapGLBufferObject(unsigned int vbo)); 46 | 47 | 48 | } // extern "C" 49 | 50 | 51 | #endif // BTGPUUTILSDHAREDDEFS_H 52 | 53 | -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/btParallelConstraintSolver.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletMultiThreaded/btParallelConstraintSolver.cpp -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/btParallelConstraintSolver.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletMultiThreaded/btParallelConstraintSolver.h -------------------------------------------------------------------------------- /Bullet/BulletMultiThreaded/btThreadSupportInterface.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2007 Erwin Coumans http://bulletphysics.com 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #include "btThreadSupportInterface.h" 17 | 18 | btThreadSupportInterface::~btThreadSupportInterface() 19 | { 20 | 21 | } 22 | 23 | -------------------------------------------------------------------------------- /Bullet/BulletSoftBody/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | INCLUDE_DIRECTORIES( 3 | ${BULLET_PHYSICS_SOURCE_DIR}/src 4 | 5 | ) 6 | 7 | #SUBDIRS( Solvers ) 8 | 9 | SET(BulletSoftBody_SRCS 10 | btSoftBody.cpp 11 | btSoftBodyConcaveCollisionAlgorithm.cpp 12 | btSoftBodyHelpers.cpp 13 | btSoftBodyRigidBodyCollisionConfiguration.cpp 14 | btSoftRigidCollisionAlgorithm.cpp 15 | btSoftRigidDynamicsWorld.cpp 16 | btSoftSoftCollisionAlgorithm.cpp 17 | btDefaultSoftBodySolver.cpp 18 | 19 | ) 20 | 21 | SET(BulletSoftBody_HDRS 22 | btSoftBody.h 23 | btSoftBodyData.h 24 | btSoftBodyConcaveCollisionAlgorithm.h 25 | btSoftBodyHelpers.h 26 | btSoftBodyRigidBodyCollisionConfiguration.h 27 | btSoftRigidCollisionAlgorithm.h 28 | btSoftRigidDynamicsWorld.h 29 | btSoftSoftCollisionAlgorithm.h 30 | btSparseSDF.h 31 | 32 | btSoftBodySolvers.h 33 | btDefaultSoftBodySolver.h 34 | 35 | btSoftBodySolverVertexBuffer.h 36 | ) 37 | 38 | 39 | 40 | ADD_LIBRARY(BulletSoftBody ${BulletSoftBody_SRCS} ${BulletSoftBody_HDRS}) 41 | SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES VERSION ${BULLET_VERSION}) 42 | SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES SOVERSION ${BULLET_VERSION}) 43 | IF (BUILD_SHARED_LIBS) 44 | TARGET_LINK_LIBRARIES(BulletSoftBody BulletDynamics) 45 | ENDIF (BUILD_SHARED_LIBS) 46 | 47 | IF (INSTALL_LIBS) 48 | IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 49 | IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 50 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 51 | INSTALL(TARGETS BulletSoftBody DESTINATION .) 52 | ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 53 | INSTALL(TARGETS BulletSoftBody DESTINATION lib${LIB_SUFFIX}) 54 | INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} 55 | DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN 56 | ".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) 57 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 58 | ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 59 | 60 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 61 | SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES FRAMEWORK true) 62 | SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES PUBLIC_HEADER "${BulletSoftBody_HDRS}") 63 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 64 | ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 65 | ENDIF (INSTALL_LIBS) 66 | -------------------------------------------------------------------------------- /Bullet/BulletSoftBody/btDefaultSoftBodySolver.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SOFT_BODY_DEFAULT_SOLVER_H 17 | #define BT_SOFT_BODY_DEFAULT_SOLVER_H 18 | 19 | 20 | #include "BulletSoftBody/btSoftBodySolvers.h" 21 | #include "btSoftBodySolverVertexBuffer.h" 22 | struct btCollisionObjectWrapper; 23 | 24 | class btDefaultSoftBodySolver : public btSoftBodySolver 25 | { 26 | protected: 27 | /** Variable to define whether we need to update solver constants on the next iteration */ 28 | bool m_updateSolverConstants; 29 | 30 | btAlignedObjectArray< btSoftBody * > m_softBodySet; 31 | 32 | 33 | public: 34 | btDefaultSoftBodySolver(); 35 | 36 | virtual ~btDefaultSoftBodySolver(); 37 | 38 | virtual SolverTypes getSolverType() const 39 | { 40 | return DEFAULT_SOLVER; 41 | } 42 | 43 | virtual bool checkInitialized(); 44 | 45 | virtual void updateSoftBodies( ); 46 | 47 | virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies,bool forceUpdate=false ); 48 | 49 | virtual void copyBackToSoftBodies(bool bMove = true); 50 | 51 | virtual void solveConstraints( float solverdt ); 52 | 53 | virtual void predictMotion( float solverdt ); 54 | 55 | virtual void copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer ); 56 | 57 | virtual void processCollision( btSoftBody *, const btCollisionObjectWrapper* ); 58 | 59 | virtual void processCollision( btSoftBody*, btSoftBody* ); 60 | 61 | }; 62 | 63 | #endif // #ifndef BT_ACCELERATED_SOFT_BODY_CPU_SOLVER_H 64 | -------------------------------------------------------------------------------- /Bullet/BulletSoftBody/btSoftBody.cpp: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/BulletSoftBody/btSoftBody.cpp -------------------------------------------------------------------------------- /Bullet/BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION 17 | #define BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION 18 | 19 | #include "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h" 20 | 21 | class btVoronoiSimplexSolver; 22 | class btGjkEpaPenetrationDepthSolver; 23 | 24 | 25 | ///btSoftBodyRigidBodyCollisionConfiguration add softbody interaction on top of btDefaultCollisionConfiguration 26 | class btSoftBodyRigidBodyCollisionConfiguration : public btDefaultCollisionConfiguration 27 | { 28 | 29 | //default CreationFunctions, filling the m_doubleDispatch table 30 | btCollisionAlgorithmCreateFunc* m_softSoftCreateFunc; 31 | btCollisionAlgorithmCreateFunc* m_softRigidConvexCreateFunc; 32 | btCollisionAlgorithmCreateFunc* m_swappedSoftRigidConvexCreateFunc; 33 | btCollisionAlgorithmCreateFunc* m_softRigidConcaveCreateFunc; 34 | btCollisionAlgorithmCreateFunc* m_swappedSoftRigidConcaveCreateFunc; 35 | 36 | public: 37 | 38 | btSoftBodyRigidBodyCollisionConfiguration(const btDefaultCollisionConstructionInfo& constructionInfo = btDefaultCollisionConstructionInfo()); 39 | 40 | virtual ~btSoftBodyRigidBodyCollisionConfiguration(); 41 | 42 | ///creation of soft-soft and soft-rigid, and otherwise fallback to base class implementation 43 | virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1); 44 | 45 | }; 46 | 47 | #endif //BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION 48 | 49 | -------------------------------------------------------------------------------- /Bullet/BulletSoftBody/premake4.lua: -------------------------------------------------------------------------------- 1 | project "BulletSoftBody" 2 | 3 | kind "StaticLib" 4 | targetdir "../../lib" 5 | includedirs { 6 | "..", 7 | } 8 | files { 9 | "**.cpp", 10 | "**.h" 11 | } -------------------------------------------------------------------------------- /Bullet/LinearMath/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | 2 | INCLUDE_DIRECTORIES( 3 | ${BULLET_PHYSICS_SOURCE_DIR}/src 4 | ) 5 | 6 | SET(LinearMath_SRCS 7 | btAlignedAllocator.cpp 8 | btConvexHull.cpp 9 | btConvexHullComputer.cpp 10 | btGeometryUtil.cpp 11 | btPolarDecomposition.cpp 12 | btQuickprof.cpp 13 | btSerializer.cpp 14 | btVector3.cpp 15 | ) 16 | 17 | SET(LinearMath_HDRS 18 | btAabbUtil2.h 19 | btAlignedAllocator.h 20 | btAlignedObjectArray.h 21 | btConvexHull.h 22 | btConvexHullComputer.h 23 | btDefaultMotionState.h 24 | btGeometryUtil.h 25 | btGrahamScan2dConvexHull.h 26 | btHashMap.h 27 | btIDebugDraw.h 28 | btList.h 29 | btMatrix3x3.h 30 | btMinMax.h 31 | btMotionState.h 32 | btPolarDecomposition.h 33 | btPoolAllocator.h 34 | btQuadWord.h 35 | btQuaternion.h 36 | btQuickprof.h 37 | btRandom.h 38 | btScalar.h 39 | btSerializer.h 40 | btStackAlloc.h 41 | btTransform.h 42 | btTransformUtil.h 43 | btVector3.h 44 | ) 45 | 46 | ADD_LIBRARY(LinearMath ${LinearMath_SRCS} ${LinearMath_HDRS}) 47 | SET_TARGET_PROPERTIES(LinearMath PROPERTIES VERSION ${BULLET_VERSION}) 48 | SET_TARGET_PROPERTIES(LinearMath PROPERTIES SOVERSION ${BULLET_VERSION}) 49 | 50 | IF (INSTALL_LIBS) 51 | IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 52 | #FILES_MATCHING requires CMake 2.6 53 | IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 54 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 55 | INSTALL(TARGETS LinearMath DESTINATION .) 56 | ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 57 | INSTALL(TARGETS LinearMath DESTINATION lib${LIB_SUFFIX}) 58 | INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} 59 | DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN 60 | ".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) 61 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 62 | ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 63 | 64 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 65 | SET_TARGET_PROPERTIES(LinearMath PROPERTIES FRAMEWORK true) 66 | SET_TARGET_PROPERTIES(LinearMath PROPERTIES PUBLIC_HEADER "${LinearMath_HDRS}") 67 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 68 | ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 69 | ENDIF (INSTALL_LIBS) 70 | -------------------------------------------------------------------------------- /Bullet/LinearMath/btDefaultMotionState.h: -------------------------------------------------------------------------------- 1 | #ifndef BT_DEFAULT_MOTION_STATE_H 2 | #define BT_DEFAULT_MOTION_STATE_H 3 | 4 | #include "btMotionState.h" 5 | 6 | ///The btDefaultMotionState provides a common implementation to synchronize world transforms with offsets. 7 | ATTRIBUTE_ALIGNED16(struct) btDefaultMotionState : public btMotionState 8 | { 9 | btTransform m_graphicsWorldTrans; 10 | btTransform m_centerOfMassOffset; 11 | btTransform m_startWorldTrans; 12 | void* m_userPointer; 13 | 14 | BT_DECLARE_ALIGNED_ALLOCATOR(); 15 | 16 | btDefaultMotionState(const btTransform& startTrans = btTransform::getIdentity(),const btTransform& centerOfMassOffset = btTransform::getIdentity()) 17 | : m_graphicsWorldTrans(startTrans), 18 | m_centerOfMassOffset(centerOfMassOffset), 19 | m_startWorldTrans(startTrans), 20 | m_userPointer(0) 21 | 22 | { 23 | } 24 | 25 | ///synchronizes world transform from user to physics 26 | virtual void getWorldTransform(btTransform& centerOfMassWorldTrans ) const 27 | { 28 | centerOfMassWorldTrans = m_centerOfMassOffset.inverse() * m_graphicsWorldTrans ; 29 | } 30 | 31 | ///synchronizes world transform from physics to user 32 | ///Bullet only calls the update of worldtransform for active objects 33 | virtual void setWorldTransform(const btTransform& centerOfMassWorldTrans) 34 | { 35 | m_graphicsWorldTrans = centerOfMassWorldTrans * m_centerOfMassOffset ; 36 | } 37 | 38 | 39 | 40 | }; 41 | 42 | #endif //BT_DEFAULT_MOTION_STATE_H 43 | -------------------------------------------------------------------------------- /Bullet/LinearMath/btGeometryUtil.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | 16 | #ifndef BT_GEOMETRY_UTIL_H 17 | #define BT_GEOMETRY_UTIL_H 18 | 19 | #include "btVector3.h" 20 | #include "btAlignedObjectArray.h" 21 | 22 | ///The btGeometryUtil helper class provides a few methods to convert between plane equations and vertices. 23 | class btGeometryUtil 24 | { 25 | public: 26 | 27 | 28 | static void getPlaneEquationsFromVertices(btAlignedObjectArray& vertices, btAlignedObjectArray& planeEquationsOut ); 29 | 30 | static void getVerticesFromPlaneEquations(const btAlignedObjectArray& planeEquations , btAlignedObjectArray& verticesOut ); 31 | 32 | static bool isInside(const btAlignedObjectArray& vertices, const btVector3& planeNormal, btScalar margin); 33 | 34 | static bool isPointInsidePlanes(const btAlignedObjectArray& planeEquations, const btVector3& point, btScalar margin); 35 | 36 | static bool areVerticesBehindPlane(const btVector3& planeNormal, const btAlignedObjectArray& vertices, btScalar margin); 37 | 38 | }; 39 | 40 | 41 | #endif //BT_GEOMETRY_UTIL_H 42 | 43 | -------------------------------------------------------------------------------- /Bullet/LinearMath/btMinMax.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | 16 | 17 | #ifndef BT_GEN_MINMAX_H 18 | #define BT_GEN_MINMAX_H 19 | 20 | #include "btScalar.h" 21 | 22 | template 23 | SIMD_FORCE_INLINE const T& btMin(const T& a, const T& b) 24 | { 25 | return a < b ? a : b ; 26 | } 27 | 28 | template 29 | SIMD_FORCE_INLINE const T& btMax(const T& a, const T& b) 30 | { 31 | return a > b ? a : b; 32 | } 33 | 34 | template 35 | SIMD_FORCE_INLINE const T& btClamped(const T& a, const T& lb, const T& ub) 36 | { 37 | return a < lb ? lb : (ub < a ? ub : a); 38 | } 39 | 40 | template 41 | SIMD_FORCE_INLINE void btSetMin(T& a, const T& b) 42 | { 43 | if (b < a) 44 | { 45 | a = b; 46 | } 47 | } 48 | 49 | template 50 | SIMD_FORCE_INLINE void btSetMax(T& a, const T& b) 51 | { 52 | if (a < b) 53 | { 54 | a = b; 55 | } 56 | } 57 | 58 | template 59 | SIMD_FORCE_INLINE void btClamp(T& a, const T& lb, const T& ub) 60 | { 61 | if (a < lb) 62 | { 63 | a = lb; 64 | } 65 | else if (ub < a) 66 | { 67 | a = ub; 68 | } 69 | } 70 | 71 | #endif //BT_GEN_MINMAX_H 72 | -------------------------------------------------------------------------------- /Bullet/LinearMath/btMotionState.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library 3 | Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 4 | 5 | This software is provided 'as-is', without any express or implied warranty. 6 | In no event will the authors be held liable for any damages arising from the use of this software. 7 | Permission is granted to anyone to use this software for any purpose, 8 | including commercial applications, and to alter it and redistribute it freely, 9 | subject to the following restrictions: 10 | 11 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 12 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 13 | 3. This notice may not be removed or altered from any source distribution. 14 | */ 15 | 16 | #ifndef BT_MOTIONSTATE_H 17 | #define BT_MOTIONSTATE_H 18 | 19 | #include "btTransform.h" 20 | 21 | ///The btMotionState interface class allows the dynamics world to synchronize and interpolate the updated world transforms with graphics 22 | ///For optimizations, potentially only moving objects get synchronized (using setWorldPosition/setWorldOrientation) 23 | class btMotionState 24 | { 25 | public: 26 | 27 | virtual ~btMotionState() 28 | { 29 | 30 | } 31 | 32 | virtual void getWorldTransform(btTransform& worldTrans ) const =0; 33 | 34 | //Bullet only calls the update of worldtransform for active objects 35 | virtual void setWorldTransform(const btTransform& worldTrans)=0; 36 | 37 | 38 | }; 39 | 40 | #endif //BT_MOTIONSTATE_H 41 | -------------------------------------------------------------------------------- /Bullet/LinearMath/btRandom.h: -------------------------------------------------------------------------------- 1 | /* 2 | Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/ 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | */ 14 | 15 | 16 | 17 | #ifndef BT_GEN_RANDOM_H 18 | #define BT_GEN_RANDOM_H 19 | 20 | #ifdef MT19937 21 | 22 | #include 23 | #include 24 | 25 | #define GEN_RAND_MAX UINT_MAX 26 | 27 | SIMD_FORCE_INLINE void GEN_srand(unsigned int seed) { init_genrand(seed); } 28 | SIMD_FORCE_INLINE unsigned int GEN_rand() { return genrand_int32(); } 29 | 30 | #else 31 | 32 | #include 33 | 34 | #define GEN_RAND_MAX RAND_MAX 35 | 36 | SIMD_FORCE_INLINE void GEN_srand(unsigned int seed) { srand(seed); } 37 | SIMD_FORCE_INLINE unsigned int GEN_rand() { return rand(); } 38 | 39 | #endif 40 | 41 | #endif //BT_GEN_RANDOM_H 42 | 43 | -------------------------------------------------------------------------------- /Bullet/LinearMath/premake4.lua: -------------------------------------------------------------------------------- 1 | project "LinearMath" 2 | 3 | kind "StaticLib" 4 | targetdir "../../lib" 5 | includedirs { 6 | "..", 7 | } 8 | files { 9 | "**.cpp", 10 | "**.h" 11 | } -------------------------------------------------------------------------------- /Bullet/MiniCL/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | #MiniCL provides a small subset of OpenCL 2 | 3 | INCLUDE_DIRECTORIES( 4 | ${BULLET_PHYSICS_SOURCE_DIR}/src 5 | ${VECTOR_MATH_INCLUDE} 6 | ) 7 | 8 | SET(MiniCL_SRCS 9 | MiniCL.cpp 10 | MiniCLTaskScheduler.cpp 11 | MiniCLTask/MiniCLTask.cpp 12 | ) 13 | 14 | SET(Root_HDRS 15 | MiniCLTaskScheduler.h 16 | cl.h 17 | cl_gl.h 18 | cl_platform.h 19 | cl_MiniCL_Defs.h 20 | ) 21 | 22 | SET(MiniCLTask_HDRS 23 | MiniCLTask/MiniCLTask.h 24 | ) 25 | 26 | SET(MiniCL_HDRS 27 | ${Root_HDRS} 28 | ${MiniCLTask_HDRS} 29 | ) 30 | 31 | ADD_LIBRARY(MiniCL ${MiniCL_SRCS} ${MiniCL_HDRS} ) 32 | SET_TARGET_PROPERTIES(MiniCL PROPERTIES VERSION ${BULLET_VERSION}) 33 | SET_TARGET_PROPERTIES(MiniCL PROPERTIES SOVERSION ${BULLET_VERSION}) 34 | 35 | 36 | IF (BUILD_SHARED_LIBS) 37 | TARGET_LINK_LIBRARIES(MiniCL BulletMultiThreaded BulletDynamics BulletCollision) 38 | ENDIF (BUILD_SHARED_LIBS) 39 | 40 | IF (INSTALL_LIBS) 41 | IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 42 | #INSTALL of other files requires CMake 2.6 43 | IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 44 | # IF(INSTALL_EXTRA_LIBS) 45 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 46 | INSTALL(TARGETS MiniCL DESTINATION .) 47 | ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 48 | INSTALL(TARGETS MiniCL DESTINATION lib${LIB_SUFFIX}) 49 | INSTALL(DIRECTORY 50 | ${CMAKE_CURRENT_SOURCE_DIR} DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING 51 | PATTERN "*.h" PATTERN ".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE) 52 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 53 | # ENDIF (INSTALL_EXTRA_LIBS) 54 | ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5) 55 | 56 | IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 57 | SET_TARGET_PROPERTIES(MiniCL PROPERTIES FRAMEWORK true) 58 | 59 | SET_TARGET_PROPERTIES(MiniCL PROPERTIES PUBLIC_HEADER "${Root_HDRS}") 60 | # Have to list out sub-directories manually: 61 | SET_PROPERTY(SOURCE ${MiniCLTask_HDRS} PROPERTY MACOSX_PACKAGE_LOCATION Headers/MiniCLTask) 62 | 63 | ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK) 64 | ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES) 65 | ENDIF (INSTALL_LIBS) 66 | 67 | -------------------------------------------------------------------------------- /Bullet/MiniCL/MiniCLTask/MiniCLTask.h: -------------------------------------------------------------------------------- 1 | /* 2 | Bullet Continuous Collision Detection and Physics Library, Copyright (c) 2007 Erwin Coumans 3 | 4 | This software is provided 'as-is', without any express or implied warranty. 5 | In no event will the authors be held liable for any damages arising from the use of this software. 6 | Permission is granted to anyone to use this software for any purpose, 7 | including commercial applications, and to alter it and redistribute it freely, 8 | subject to the following restrictions: 9 | 10 | 1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. 11 | 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 12 | 3. This notice may not be removed or altered from any source distribution. 13 | 14 | */ 15 | 16 | #ifndef MINICL__TASK_H 17 | #define MINICL__TASK_H 18 | 19 | #include "BulletMultiThreaded/PlatformDefinitions.h" 20 | #include "LinearMath/btScalar.h" 21 | 22 | #include "LinearMath/btAlignedAllocator.h" 23 | 24 | 25 | #define MINICL_MAX_ARGLENGTH (sizeof(void*)) 26 | #define MINI_CL_MAX_ARG 16 27 | #define MINI_CL_MAX_KERNEL_NAME 256 28 | 29 | struct MiniCLKernel; 30 | 31 | ATTRIBUTE_ALIGNED16(struct) MiniCLTaskDesc 32 | { 33 | BT_DECLARE_ALIGNED_ALLOCATOR(); 34 | 35 | MiniCLTaskDesc() 36 | { 37 | for (int i=0;i m_originTransform; 3 | BulletCollision/CollisionShapes/btCompoundShape.cpp line84 add m_originTransform.push_back(localTransform); 4 | BulletCollision/CollisionShapes/btCompoundShape.cpp line284 changed to btTransform childTrans = m_originTransform[i]; 5 | BulletCollision/CollisionShapes/btCompoundShape.cpp line288 changed to m_children[i].m_childShape->setLocalScaling(scaling); 6 | BulletDynamics/Dynamics/btRigidBody.h line57 added public 7 | BulletDynamics/Dynamics/btRigidBody.h line94 move m_angularFactor to public 8 | BulletDynamics/Dynamics/btRigidBody.h line95 move m_invMass to public 9 | BulletDynamics/Character/btKinematicCharacterController.h line38 changed protected to public 10 | BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h line38 changed protected to public 11 | BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h line57 added bool m_collisionCallbackOn; 12 | BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h line59 added btAlignedObjectArray m_vehicles; 13 | BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp line509 added m_vehicles.push_back(vehicle); 14 | BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp line515 added m_vehicles.remove(vehicle); 15 | BulletDynamics/ConstraintSolver/btTypedConstraint.h line318 added public 16 | BulletDynamics/ConstraintSolver/btHingeConstraint.h line52 removed #ifdef IN_PARALLELL_SOLVER 17 | BulletDynamics/ConstraintSolver/btHingeConstraint.h removed all #ifdef _BT_USE_CENTER_LIMIT_ 18 | BulletDynamics/ConstraintSolver/btHingeConstraint.cpp removed all #ifdef _BT_USE_CENTER_LIMIT_ 19 | BulletDynamics/ConstraintSolver/btConeTwistConstraint.h line55 removed #ifdef IN_PARALLELL_SOLVER 20 | BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.h line273 changed protected to public 21 | BulletDynamics/ConstraintSolver/btSliderConstraint.h line65 changed protected to public 22 | LinearMath/btMatrix3x3.h line33 add public 23 | LinearMath/btTransform.h line36 add public -------------------------------------------------------------------------------- /Bullet/exports.txt: -------------------------------------------------------------------------------- 1 | # built in symbols that must always be preserved 2 | _start1 3 | malloc 4 | free 5 | memcpy 6 | memmove 7 | flascc_uiTickProc 8 | _sync_synchronize 9 | 10 | # symbols for C++ exception handling 11 | _Unwind_SjLj_Register 12 | _Unwind_SjLj_Resume 13 | _Unwind_SjLj_Unregister 14 | _Unwind_SjLj_RaiseException 15 | 16 | # symbols from libm.a 17 | __muldi3 18 | 19 | # symbols for the GLUT based examples 20 | _avm2_glut_keyhandler 21 | glutMainLoopBody -------------------------------------------------------------------------------- /Bullet/libbulletcollision.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/libbulletcollision.a -------------------------------------------------------------------------------- /Bullet/libbulletdynamics.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/libbulletdynamics.a -------------------------------------------------------------------------------- /Bullet/libbulletmath.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/away3d/awayphysics-core-fp11/5906960bc4909e6735ebd83e58666fe49c2e7684/Bullet/libbulletmath.a -------------------------------------------------------------------------------- /Bullet/vectormath/vmInclude.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef __VM_INCLUDE_H 3 | #define __VM_INCLUDE_H 4 | 5 | #include "LinearMath/btScalar.h" 6 | 7 | #if defined (USE_SYSTEM_VECTORMATH) || defined (__CELLOS_LV2__) 8 | #include 9 | #else //(USE_SYSTEM_VECTORMATH) 10 | #if defined (BT_USE_SSE) 11 | #include "sse/vectormath_aos.h" 12 | #else //all other platforms 13 | #if defined (BT_USE_NEON) 14 | #include "neon/vectormath_aos.h" 15 | #else 16 | #include "scalar/vectormath_aos.h" 17 | #endif 18 | #endif //(BT_USE_SSE) && defined (_WIN32) 19 | #endif //(USE_SYSTEM_VECTORMATH) 20 | 21 | 22 | 23 | typedef Vectormath::Aos::Vector3 vmVector3; 24 | typedef Vectormath::Aos::Quat vmQuat; 25 | typedef Vectormath::Aos::Matrix3 vmMatrix3; 26 | typedef Vectormath::Aos::Transform3 vmTransform3; 27 | typedef Vectormath::Aos::Point3 vmPoint3; 28 | 29 | #endif //__VM_INCLUDE_H 30 | 31 | 32 | -------------------------------------------------------------------------------- /README.txt: -------------------------------------------------------------------------------- 1 | Away Physics - 3D physics library for the Away3D Engine in Flash Player 11 --------------------------------------------------------------------------------