summaryrefslogtreecommitdiff
path: root/modules/bullet
diff options
context:
space:
mode:
Diffstat (limited to 'modules/bullet')
-rw-r--r--modules/bullet/SCsub357
-rw-r--r--modules/bullet/area_bullet.cpp48
-rw-r--r--modules/bullet/area_bullet.h16
-rw-r--r--modules/bullet/btRayShape.cpp1
-rw-r--r--modules/bullet/bullet_physics_server.cpp426
-rw-r--r--modules/bullet/bullet_physics_server.h20
-rw-r--r--modules/bullet/bullet_utilities.h2
-rw-r--r--modules/bullet/collision_object_bullet.cpp14
-rw-r--r--modules/bullet/collision_object_bullet.h8
-rw-r--r--modules/bullet/cone_twist_joint_bullet.cpp28
-rw-r--r--modules/bullet/cone_twist_joint_bullet.h6
-rw-r--r--modules/bullet/config.py10
-rw-r--r--modules/bullet/constraint_bullet.cpp4
-rw-r--r--modules/bullet/constraint_bullet.h2
-rw-r--r--modules/bullet/doc_classes/BulletPhysicsDirectBodyState.xml13
-rw-r--r--modules/bullet/doc_classes/BulletPhysicsServer.xml13
-rw-r--r--modules/bullet/generic_6dof_joint_bullet.cpp104
-rw-r--r--modules/bullet/generic_6dof_joint_bullet.h12
-rw-r--r--modules/bullet/godot_collision_configuration.cpp4
-rw-r--r--modules/bullet/godot_result_callbacks.cpp8
-rw-r--r--modules/bullet/godot_result_callbacks.h14
-rw-r--r--modules/bullet/hinge_joint_bullet.cpp58
-rw-r--r--modules/bullet/hinge_joint_bullet.h10
-rw-r--r--modules/bullet/joint_bullet.h4
-rw-r--r--modules/bullet/pin_joint_bullet.cpp16
-rw-r--r--modules/bullet/pin_joint_bullet.h6
-rw-r--r--modules/bullet/register_types.cpp8
-rw-r--r--modules/bullet/rid_bullet.h8
-rw-r--r--modules/bullet/rigid_body_bullet.cpp214
-rw-r--r--modules/bullet/rigid_body_bullet.h44
-rw-r--r--modules/bullet/shape_bullet.cpp46
-rw-r--r--modules/bullet/shape_bullet.h22
-rw-r--r--modules/bullet/slider_joint_bullet.cpp94
-rw-r--r--modules/bullet/slider_joint_bullet.h6
-rw-r--r--modules/bullet/soft_body_bullet.cpp24
-rw-r--r--modules/bullet/soft_body_bullet.h4
-rw-r--r--modules/bullet/space_bullet.cpp146
-rw-r--r--modules/bullet/space_bullet.h32
38 files changed, 910 insertions, 942 deletions
diff --git a/modules/bullet/SCsub b/modules/bullet/SCsub
index 02d0a31a69..692c749886 100644
--- a/modules/bullet/SCsub
+++ b/modules/bullet/SCsub
@@ -1,208 +1,203 @@
#!/usr/bin/env python
-Import('env')
-Import('env_modules')
+Import("env")
+Import("env_modules")
env_bullet = env_modules.Clone()
# Thirdparty source files
-if env['builtin_bullet']:
+if env["builtin_bullet"]:
# Build only version 2 for now (as of 2.89)
# Sync file list with relevant upstream CMakeLists.txt for each folder.
thirdparty_dir = "#thirdparty/bullet/"
bullet2_src = [
# BulletCollision
- "BulletCollision/BroadphaseCollision/btAxisSweep3.cpp"
- , "BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp"
- , "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp"
- , "BulletCollision/BroadphaseCollision/btDbvt.cpp"
- , "BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp"
- , "BulletCollision/BroadphaseCollision/btDispatcher.cpp"
- , "BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp"
- , "BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp"
- , "BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp"
- , "BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp"
- , "BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp"
- , "BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp"
- , "BulletCollision/CollisionDispatch/btCollisionObject.cpp"
- , "BulletCollision/CollisionDispatch/btCollisionWorld.cpp"
- , "BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp"
- , "BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp"
- , "BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btGhostObject.cpp"
- , "BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp"
- , "BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp"
- , "BulletCollision/CollisionDispatch/btManifoldResult.cpp"
- , "BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp"
- , "BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp"
- , "BulletCollision/CollisionDispatch/btUnionFind.cpp"
- , "BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp"
- , "BulletCollision/CollisionShapes/btBoxShape.cpp"
- , "BulletCollision/CollisionShapes/btBox2dShape.cpp"
- , "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp"
- , "BulletCollision/CollisionShapes/btCapsuleShape.cpp"
- , "BulletCollision/CollisionShapes/btCollisionShape.cpp"
- , "BulletCollision/CollisionShapes/btCompoundShape.cpp"
- , "BulletCollision/CollisionShapes/btConcaveShape.cpp"
- , "BulletCollision/CollisionShapes/btConeShape.cpp"
- , "BulletCollision/CollisionShapes/btConvexHullShape.cpp"
- , "BulletCollision/CollisionShapes/btConvexInternalShape.cpp"
- , "BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp"
- , "BulletCollision/CollisionShapes/btConvexPolyhedron.cpp"
- , "BulletCollision/CollisionShapes/btConvexShape.cpp"
- , "BulletCollision/CollisionShapes/btConvex2dShape.cpp"
- , "BulletCollision/CollisionShapes/btConvexTriangleMeshShape.cpp"
- , "BulletCollision/CollisionShapes/btCylinderShape.cpp"
- , "BulletCollision/CollisionShapes/btEmptyShape.cpp"
- , "BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp"
- , "BulletCollision/CollisionShapes/btMiniSDF.cpp"
- , "BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp"
- , "BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp"
- , "BulletCollision/CollisionShapes/btMultiSphereShape.cpp"
- , "BulletCollision/CollisionShapes/btOptimizedBvh.cpp"
- , "BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp"
- , "BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp"
- , "BulletCollision/CollisionShapes/btSdfCollisionShape.cpp"
- , "BulletCollision/CollisionShapes/btShapeHull.cpp"
- , "BulletCollision/CollisionShapes/btSphereShape.cpp"
- , "BulletCollision/CollisionShapes/btStaticPlaneShape.cpp"
- , "BulletCollision/CollisionShapes/btStridingMeshInterface.cpp"
- , "BulletCollision/CollisionShapes/btTetrahedronShape.cpp"
- , "BulletCollision/CollisionShapes/btTriangleBuffer.cpp"
- , "BulletCollision/CollisionShapes/btTriangleCallback.cpp"
- , "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.cpp"
- , "BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.cpp"
- , "BulletCollision/CollisionShapes/btTriangleMesh.cpp"
- , "BulletCollision/CollisionShapes/btTriangleMeshShape.cpp"
- , "BulletCollision/CollisionShapes/btUniformScalingShape.cpp"
- , "BulletCollision/Gimpact/btContactProcessing.cpp"
- , "BulletCollision/Gimpact/btGenericPoolAllocator.cpp"
- , "BulletCollision/Gimpact/btGImpactBvh.cpp"
- , "BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp"
- , "BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp"
- , "BulletCollision/Gimpact/btGImpactShape.cpp"
- , "BulletCollision/Gimpact/btTriangleShapeEx.cpp"
- , "BulletCollision/Gimpact/gim_box_set.cpp"
- , "BulletCollision/Gimpact/gim_contact.cpp"
- , "BulletCollision/Gimpact/gim_memory.cpp"
- , "BulletCollision/Gimpact/gim_tri_collision.cpp"
- , "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp"
- , "BulletCollision/NarrowPhaseCollision/btConvexCast.cpp"
- , "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp"
- , "BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp"
- , "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp"
- , "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp"
- , "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp"
- , "BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp"
- , "BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp"
- , "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp"
- , "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp"
- , "BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp"
-
+ "BulletCollision/BroadphaseCollision/btAxisSweep3.cpp",
+ "BulletCollision/BroadphaseCollision/btBroadphaseProxy.cpp",
+ "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.cpp",
+ "BulletCollision/BroadphaseCollision/btDbvt.cpp",
+ "BulletCollision/BroadphaseCollision/btDbvtBroadphase.cpp",
+ "BulletCollision/BroadphaseCollision/btDispatcher.cpp",
+ "BulletCollision/BroadphaseCollision/btOverlappingPairCache.cpp",
+ "BulletCollision/BroadphaseCollision/btQuantizedBvh.cpp",
+ "BulletCollision/BroadphaseCollision/btSimpleBroadphase.cpp",
+ "BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btBox2dBox2dCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btBoxBoxDetector.cpp",
+ "BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp",
+ "BulletCollision/CollisionDispatch/btCollisionDispatcherMt.cpp",
+ "BulletCollision/CollisionDispatch/btCollisionObject.cpp",
+ "BulletCollision/CollisionDispatch/btCollisionWorld.cpp",
+ "BulletCollision/CollisionDispatch/btCollisionWorldImporter.cpp",
+ "BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btConvexConvexAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btConvex2dConvex2dAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp",
+ "BulletCollision/CollisionDispatch/btEmptyCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btGhostObject.cpp",
+ "BulletCollision/CollisionDispatch/btHashedSimplePairCache.cpp",
+ "BulletCollision/CollisionDispatch/btInternalEdgeUtility.cpp",
+ "BulletCollision/CollisionDispatch/btManifoldResult.cpp",
+ "BulletCollision/CollisionDispatch/btSimulationIslandManager.cpp",
+ "BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp",
+ "BulletCollision/CollisionDispatch/btUnionFind.cpp",
+ "BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp",
+ "BulletCollision/CollisionShapes/btBoxShape.cpp",
+ "BulletCollision/CollisionShapes/btBox2dShape.cpp",
+ "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.cpp",
+ "BulletCollision/CollisionShapes/btCapsuleShape.cpp",
+ "BulletCollision/CollisionShapes/btCollisionShape.cpp",
+ "BulletCollision/CollisionShapes/btCompoundShape.cpp",
+ "BulletCollision/CollisionShapes/btConcaveShape.cpp",
+ "BulletCollision/CollisionShapes/btConeShape.cpp",
+ "BulletCollision/CollisionShapes/btConvexHullShape.cpp",
+ "BulletCollision/CollisionShapes/btConvexInternalShape.cpp",
+ "BulletCollision/CollisionShapes/btConvexPointCloudShape.cpp",
+ "BulletCollision/CollisionShapes/btConvexPolyhedron.cpp",
+ "BulletCollision/CollisionShapes/btConvexShape.cpp",
+ "BulletCollision/CollisionShapes/btConvex2dShape.cpp",
+ "BulletCollision/CollisionShapes/btConvexTriangleMeshShape.cpp",
+ "BulletCollision/CollisionShapes/btCylinderShape.cpp",
+ "BulletCollision/CollisionShapes/btEmptyShape.cpp",
+ "BulletCollision/CollisionShapes/btHeightfieldTerrainShape.cpp",
+ "BulletCollision/CollisionShapes/btMiniSDF.cpp",
+ "BulletCollision/CollisionShapes/btMinkowskiSumShape.cpp",
+ "BulletCollision/CollisionShapes/btMultimaterialTriangleMeshShape.cpp",
+ "BulletCollision/CollisionShapes/btMultiSphereShape.cpp",
+ "BulletCollision/CollisionShapes/btOptimizedBvh.cpp",
+ "BulletCollision/CollisionShapes/btPolyhedralConvexShape.cpp",
+ "BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.cpp",
+ "BulletCollision/CollisionShapes/btSdfCollisionShape.cpp",
+ "BulletCollision/CollisionShapes/btShapeHull.cpp",
+ "BulletCollision/CollisionShapes/btSphereShape.cpp",
+ "BulletCollision/CollisionShapes/btStaticPlaneShape.cpp",
+ "BulletCollision/CollisionShapes/btStridingMeshInterface.cpp",
+ "BulletCollision/CollisionShapes/btTetrahedronShape.cpp",
+ "BulletCollision/CollisionShapes/btTriangleBuffer.cpp",
+ "BulletCollision/CollisionShapes/btTriangleCallback.cpp",
+ "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.cpp",
+ "BulletCollision/CollisionShapes/btTriangleIndexVertexMaterialArray.cpp",
+ "BulletCollision/CollisionShapes/btTriangleMesh.cpp",
+ "BulletCollision/CollisionShapes/btTriangleMeshShape.cpp",
+ "BulletCollision/CollisionShapes/btUniformScalingShape.cpp",
+ "BulletCollision/Gimpact/btContactProcessing.cpp",
+ "BulletCollision/Gimpact/btGenericPoolAllocator.cpp",
+ "BulletCollision/Gimpact/btGImpactBvh.cpp",
+ "BulletCollision/Gimpact/btGImpactCollisionAlgorithm.cpp",
+ "BulletCollision/Gimpact/btGImpactQuantizedBvh.cpp",
+ "BulletCollision/Gimpact/btGImpactShape.cpp",
+ "BulletCollision/Gimpact/btTriangleShapeEx.cpp",
+ "BulletCollision/Gimpact/gim_box_set.cpp",
+ "BulletCollision/Gimpact/gim_contact.cpp",
+ "BulletCollision/Gimpact/gim_memory.cpp",
+ "BulletCollision/Gimpact/gim_tri_collision.cpp",
+ "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.cpp",
+ "BulletCollision/NarrowPhaseCollision/btConvexCast.cpp",
+ "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.cpp",
+ "BulletCollision/NarrowPhaseCollision/btGjkEpa2.cpp",
+ "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.cpp",
+ "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.cpp",
+ "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.cpp",
+ "BulletCollision/NarrowPhaseCollision/btPersistentManifold.cpp",
+ "BulletCollision/NarrowPhaseCollision/btRaycastCallback.cpp",
+ "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.cpp",
+ "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.cpp",
+ "BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.cpp",
# BulletDynamics
- , "BulletDynamics/Character/btKinematicCharacterController.cpp"
- , "BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btContactConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btFixedConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btGearConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp"
- , "BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp"
- , "BulletDynamics/ConstraintSolver/btHingeConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp"
- , "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp"
- , "BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp"
- , "BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp"
- , "BulletDynamics/ConstraintSolver/btSliderConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btTypedConstraint.cpp"
- , "BulletDynamics/ConstraintSolver/btUniversalConstraint.cpp"
- , "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp"
- , "BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp"
- , "BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp"
- , "BulletDynamics/Dynamics/btRigidBody.cpp"
- , "BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp"
- #, "BulletDynamics/Dynamics/Bullet-C-API.cpp"
- , "BulletDynamics/Vehicle/btRaycastVehicle.cpp"
- , "BulletDynamics/Vehicle/btWheelInfo.cpp"
- , "BulletDynamics/Featherstone/btMultiBody.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyConstraint.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp"
- , "BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp"
- , "BulletDynamics/Featherstone/btMultiBodySliderConstraint.cpp"
- , "BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp"
- , "BulletDynamics/MLCPSolvers/btDantzigLCP.cpp"
- , "BulletDynamics/MLCPSolvers/btMLCPSolver.cpp"
- , "BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp"
-
+ "BulletDynamics/Character/btKinematicCharacterController.cpp",
+ "BulletDynamics/ConstraintSolver/btConeTwistConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btContactConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btFixedConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btGearConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btGeneric6DofConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btGeneric6DofSpringConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btGeneric6DofSpring2Constraint.cpp",
+ "BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp",
+ "BulletDynamics/ConstraintSolver/btHingeConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btPoint2PointConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp",
+ "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolverMt.cpp",
+ "BulletDynamics/ConstraintSolver/btBatchedConstraints.cpp",
+ "BulletDynamics/ConstraintSolver/btNNCGConstraintSolver.cpp",
+ "BulletDynamics/ConstraintSolver/btSliderConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btSolve2LinearConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btTypedConstraint.cpp",
+ "BulletDynamics/ConstraintSolver/btUniversalConstraint.cpp",
+ "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.cpp",
+ "BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp",
+ "BulletDynamics/Dynamics/btSimulationIslandManagerMt.cpp",
+ "BulletDynamics/Dynamics/btRigidBody.cpp",
+ "BulletDynamics/Dynamics/btSimpleDynamicsWorld.cpp",
+ # "BulletDynamics/Dynamics/Bullet-C-API.cpp",
+ "BulletDynamics/Vehicle/btRaycastVehicle.cpp",
+ "BulletDynamics/Vehicle/btWheelInfo.cpp",
+ "BulletDynamics/Featherstone/btMultiBody.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyConstraint.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyGearConstraint.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyJointLimitConstraint.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyJointMotor.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyMLCPConstraintSolver.cpp",
+ "BulletDynamics/Featherstone/btMultiBodyPoint2Point.cpp",
+ "BulletDynamics/Featherstone/btMultiBodySliderConstraint.cpp",
+ "BulletDynamics/Featherstone/btMultiBodySphericalJointMotor.cpp",
+ "BulletDynamics/MLCPSolvers/btDantzigLCP.cpp",
+ "BulletDynamics/MLCPSolvers/btMLCPSolver.cpp",
+ "BulletDynamics/MLCPSolvers/btLemkeAlgorithm.cpp",
# BulletInverseDynamics
- , "BulletInverseDynamics/IDMath.cpp"
- , "BulletInverseDynamics/MultiBodyTree.cpp"
- , "BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp"
- , "BulletInverseDynamics/details/MultiBodyTreeImpl.cpp"
-
+ "BulletInverseDynamics/IDMath.cpp",
+ "BulletInverseDynamics/MultiBodyTree.cpp",
+ "BulletInverseDynamics/details/MultiBodyTreeInitCache.cpp",
+ "BulletInverseDynamics/details/MultiBodyTreeImpl.cpp",
# BulletSoftBody
- , "BulletSoftBody/btSoftBody.cpp"
- , "BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp"
- , "BulletSoftBody/btSoftBodyHelpers.cpp"
- , "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp"
- , "BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp"
- , "BulletSoftBody/btSoftRigidDynamicsWorld.cpp"
- , "BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp"
- , "BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp"
- , "BulletSoftBody/btDefaultSoftBodySolver.cpp"
- , "BulletSoftBody/btDeformableBackwardEulerObjective.cpp"
- , "BulletSoftBody/btDeformableBodySolver.cpp"
- , "BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp"
- , "BulletSoftBody/btDeformableContactProjection.cpp"
- , "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp"
- , "BulletSoftBody/btDeformableContactConstraint.cpp"
-
+ "BulletSoftBody/btSoftBody.cpp",
+ "BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp",
+ "BulletSoftBody/btSoftBodyHelpers.cpp",
+ "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.cpp",
+ "BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp",
+ "BulletSoftBody/btSoftRigidDynamicsWorld.cpp",
+ "BulletSoftBody/btSoftMultiBodyDynamicsWorld.cpp",
+ "BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp",
+ "BulletSoftBody/btDefaultSoftBodySolver.cpp",
+ "BulletSoftBody/btDeformableBackwardEulerObjective.cpp",
+ "BulletSoftBody/btDeformableBodySolver.cpp",
+ "BulletSoftBody/btDeformableMultiBodyConstraintSolver.cpp",
+ "BulletSoftBody/btDeformableContactProjection.cpp",
+ "BulletSoftBody/btDeformableMultiBodyDynamicsWorld.cpp",
+ "BulletSoftBody/btDeformableContactConstraint.cpp",
# clew
- , "clew/clew.c"
-
+ "clew/clew.c",
# LinearMath
- , "LinearMath/btAlignedAllocator.cpp"
- , "LinearMath/btConvexHull.cpp"
- , "LinearMath/btConvexHullComputer.cpp"
- , "LinearMath/btGeometryUtil.cpp"
- , "LinearMath/btPolarDecomposition.cpp"
- , "LinearMath/btQuickprof.cpp"
- , "LinearMath/btSerializer.cpp"
- , "LinearMath/btSerializer64.cpp"
- , "LinearMath/btThreads.cpp"
- , "LinearMath/btVector3.cpp"
- , "LinearMath/TaskScheduler/btTaskScheduler.cpp"
- , "LinearMath/TaskScheduler/btThreadSupportPosix.cpp"
- , "LinearMath/TaskScheduler/btThreadSupportWin32.cpp"
+ "LinearMath/btAlignedAllocator.cpp",
+ "LinearMath/btConvexHull.cpp",
+ "LinearMath/btConvexHullComputer.cpp",
+ "LinearMath/btGeometryUtil.cpp",
+ "LinearMath/btPolarDecomposition.cpp",
+ "LinearMath/btQuickprof.cpp",
+ "LinearMath/btSerializer.cpp",
+ "LinearMath/btSerializer64.cpp",
+ "LinearMath/btThreads.cpp",
+ "LinearMath/btVector3.cpp",
+ "LinearMath/TaskScheduler/btTaskScheduler.cpp",
+ "LinearMath/TaskScheduler/btThreadSupportPosix.cpp",
+ "LinearMath/TaskScheduler/btThreadSupportWin32.cpp",
]
thirdparty_sources = [thirdparty_dir + file for file in bullet2_src]
# Treat Bullet headers as system headers to avoid raising warnings. Not supported on MSVC.
if not env.msvc:
- env_bullet.Append(CPPFLAGS=['-isystem', Dir(thirdparty_dir).path])
+ env_bullet.Append(CPPFLAGS=["-isystem", Dir(thirdparty_dir).path])
else:
env_bullet.Prepend(CPPPATH=[thirdparty_dir])
# if env['target'] == "debug" or env['target'] == "release_debug":
diff --git a/modules/bullet/area_bullet.cpp b/modules/bullet/area_bullet.cpp
index e8a5c1475a..4d727529ef 100644
--- a/modules/bullet/area_bullet.cpp
+++ b/modules/bullet/area_bullet.cpp
@@ -46,7 +46,7 @@
AreaBullet::AreaBullet() :
RigidCollisionObjectBullet(CollisionObjectBullet::TYPE_AREA),
monitorable(true),
- spOv_mode(PhysicsServer::AREA_SPACE_OVERRIDE_DISABLED),
+ spOv_mode(PhysicsServer3D::AREA_SPACE_OVERRIDE_DISABLED),
spOv_gravityPoint(false),
spOv_gravityPointDistanceScale(0),
spOv_gravityPointAttenuation(1),
@@ -86,11 +86,11 @@ void AreaBullet::dispatch_callbacks() {
switch (otherObj.state) {
case OVERLAP_STATE_ENTER:
otherObj.state = OVERLAP_STATE_INSIDE;
- call_event(otherObj.object, PhysicsServer::AREA_BODY_ADDED);
+ call_event(otherObj.object, PhysicsServer3D::AREA_BODY_ADDED);
otherObj.object->on_enter_area(this);
break;
case OVERLAP_STATE_EXIT:
- call_event(otherObj.object, PhysicsServer::AREA_BODY_REMOVED);
+ call_event(otherObj.object, PhysicsServer3D::AREA_BODY_REMOVED);
otherObj.object->on_exit_area(this);
overlappingObjects.remove(i); // Remove after callback
break;
@@ -101,7 +101,7 @@ void AreaBullet::dispatch_callbacks() {
}
}
-void AreaBullet::call_event(CollisionObjectBullet *p_otherObject, PhysicsServer::AreaBodyStatus p_status) {
+void AreaBullet::call_event(CollisionObjectBullet *p_otherObject, PhysicsServer3D::AreaBodyStatus p_status) {
InOutEventCallback &event = eventsCallbacks[static_cast<int>(p_otherObject->getType())];
Object *areaGodoObject = ObjectDB::get_instance(event.event_callback_id);
@@ -130,7 +130,7 @@ void AreaBullet::scratch() {
void AreaBullet::clear_overlaps(bool p_notify) {
for (int i = overlappingObjects.size() - 1; 0 <= i; --i) {
if (p_notify)
- call_event(overlappingObjects[i].object, PhysicsServer::AREA_BODY_REMOVED);
+ call_event(overlappingObjects[i].object, PhysicsServer3D::AREA_BODY_REMOVED);
overlappingObjects[i].object->on_exit_area(this);
}
overlappingObjects.clear();
@@ -140,7 +140,7 @@ void AreaBullet::remove_overlap(CollisionObjectBullet *p_object, bool p_notify)
for (int i = overlappingObjects.size() - 1; 0 <= i; --i) {
if (overlappingObjects[i].object == p_object) {
if (p_notify)
- call_event(overlappingObjects[i].object, PhysicsServer::AREA_BODY_REMOVED);
+ call_event(overlappingObjects[i].object, PhysicsServer3D::AREA_BODY_REMOVED);
overlappingObjects[i].object->on_exit_area(this);
overlappingObjects.remove(i);
break;
@@ -218,30 +218,30 @@ void AreaBullet::put_overlap_as_inside(int p_index) {
}
}
-void AreaBullet::set_param(PhysicsServer::AreaParameter p_param, const Variant &p_value) {
+void AreaBullet::set_param(PhysicsServer3D::AreaParameter p_param, const Variant &p_value) {
switch (p_param) {
- case PhysicsServer::AREA_PARAM_GRAVITY:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY:
set_spOv_gravityMag(p_value);
break;
- case PhysicsServer::AREA_PARAM_GRAVITY_VECTOR:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_VECTOR:
set_spOv_gravityVec(p_value);
break;
- case PhysicsServer::AREA_PARAM_LINEAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_LINEAR_DAMP:
set_spOv_linearDump(p_value);
break;
- case PhysicsServer::AREA_PARAM_ANGULAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_ANGULAR_DAMP:
set_spOv_angularDump(p_value);
break;
- case PhysicsServer::AREA_PARAM_PRIORITY:
+ case PhysicsServer3D::AREA_PARAM_PRIORITY:
set_spOv_priority(p_value);
break;
- case PhysicsServer::AREA_PARAM_GRAVITY_IS_POINT:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_IS_POINT:
set_spOv_gravityPoint(p_value);
break;
- case PhysicsServer::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
set_spOv_gravityPointDistanceScale(p_value);
break;
- case PhysicsServer::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
set_spOv_gravityPointAttenuation(p_value);
break;
default:
@@ -249,23 +249,23 @@ void AreaBullet::set_param(PhysicsServer::AreaParameter p_param, const Variant &
}
}
-Variant AreaBullet::get_param(PhysicsServer::AreaParameter p_param) const {
+Variant AreaBullet::get_param(PhysicsServer3D::AreaParameter p_param) const {
switch (p_param) {
- case PhysicsServer::AREA_PARAM_GRAVITY:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY:
return spOv_gravityMag;
- case PhysicsServer::AREA_PARAM_GRAVITY_VECTOR:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_VECTOR:
return spOv_gravityVec;
- case PhysicsServer::AREA_PARAM_LINEAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_LINEAR_DAMP:
return spOv_linearDump;
- case PhysicsServer::AREA_PARAM_ANGULAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_ANGULAR_DAMP:
return spOv_angularDump;
- case PhysicsServer::AREA_PARAM_PRIORITY:
+ case PhysicsServer3D::AREA_PARAM_PRIORITY:
return spOv_priority;
- case PhysicsServer::AREA_PARAM_GRAVITY_IS_POINT:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_IS_POINT:
return spOv_gravityPoint;
- case PhysicsServer::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
return spOv_gravityPointDistanceScale;
- case PhysicsServer::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
return spOv_gravityPointAttenuation;
default:
WARN_PRINT("Area doesn't support this parameter in the Bullet backend: " + itos(p_param));
diff --git a/modules/bullet/area_bullet.h b/modules/bullet/area_bullet.h
index 18888c6725..0272350510 100644
--- a/modules/bullet/area_bullet.h
+++ b/modules/bullet/area_bullet.h
@@ -33,7 +33,7 @@
#include "collision_object_bullet.h"
#include "core/vector.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#include "space_bullet.h"
/**
@@ -65,7 +65,7 @@ public:
OverlapState state;
OverlappingObjectData() :
- object(NULL),
+ object(nullptr),
state(OVERLAP_STATE_ENTER) {}
OverlappingObjectData(CollisionObjectBullet *p_object, OverlapState p_state) :
object(p_object),
@@ -88,7 +88,7 @@ private:
Vector<OverlappingObjectData> overlappingObjects;
bool monitorable;
- PhysicsServer::AreaSpaceOverrideMode spOv_mode;
+ PhysicsServer3D::AreaSpaceOverrideMode spOv_mode;
bool spOv_gravityPoint;
real_t spOv_gravityPointDistanceScale;
real_t spOv_gravityPointAttenuation;
@@ -114,8 +114,8 @@ public:
bool is_monitoring() const;
- _FORCE_INLINE_ void set_spOv_mode(PhysicsServer::AreaSpaceOverrideMode p_mode) { spOv_mode = p_mode; }
- _FORCE_INLINE_ PhysicsServer::AreaSpaceOverrideMode get_spOv_mode() { return spOv_mode; }
+ _FORCE_INLINE_ void set_spOv_mode(PhysicsServer3D::AreaSpaceOverrideMode p_mode) { spOv_mode = p_mode; }
+ _FORCE_INLINE_ PhysicsServer3D::AreaSpaceOverrideMode get_spOv_mode() { return spOv_mode; }
_FORCE_INLINE_ void set_spOv_gravityPoint(bool p_isGP) { spOv_gravityPoint = p_isGP; }
_FORCE_INLINE_ bool is_spOv_gravityPoint() { return spOv_gravityPoint; }
@@ -146,7 +146,7 @@ public:
virtual void set_space(SpaceBullet *p_space);
virtual void dispatch_callbacks();
- void call_event(CollisionObjectBullet *p_otherObject, PhysicsServer::AreaBodyStatus p_status);
+ void call_event(CollisionObjectBullet *p_otherObject, PhysicsServer3D::AreaBodyStatus p_status);
void set_on_state_change(ObjectID p_id, const StringName &p_method, const Variant &p_udata = Variant());
void scratch();
@@ -162,8 +162,8 @@ public:
void put_overlap_as_exit(int p_index);
void put_overlap_as_inside(int p_index);
- void set_param(PhysicsServer::AreaParameter p_param, const Variant &p_value);
- Variant get_param(PhysicsServer::AreaParameter p_param) const;
+ void set_param(PhysicsServer3D::AreaParameter p_param, const Variant &p_value);
+ Variant get_param(PhysicsServer3D::AreaParameter p_param) const;
void set_event_callback(Type p_callbackObjectType, ObjectID p_id, const StringName &p_method);
bool has_event_callback(Type p_callbackObjectType);
diff --git a/modules/bullet/btRayShape.cpp b/modules/bullet/btRayShape.cpp
index 4071723a3e..0f54f848dc 100644
--- a/modules/bullet/btRayShape.cpp
+++ b/modules/bullet/btRayShape.cpp
@@ -43,6 +43,7 @@ btRayShape::btRayShape(btScalar length) :
m_shapeAxis(0, 0, 1) {
m_shapeType = CUSTOM_CONVEX_SHAPE_TYPE;
setLength(length);
+ slipsOnSlope = false;
}
btRayShape::~btRayShape() {
diff --git a/modules/bullet/bullet_physics_server.cpp b/modules/bullet/bullet_physics_server.cpp
index 89868babc6..2705c749a2 100644
--- a/modules/bullet/bullet_physics_server.cpp
+++ b/modules/bullet/bullet_physics_server.cpp
@@ -74,19 +74,19 @@
body->get_space()->add_constraint(joint, joint->is_disabled_collisions_between_bodies());
// <--------------- Joint creation asserts
-void BulletPhysicsServer::_bind_methods() {
- //ClassDB::bind_method(D_METHOD("DoTest"), &BulletPhysicsServer::DoTest);
+void BulletPhysicsServer3D::_bind_methods() {
+ //ClassDB::bind_method(D_METHOD("DoTest"), &BulletPhysicsServer3D::DoTest);
}
-BulletPhysicsServer::BulletPhysicsServer() :
- PhysicsServer(),
+BulletPhysicsServer3D::BulletPhysicsServer3D() :
+ PhysicsServer3D(),
active(true),
active_spaces_count(0) {}
-BulletPhysicsServer::~BulletPhysicsServer() {}
+BulletPhysicsServer3D::~BulletPhysicsServer3D() {}
-RID BulletPhysicsServer::shape_create(ShapeType p_shape) {
- ShapeBullet *shape = NULL;
+RID BulletPhysicsServer3D::shape_create(ShapeType p_shape) {
+ ShapeBullet *shape = nullptr;
switch (p_shape) {
case SHAPE_PLANE: {
@@ -133,51 +133,51 @@ RID BulletPhysicsServer::shape_create(ShapeType p_shape) {
CreateThenReturnRID(shape_owner, shape)
}
-void BulletPhysicsServer::shape_set_data(RID p_shape, const Variant &p_data) {
+void BulletPhysicsServer3D::shape_set_data(RID p_shape, const Variant &p_data) {
ShapeBullet *shape = shape_owner.getornull(p_shape);
ERR_FAIL_COND(!shape);
shape->set_data(p_data);
}
-void BulletPhysicsServer::shape_set_custom_solver_bias(RID p_shape, real_t p_bias) {
+void BulletPhysicsServer3D::shape_set_custom_solver_bias(RID p_shape, real_t p_bias) {
//WARN_PRINT("Bias not supported by Bullet physics engine");
}
-PhysicsServer::ShapeType BulletPhysicsServer::shape_get_type(RID p_shape) const {
+PhysicsServer3D::ShapeType BulletPhysicsServer3D::shape_get_type(RID p_shape) const {
ShapeBullet *shape = shape_owner.getornull(p_shape);
- ERR_FAIL_COND_V(!shape, PhysicsServer::SHAPE_CUSTOM);
+ ERR_FAIL_COND_V(!shape, PhysicsServer3D::SHAPE_CUSTOM);
return shape->get_type();
}
-Variant BulletPhysicsServer::shape_get_data(RID p_shape) const {
+Variant BulletPhysicsServer3D::shape_get_data(RID p_shape) const {
ShapeBullet *shape = shape_owner.getornull(p_shape);
ERR_FAIL_COND_V(!shape, Variant());
return shape->get_data();
}
-void BulletPhysicsServer::shape_set_margin(RID p_shape, real_t p_margin) {
+void BulletPhysicsServer3D::shape_set_margin(RID p_shape, real_t p_margin) {
ShapeBullet *shape = shape_owner.getornull(p_shape);
ERR_FAIL_COND(!shape);
shape->set_margin(p_margin);
}
-real_t BulletPhysicsServer::shape_get_margin(RID p_shape) const {
+real_t BulletPhysicsServer3D::shape_get_margin(RID p_shape) const {
ShapeBullet *shape = shape_owner.getornull(p_shape);
ERR_FAIL_COND_V(!shape, 0.0);
return shape->get_margin();
}
-real_t BulletPhysicsServer::shape_get_custom_solver_bias(RID p_shape) const {
+real_t BulletPhysicsServer3D::shape_get_custom_solver_bias(RID p_shape) const {
//WARN_PRINT("Bias not supported by Bullet physics engine");
return 0.;
}
-RID BulletPhysicsServer::space_create() {
+RID BulletPhysicsServer3D::space_create() {
SpaceBullet *space = bulletnew(SpaceBullet);
CreateThenReturnRID(space_owner, space);
}
-void BulletPhysicsServer::space_set_active(RID p_space, bool p_active) {
+void BulletPhysicsServer3D::space_set_active(RID p_space, bool p_active) {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND(!space);
@@ -195,64 +195,64 @@ void BulletPhysicsServer::space_set_active(RID p_space, bool p_active) {
}
}
-bool BulletPhysicsServer::space_is_active(RID p_space) const {
+bool BulletPhysicsServer3D::space_is_active(RID p_space) const {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND_V(!space, false);
return -1 != active_spaces.find(space);
}
-void BulletPhysicsServer::space_set_param(RID p_space, SpaceParameter p_param, real_t p_value) {
+void BulletPhysicsServer3D::space_set_param(RID p_space, SpaceParameter p_param, real_t p_value) {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND(!space);
space->set_param(p_param, p_value);
}
-real_t BulletPhysicsServer::space_get_param(RID p_space, SpaceParameter p_param) const {
+real_t BulletPhysicsServer3D::space_get_param(RID p_space, SpaceParameter p_param) const {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND_V(!space, 0);
return space->get_param(p_param);
}
-PhysicsDirectSpaceState *BulletPhysicsServer::space_get_direct_state(RID p_space) {
+PhysicsDirectSpaceState3D *BulletPhysicsServer3D::space_get_direct_state(RID p_space) {
SpaceBullet *space = space_owner.getornull(p_space);
- ERR_FAIL_COND_V(!space, NULL);
+ ERR_FAIL_COND_V(!space, nullptr);
return space->get_direct_state();
}
-void BulletPhysicsServer::space_set_debug_contacts(RID p_space, int p_max_contacts) {
+void BulletPhysicsServer3D::space_set_debug_contacts(RID p_space, int p_max_contacts) {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND(!space);
space->set_debug_contacts(p_max_contacts);
}
-Vector<Vector3> BulletPhysicsServer::space_get_contacts(RID p_space) const {
+Vector<Vector3> BulletPhysicsServer3D::space_get_contacts(RID p_space) const {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND_V(!space, Vector<Vector3>());
return space->get_debug_contacts();
}
-int BulletPhysicsServer::space_get_contact_count(RID p_space) const {
+int BulletPhysicsServer3D::space_get_contact_count(RID p_space) const {
SpaceBullet *space = space_owner.getornull(p_space);
ERR_FAIL_COND_V(!space, 0);
return space->get_debug_contact_count();
}
-RID BulletPhysicsServer::area_create() {
+RID BulletPhysicsServer3D::area_create() {
AreaBullet *area = bulletnew(AreaBullet);
area->set_collision_layer(1);
area->set_collision_mask(1);
CreateThenReturnRID(area_owner, area)
}
-void BulletPhysicsServer::area_set_space(RID p_area, RID p_space) {
+void BulletPhysicsServer3D::area_set_space(RID p_area, RID p_space) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
- SpaceBullet *space = NULL;
+ SpaceBullet *space = nullptr;
if (p_space.is_valid()) {
space = space_owner.getornull(p_space);
ERR_FAIL_COND(!space);
@@ -260,26 +260,26 @@ void BulletPhysicsServer::area_set_space(RID p_area, RID p_space) {
area->set_space(space);
}
-RID BulletPhysicsServer::area_get_space(RID p_area) const {
+RID BulletPhysicsServer3D::area_get_space(RID p_area) const {
AreaBullet *area = area_owner.getornull(p_area);
return area->get_space()->get_self();
}
-void BulletPhysicsServer::area_set_space_override_mode(RID p_area, AreaSpaceOverrideMode p_mode) {
+void BulletPhysicsServer3D::area_set_space_override_mode(RID p_area, AreaSpaceOverrideMode p_mode) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_spOv_mode(p_mode);
}
-PhysicsServer::AreaSpaceOverrideMode BulletPhysicsServer::area_get_space_override_mode(RID p_area) const {
+PhysicsServer3D::AreaSpaceOverrideMode BulletPhysicsServer3D::area_get_space_override_mode(RID p_area) const {
AreaBullet *area = area_owner.getornull(p_area);
- ERR_FAIL_COND_V(!area, PhysicsServer::AREA_SPACE_OVERRIDE_DISABLED);
+ ERR_FAIL_COND_V(!area, PhysicsServer3D::AREA_SPACE_OVERRIDE_DISABLED);
return area->get_spOv_mode();
}
-void BulletPhysicsServer::area_add_shape(RID p_area, RID p_shape, const Transform &p_transform, bool p_disabled) {
+void BulletPhysicsServer3D::area_add_shape(RID p_area, RID p_shape, const Transform &p_transform, bool p_disabled) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
@@ -289,7 +289,7 @@ void BulletPhysicsServer::area_add_shape(RID p_area, RID p_shape, const Transfor
area->add_shape(shape, p_transform, p_disabled);
}
-void BulletPhysicsServer::area_set_shape(RID p_area, int p_shape_idx, RID p_shape) {
+void BulletPhysicsServer3D::area_set_shape(RID p_area, int p_shape_idx, RID p_shape) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
@@ -299,41 +299,41 @@ void BulletPhysicsServer::area_set_shape(RID p_area, int p_shape_idx, RID p_shap
area->set_shape(p_shape_idx, shape);
}
-void BulletPhysicsServer::area_set_shape_transform(RID p_area, int p_shape_idx, const Transform &p_transform) {
+void BulletPhysicsServer3D::area_set_shape_transform(RID p_area, int p_shape_idx, const Transform &p_transform) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_shape_transform(p_shape_idx, p_transform);
}
-int BulletPhysicsServer::area_get_shape_count(RID p_area) const {
+int BulletPhysicsServer3D::area_get_shape_count(RID p_area) const {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND_V(!area, 0);
return area->get_shape_count();
}
-RID BulletPhysicsServer::area_get_shape(RID p_area, int p_shape_idx) const {
+RID BulletPhysicsServer3D::area_get_shape(RID p_area, int p_shape_idx) const {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND_V(!area, RID());
return area->get_shape(p_shape_idx)->get_self();
}
-Transform BulletPhysicsServer::area_get_shape_transform(RID p_area, int p_shape_idx) const {
+Transform BulletPhysicsServer3D::area_get_shape_transform(RID p_area, int p_shape_idx) const {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND_V(!area, Transform());
return area->get_shape_transform(p_shape_idx);
}
-void BulletPhysicsServer::area_remove_shape(RID p_area, int p_shape_idx) {
+void BulletPhysicsServer3D::area_remove_shape(RID p_area, int p_shape_idx) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
return area->remove_shape_full(p_shape_idx);
}
-void BulletPhysicsServer::area_clear_shapes(RID p_area) {
+void BulletPhysicsServer3D::area_clear_shapes(RID p_area) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
@@ -341,14 +341,14 @@ void BulletPhysicsServer::area_clear_shapes(RID p_area) {
area->remove_shape_full(0);
}
-void BulletPhysicsServer::area_set_shape_disabled(RID p_area, int p_shape_idx, bool p_disabled) {
+void BulletPhysicsServer3D::area_set_shape_disabled(RID p_area, int p_shape_idx, bool p_disabled) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_shape_disabled(p_shape_idx, p_disabled);
}
-void BulletPhysicsServer::area_attach_object_instance_id(RID p_area, ObjectID p_id) {
+void BulletPhysicsServer3D::area_attach_object_instance_id(RID p_area, ObjectID p_id) {
if (space_owner.owns(p_area)) {
return;
}
@@ -357,7 +357,7 @@ void BulletPhysicsServer::area_attach_object_instance_id(RID p_area, ObjectID p_
area->set_instance_id(p_id);
}
-ObjectID BulletPhysicsServer::area_get_object_instance_id(RID p_area) const {
+ObjectID BulletPhysicsServer3D::area_get_object_instance_id(RID p_area) const {
if (space_owner.owns(p_area)) {
return ObjectID();
}
@@ -366,7 +366,7 @@ ObjectID BulletPhysicsServer::area_get_object_instance_id(RID p_area) const {
return area->get_instance_id();
}
-void BulletPhysicsServer::area_set_param(RID p_area, AreaParameter p_param, const Variant &p_value) {
+void BulletPhysicsServer3D::area_set_param(RID p_area, AreaParameter p_param, const Variant &p_value) {
if (space_owner.owns(p_area)) {
SpaceBullet *space = space_owner.getornull(p_area);
if (space) {
@@ -381,7 +381,7 @@ void BulletPhysicsServer::area_set_param(RID p_area, AreaParameter p_param, cons
}
}
-Variant BulletPhysicsServer::area_get_param(RID p_area, AreaParameter p_param) const {
+Variant BulletPhysicsServer3D::area_get_param(RID p_area, AreaParameter p_param) const {
if (space_owner.owns(p_area)) {
SpaceBullet *space = space_owner.getornull(p_area);
return space->get_param(p_param);
@@ -393,64 +393,64 @@ Variant BulletPhysicsServer::area_get_param(RID p_area, AreaParameter p_param) c
}
}
-void BulletPhysicsServer::area_set_transform(RID p_area, const Transform &p_transform) {
+void BulletPhysicsServer3D::area_set_transform(RID p_area, const Transform &p_transform) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_transform(p_transform);
}
-Transform BulletPhysicsServer::area_get_transform(RID p_area) const {
+Transform BulletPhysicsServer3D::area_get_transform(RID p_area) const {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND_V(!area, Transform());
return area->get_transform();
}
-void BulletPhysicsServer::area_set_collision_mask(RID p_area, uint32_t p_mask) {
+void BulletPhysicsServer3D::area_set_collision_mask(RID p_area, uint32_t p_mask) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_collision_mask(p_mask);
}
-void BulletPhysicsServer::area_set_collision_layer(RID p_area, uint32_t p_layer) {
+void BulletPhysicsServer3D::area_set_collision_layer(RID p_area, uint32_t p_layer) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_collision_layer(p_layer);
}
-void BulletPhysicsServer::area_set_monitorable(RID p_area, bool p_monitorable) {
+void BulletPhysicsServer3D::area_set_monitorable(RID p_area, bool p_monitorable) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_monitorable(p_monitorable);
}
-void BulletPhysicsServer::area_set_monitor_callback(RID p_area, Object *p_receiver, const StringName &p_method) {
+void BulletPhysicsServer3D::area_set_monitor_callback(RID p_area, Object *p_receiver, const StringName &p_method) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_event_callback(CollisionObjectBullet::TYPE_RIGID_BODY, p_receiver ? p_receiver->get_instance_id() : ObjectID(), p_method);
}
-void BulletPhysicsServer::area_set_area_monitor_callback(RID p_area, Object *p_receiver, const StringName &p_method) {
+void BulletPhysicsServer3D::area_set_area_monitor_callback(RID p_area, Object *p_receiver, const StringName &p_method) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_event_callback(CollisionObjectBullet::TYPE_AREA, p_receiver ? p_receiver->get_instance_id() : ObjectID(), p_method);
}
-void BulletPhysicsServer::area_set_ray_pickable(RID p_area, bool p_enable) {
+void BulletPhysicsServer3D::area_set_ray_pickable(RID p_area, bool p_enable) {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND(!area);
area->set_ray_pickable(p_enable);
}
-bool BulletPhysicsServer::area_is_ray_pickable(RID p_area) const {
+bool BulletPhysicsServer3D::area_is_ray_pickable(RID p_area) const {
AreaBullet *area = area_owner.getornull(p_area);
ERR_FAIL_COND_V(!area, false);
return area->is_ray_pickable();
}
-RID BulletPhysicsServer::body_create(BodyMode p_mode, bool p_init_sleeping) {
+RID BulletPhysicsServer3D::body_create(BodyMode p_mode, bool p_init_sleeping) {
RigidBodyBullet *body = bulletnew(RigidBodyBullet);
body->set_mode(p_mode);
body->set_collision_layer(1);
@@ -460,10 +460,10 @@ RID BulletPhysicsServer::body_create(BodyMode p_mode, bool p_init_sleeping) {
CreateThenReturnRID(rigid_body_owner, body);
}
-void BulletPhysicsServer::body_set_space(RID p_body, RID p_space) {
+void BulletPhysicsServer3D::body_set_space(RID p_body, RID p_space) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
- SpaceBullet *space = NULL;
+ SpaceBullet *space = nullptr;
if (p_space.is_valid()) {
space = space_owner.getornull(p_space);
@@ -476,7 +476,7 @@ void BulletPhysicsServer::body_set_space(RID p_body, RID p_space) {
body->set_space(space);
}
-RID BulletPhysicsServer::body_get_space(RID p_body) const {
+RID BulletPhysicsServer3D::body_get_space(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, RID());
@@ -486,19 +486,19 @@ RID BulletPhysicsServer::body_get_space(RID p_body) const {
return space->get_self();
}
-void BulletPhysicsServer::body_set_mode(RID p_body, PhysicsServer::BodyMode p_mode) {
+void BulletPhysicsServer3D::body_set_mode(RID p_body, PhysicsServer3D::BodyMode p_mode) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_mode(p_mode);
}
-PhysicsServer::BodyMode BulletPhysicsServer::body_get_mode(RID p_body) const {
+PhysicsServer3D::BodyMode BulletPhysicsServer3D::body_get_mode(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, BODY_MODE_STATIC);
return body->get_mode();
}
-void BulletPhysicsServer::body_add_shape(RID p_body, RID p_shape, const Transform &p_transform, bool p_disabled) {
+void BulletPhysicsServer3D::body_add_shape(RID p_body, RID p_shape, const Transform &p_transform, bool p_disabled) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -509,7 +509,7 @@ void BulletPhysicsServer::body_add_shape(RID p_body, RID p_shape, const Transfor
body->add_shape(shape, p_transform, p_disabled);
}
-void BulletPhysicsServer::body_set_shape(RID p_body, int p_shape_idx, RID p_shape) {
+void BulletPhysicsServer3D::body_set_shape(RID p_body, int p_shape_idx, RID p_shape) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -519,20 +519,20 @@ void BulletPhysicsServer::body_set_shape(RID p_body, int p_shape_idx, RID p_shap
body->set_shape(p_shape_idx, shape);
}
-void BulletPhysicsServer::body_set_shape_transform(RID p_body, int p_shape_idx, const Transform &p_transform) {
+void BulletPhysicsServer3D::body_set_shape_transform(RID p_body, int p_shape_idx, const Transform &p_transform) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_shape_transform(p_shape_idx, p_transform);
}
-int BulletPhysicsServer::body_get_shape_count(RID p_body) const {
+int BulletPhysicsServer3D::body_get_shape_count(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_shape_count();
}
-RID BulletPhysicsServer::body_get_shape(RID p_body, int p_shape_idx) const {
+RID BulletPhysicsServer3D::body_get_shape(RID p_body, int p_shape_idx) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, RID());
@@ -542,113 +542,113 @@ RID BulletPhysicsServer::body_get_shape(RID p_body, int p_shape_idx) const {
return shape->get_self();
}
-Transform BulletPhysicsServer::body_get_shape_transform(RID p_body, int p_shape_idx) const {
+Transform BulletPhysicsServer3D::body_get_shape_transform(RID p_body, int p_shape_idx) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, Transform());
return body->get_shape_transform(p_shape_idx);
}
-void BulletPhysicsServer::body_set_shape_disabled(RID p_body, int p_shape_idx, bool p_disabled) {
+void BulletPhysicsServer3D::body_set_shape_disabled(RID p_body, int p_shape_idx, bool p_disabled) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_shape_disabled(p_shape_idx, p_disabled);
}
-void BulletPhysicsServer::body_remove_shape(RID p_body, int p_shape_idx) {
+void BulletPhysicsServer3D::body_remove_shape(RID p_body, int p_shape_idx) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->remove_shape_full(p_shape_idx);
}
-void BulletPhysicsServer::body_clear_shapes(RID p_body) {
+void BulletPhysicsServer3D::body_clear_shapes(RID p_body) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->remove_all_shapes();
}
-void BulletPhysicsServer::body_attach_object_instance_id(RID p_body, ObjectID p_id) {
+void BulletPhysicsServer3D::body_attach_object_instance_id(RID p_body, ObjectID p_id) {
CollisionObjectBullet *body = get_collisin_object(p_body);
ERR_FAIL_COND(!body);
body->set_instance_id(p_id);
}
-ObjectID BulletPhysicsServer::body_get_object_instance_id(RID p_body) const {
+ObjectID BulletPhysicsServer3D::body_get_object_instance_id(RID p_body) const {
CollisionObjectBullet *body = get_collisin_object(p_body);
ERR_FAIL_COND_V(!body, ObjectID());
return body->get_instance_id();
}
-void BulletPhysicsServer::body_set_enable_continuous_collision_detection(RID p_body, bool p_enable) {
+void BulletPhysicsServer3D::body_set_enable_continuous_collision_detection(RID p_body, bool p_enable) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_continuous_collision_detection(p_enable);
}
-bool BulletPhysicsServer::body_is_continuous_collision_detection_enabled(RID p_body) const {
+bool BulletPhysicsServer3D::body_is_continuous_collision_detection_enabled(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, false);
return body->is_continuous_collision_detection_enabled();
}
-void BulletPhysicsServer::body_set_collision_layer(RID p_body, uint32_t p_layer) {
+void BulletPhysicsServer3D::body_set_collision_layer(RID p_body, uint32_t p_layer) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_collision_layer(p_layer);
}
-uint32_t BulletPhysicsServer::body_get_collision_layer(RID p_body) const {
+uint32_t BulletPhysicsServer3D::body_get_collision_layer(RID p_body) const {
const RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_collision_layer();
}
-void BulletPhysicsServer::body_set_collision_mask(RID p_body, uint32_t p_mask) {
+void BulletPhysicsServer3D::body_set_collision_mask(RID p_body, uint32_t p_mask) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_collision_mask(p_mask);
}
-uint32_t BulletPhysicsServer::body_get_collision_mask(RID p_body) const {
+uint32_t BulletPhysicsServer3D::body_get_collision_mask(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_collision_mask();
}
-void BulletPhysicsServer::body_set_user_flags(RID p_body, uint32_t p_flags) {
+void BulletPhysicsServer3D::body_set_user_flags(RID p_body, uint32_t p_flags) {
// This function si not currently supported
}
-uint32_t BulletPhysicsServer::body_get_user_flags(RID p_body) const {
+uint32_t BulletPhysicsServer3D::body_get_user_flags(RID p_body) const {
// This function si not currently supported
return 0;
}
-void BulletPhysicsServer::body_set_param(RID p_body, BodyParameter p_param, float p_value) {
+void BulletPhysicsServer3D::body_set_param(RID p_body, BodyParameter p_param, float p_value) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_param(p_param, p_value);
}
-float BulletPhysicsServer::body_get_param(RID p_body, BodyParameter p_param) const {
+float BulletPhysicsServer3D::body_get_param(RID p_body, BodyParameter p_param) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_param(p_param);
}
-void BulletPhysicsServer::body_set_kinematic_safe_margin(RID p_body, real_t p_margin) {
+void BulletPhysicsServer3D::body_set_kinematic_safe_margin(RID p_body, real_t p_margin) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -658,7 +658,7 @@ void BulletPhysicsServer::body_set_kinematic_safe_margin(RID p_body, real_t p_ma
}
}
-real_t BulletPhysicsServer::body_get_kinematic_safe_margin(RID p_body) const {
+real_t BulletPhysicsServer3D::body_get_kinematic_safe_margin(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
@@ -670,90 +670,90 @@ real_t BulletPhysicsServer::body_get_kinematic_safe_margin(RID p_body) const {
return 0;
}
-void BulletPhysicsServer::body_set_state(RID p_body, BodyState p_state, const Variant &p_variant) {
+void BulletPhysicsServer3D::body_set_state(RID p_body, BodyState p_state, const Variant &p_variant) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_state(p_state, p_variant);
}
-Variant BulletPhysicsServer::body_get_state(RID p_body, BodyState p_state) const {
+Variant BulletPhysicsServer3D::body_get_state(RID p_body, BodyState p_state) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, Variant());
return body->get_state(p_state);
}
-void BulletPhysicsServer::body_set_applied_force(RID p_body, const Vector3 &p_force) {
+void BulletPhysicsServer3D::body_set_applied_force(RID p_body, const Vector3 &p_force) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_applied_force(p_force);
}
-Vector3 BulletPhysicsServer::body_get_applied_force(RID p_body) const {
+Vector3 BulletPhysicsServer3D::body_get_applied_force(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, Vector3());
return body->get_applied_force();
}
-void BulletPhysicsServer::body_set_applied_torque(RID p_body, const Vector3 &p_torque) {
+void BulletPhysicsServer3D::body_set_applied_torque(RID p_body, const Vector3 &p_torque) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_applied_torque(p_torque);
}
-Vector3 BulletPhysicsServer::body_get_applied_torque(RID p_body) const {
+Vector3 BulletPhysicsServer3D::body_get_applied_torque(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, Vector3());
return body->get_applied_torque();
}
-void BulletPhysicsServer::body_add_central_force(RID p_body, const Vector3 &p_force) {
+void BulletPhysicsServer3D::body_add_central_force(RID p_body, const Vector3 &p_force) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->apply_central_force(p_force);
}
-void BulletPhysicsServer::body_add_force(RID p_body, const Vector3 &p_force, const Vector3 &p_pos) {
+void BulletPhysicsServer3D::body_add_force(RID p_body, const Vector3 &p_force, const Vector3 &p_pos) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->apply_force(p_force, p_pos);
}
-void BulletPhysicsServer::body_add_torque(RID p_body, const Vector3 &p_torque) {
+void BulletPhysicsServer3D::body_add_torque(RID p_body, const Vector3 &p_torque) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->apply_torque(p_torque);
}
-void BulletPhysicsServer::body_apply_central_impulse(RID p_body, const Vector3 &p_impulse) {
+void BulletPhysicsServer3D::body_apply_central_impulse(RID p_body, const Vector3 &p_impulse) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->apply_central_impulse(p_impulse);
}
-void BulletPhysicsServer::body_apply_impulse(RID p_body, const Vector3 &p_pos, const Vector3 &p_impulse) {
+void BulletPhysicsServer3D::body_apply_impulse(RID p_body, const Vector3 &p_pos, const Vector3 &p_impulse) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->apply_impulse(p_pos, p_impulse);
}
-void BulletPhysicsServer::body_apply_torque_impulse(RID p_body, const Vector3 &p_impulse) {
+void BulletPhysicsServer3D::body_apply_torque_impulse(RID p_body, const Vector3 &p_impulse) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->apply_torque_impulse(p_impulse);
}
-void BulletPhysicsServer::body_set_axis_velocity(RID p_body, const Vector3 &p_axis_velocity) {
+void BulletPhysicsServer3D::body_set_axis_velocity(RID p_body, const Vector3 &p_axis_velocity) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -764,19 +764,19 @@ void BulletPhysicsServer::body_set_axis_velocity(RID p_body, const Vector3 &p_ax
body->set_linear_velocity(v);
}
-void BulletPhysicsServer::body_set_axis_lock(RID p_body, BodyAxis p_axis, bool p_lock) {
+void BulletPhysicsServer3D::body_set_axis_lock(RID p_body, BodyAxis p_axis, bool p_lock) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_axis_lock(p_axis, p_lock);
}
-bool BulletPhysicsServer::body_is_axis_locked(RID p_body, BodyAxis p_axis) const {
+bool BulletPhysicsServer3D::body_is_axis_locked(RID p_body, BodyAxis p_axis) const {
const RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->is_axis_locked(p_axis);
}
-void BulletPhysicsServer::body_add_collision_exception(RID p_body, RID p_body_b) {
+void BulletPhysicsServer3D::body_add_collision_exception(RID p_body, RID p_body_b) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -786,7 +786,7 @@ void BulletPhysicsServer::body_add_collision_exception(RID p_body, RID p_body_b)
body->add_collision_exception(other_body);
}
-void BulletPhysicsServer::body_remove_collision_exception(RID p_body, RID p_body_b) {
+void BulletPhysicsServer3D::body_remove_collision_exception(RID p_body, RID p_body_b) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -796,7 +796,7 @@ void BulletPhysicsServer::body_remove_collision_exception(RID p_body, RID p_body
body->remove_collision_exception(other_body);
}
-void BulletPhysicsServer::body_get_collision_exceptions(RID p_body, List<RID> *p_exceptions) {
+void BulletPhysicsServer3D::body_get_collision_exceptions(RID p_body, List<RID> *p_exceptions) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
for (int i = 0; i < body->get_exceptions().size(); i++) {
@@ -804,68 +804,68 @@ void BulletPhysicsServer::body_get_collision_exceptions(RID p_body, List<RID> *p
}
}
-void BulletPhysicsServer::body_set_max_contacts_reported(RID p_body, int p_contacts) {
+void BulletPhysicsServer3D::body_set_max_contacts_reported(RID p_body, int p_contacts) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_max_collisions_detection(p_contacts);
}
-int BulletPhysicsServer::body_get_max_contacts_reported(RID p_body) const {
+int BulletPhysicsServer3D::body_get_max_contacts_reported(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_max_collisions_detection();
}
-void BulletPhysicsServer::body_set_contacts_reported_depth_threshold(RID p_body, float p_threshold) {
+void BulletPhysicsServer3D::body_set_contacts_reported_depth_threshold(RID p_body, float p_threshold) {
// Not supported by bullet and even Godot
}
-float BulletPhysicsServer::body_get_contacts_reported_depth_threshold(RID p_body) const {
+float BulletPhysicsServer3D::body_get_contacts_reported_depth_threshold(RID p_body) const {
// Not supported by bullet and even Godot
return 0.;
}
-void BulletPhysicsServer::body_set_omit_force_integration(RID p_body, bool p_omit) {
+void BulletPhysicsServer3D::body_set_omit_force_integration(RID p_body, bool p_omit) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_omit_forces_integration(p_omit);
}
-bool BulletPhysicsServer::body_is_omitting_force_integration(RID p_body) const {
+bool BulletPhysicsServer3D::body_is_omitting_force_integration(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, false);
return body->get_omit_forces_integration();
}
-void BulletPhysicsServer::body_set_force_integration_callback(RID p_body, Object *p_receiver, const StringName &p_method, const Variant &p_udata) {
+void BulletPhysicsServer3D::body_set_force_integration_callback(RID p_body, Object *p_receiver, const StringName &p_method, const Variant &p_udata) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_force_integration_callback(p_receiver ? p_receiver->get_instance_id() : ObjectID(), p_method, p_udata);
}
-void BulletPhysicsServer::body_set_ray_pickable(RID p_body, bool p_enable) {
+void BulletPhysicsServer3D::body_set_ray_pickable(RID p_body, bool p_enable) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_ray_pickable(p_enable);
}
-bool BulletPhysicsServer::body_is_ray_pickable(RID p_body) const {
+bool BulletPhysicsServer3D::body_is_ray_pickable(RID p_body) const {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, false);
return body->is_ray_pickable();
}
-PhysicsDirectBodyState *BulletPhysicsServer::body_get_direct_state(RID p_body) {
+PhysicsDirectBodyState3D *BulletPhysicsServer3D::body_get_direct_state(RID p_body) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
- ERR_FAIL_COND_V(!body, NULL);
- return BulletPhysicsDirectBodyState::get_singleton(body);
+ ERR_FAIL_COND_V(!body, nullptr);
+ return BulletPhysicsDirectBodyState3D::get_singleton(body);
}
-bool BulletPhysicsServer::body_test_motion(RID p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, MotionResult *r_result, bool p_exclude_raycast_shapes) {
+bool BulletPhysicsServer3D::body_test_motion(RID p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, MotionResult *r_result, bool p_exclude_raycast_shapes) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, false);
ERR_FAIL_COND_V(!body->get_space(), false);
@@ -873,7 +873,7 @@ bool BulletPhysicsServer::body_test_motion(RID p_body, const Transform &p_from,
return body->get_space()->test_body_motion(body, p_from, p_motion, p_infinite_inertia, r_result, p_exclude_raycast_shapes);
}
-int BulletPhysicsServer::body_test_ray_separation(RID p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, SeparationResult *r_results, int p_result_max, float p_margin) {
+int BulletPhysicsServer3D::body_test_ray_separation(RID p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, SeparationResult *r_results, int p_result_max, float p_margin) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
ERR_FAIL_COND_V(!body->get_space(), 0);
@@ -881,7 +881,7 @@ int BulletPhysicsServer::body_test_ray_separation(RID p_body, const Transform &p
return body->get_space()->test_ray_separation(body, p_transform, p_infinite_inertia, r_recover_motion, r_results, p_result_max, p_margin);
}
-RID BulletPhysicsServer::soft_body_create(bool p_init_sleeping) {
+RID BulletPhysicsServer3D::soft_body_create(bool p_init_sleeping) {
SoftBodyBullet *body = bulletnew(SoftBodyBullet);
body->set_collision_layer(1);
body->set_collision_mask(1);
@@ -890,17 +890,17 @@ RID BulletPhysicsServer::soft_body_create(bool p_init_sleeping) {
CreateThenReturnRID(soft_body_owner, body);
}
-void BulletPhysicsServer::soft_body_update_visual_server(RID p_body, class SoftBodyVisualServerHandler *p_visual_server_handler) {
+void BulletPhysicsServer3D::soft_body_update_rendering_server(RID p_body, class SoftBodyRenderingServerHandler *p_rendering_server_handler) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
- body->update_visual_server(p_visual_server_handler);
+ body->update_rendering_server(p_rendering_server_handler);
}
-void BulletPhysicsServer::soft_body_set_space(RID p_body, RID p_space) {
+void BulletPhysicsServer3D::soft_body_set_space(RID p_body, RID p_space) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
- SpaceBullet *space = NULL;
+ SpaceBullet *space = nullptr;
if (p_space.is_valid()) {
space = space_owner.getornull(p_space);
@@ -913,7 +913,7 @@ void BulletPhysicsServer::soft_body_set_space(RID p_body, RID p_space) {
body->set_space(space);
}
-RID BulletPhysicsServer::soft_body_get_space(RID p_body) const {
+RID BulletPhysicsServer3D::soft_body_get_space(RID p_body) const {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, RID());
@@ -923,42 +923,42 @@ RID BulletPhysicsServer::soft_body_get_space(RID p_body) const {
return space->get_self();
}
-void BulletPhysicsServer::soft_body_set_mesh(RID p_body, const REF &p_mesh) {
+void BulletPhysicsServer3D::soft_body_set_mesh(RID p_body, const REF &p_mesh) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_soft_mesh(p_mesh);
}
-void BulletPhysicsServer::soft_body_set_collision_layer(RID p_body, uint32_t p_layer) {
+void BulletPhysicsServer3D::soft_body_set_collision_layer(RID p_body, uint32_t p_layer) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_collision_layer(p_layer);
}
-uint32_t BulletPhysicsServer::soft_body_get_collision_layer(RID p_body) const {
+uint32_t BulletPhysicsServer3D::soft_body_get_collision_layer(RID p_body) const {
const SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_collision_layer();
}
-void BulletPhysicsServer::soft_body_set_collision_mask(RID p_body, uint32_t p_mask) {
+void BulletPhysicsServer3D::soft_body_set_collision_mask(RID p_body, uint32_t p_mask) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_collision_mask(p_mask);
}
-uint32_t BulletPhysicsServer::soft_body_get_collision_mask(RID p_body) const {
+uint32_t BulletPhysicsServer3D::soft_body_get_collision_mask(RID p_body) const {
const SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0);
return body->get_collision_mask();
}
-void BulletPhysicsServer::soft_body_add_collision_exception(RID p_body, RID p_body_b) {
+void BulletPhysicsServer3D::soft_body_add_collision_exception(RID p_body, RID p_body_b) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -971,7 +971,7 @@ void BulletPhysicsServer::soft_body_add_collision_exception(RID p_body, RID p_bo
body->add_collision_exception(other_body);
}
-void BulletPhysicsServer::soft_body_remove_collision_exception(RID p_body, RID p_body_b) {
+void BulletPhysicsServer3D::soft_body_remove_collision_exception(RID p_body, RID p_body_b) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
@@ -984,7 +984,7 @@ void BulletPhysicsServer::soft_body_remove_collision_exception(RID p_body, RID p
body->remove_collision_exception(other_body);
}
-void BulletPhysicsServer::soft_body_get_collision_exceptions(RID p_body, List<RID> *p_exceptions) {
+void BulletPhysicsServer3D::soft_body_get_collision_exceptions(RID p_body, List<RID> *p_exceptions) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
for (int i = 0; i < body->get_exceptions().size(); i++) {
@@ -992,25 +992,25 @@ void BulletPhysicsServer::soft_body_get_collision_exceptions(RID p_body, List<RI
}
}
-void BulletPhysicsServer::soft_body_set_state(RID p_body, BodyState p_state, const Variant &p_variant) {
+void BulletPhysicsServer3D::soft_body_set_state(RID p_body, BodyState p_state, const Variant &p_variant) {
// FIXME: Must be implemented.
WARN_PRINT("soft_body_state is not implemented yet in Bullet backend.");
}
-Variant BulletPhysicsServer::soft_body_get_state(RID p_body, BodyState p_state) const {
+Variant BulletPhysicsServer3D::soft_body_get_state(RID p_body, BodyState p_state) const {
// FIXME: Must be implemented.
WARN_PRINT("soft_body_state is not implemented yet in Bullet backend.");
return Variant();
}
-void BulletPhysicsServer::soft_body_set_transform(RID p_body, const Transform &p_transform) {
+void BulletPhysicsServer3D::soft_body_set_transform(RID p_body, const Transform &p_transform) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_soft_transform(p_transform);
}
-Vector3 BulletPhysicsServer::soft_body_get_vertex_position(RID p_body, int vertex_index) const {
+Vector3 BulletPhysicsServer3D::soft_body_get_vertex_position(RID p_body, int vertex_index) const {
const SoftBodyBullet *body = soft_body_owner.getornull(p_body);
Vector3 pos;
ERR_FAIL_COND_V(!body, pos);
@@ -1019,133 +1019,133 @@ Vector3 BulletPhysicsServer::soft_body_get_vertex_position(RID p_body, int verte
return pos;
}
-void BulletPhysicsServer::soft_body_set_ray_pickable(RID p_body, bool p_enable) {
+void BulletPhysicsServer3D::soft_body_set_ray_pickable(RID p_body, bool p_enable) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_ray_pickable(p_enable);
}
-bool BulletPhysicsServer::soft_body_is_ray_pickable(RID p_body) const {
+bool BulletPhysicsServer3D::soft_body_is_ray_pickable(RID p_body) const {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, false);
return body->is_ray_pickable();
}
-void BulletPhysicsServer::soft_body_set_simulation_precision(RID p_body, int p_simulation_precision) {
+void BulletPhysicsServer3D::soft_body_set_simulation_precision(RID p_body, int p_simulation_precision) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_simulation_precision(p_simulation_precision);
}
-int BulletPhysicsServer::soft_body_get_simulation_precision(RID p_body) {
+int BulletPhysicsServer3D::soft_body_get_simulation_precision(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_simulation_precision();
}
-void BulletPhysicsServer::soft_body_set_total_mass(RID p_body, real_t p_total_mass) {
+void BulletPhysicsServer3D::soft_body_set_total_mass(RID p_body, real_t p_total_mass) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_total_mass(p_total_mass);
}
-real_t BulletPhysicsServer::soft_body_get_total_mass(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_total_mass(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_total_mass();
}
-void BulletPhysicsServer::soft_body_set_linear_stiffness(RID p_body, real_t p_stiffness) {
+void BulletPhysicsServer3D::soft_body_set_linear_stiffness(RID p_body, real_t p_stiffness) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_linear_stiffness(p_stiffness);
}
-real_t BulletPhysicsServer::soft_body_get_linear_stiffness(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_linear_stiffness(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_linear_stiffness();
}
-void BulletPhysicsServer::soft_body_set_areaAngular_stiffness(RID p_body, real_t p_stiffness) {
+void BulletPhysicsServer3D::soft_body_set_areaAngular_stiffness(RID p_body, real_t p_stiffness) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_areaAngular_stiffness(p_stiffness);
}
-real_t BulletPhysicsServer::soft_body_get_areaAngular_stiffness(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_areaAngular_stiffness(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_areaAngular_stiffness();
}
-void BulletPhysicsServer::soft_body_set_volume_stiffness(RID p_body, real_t p_stiffness) {
+void BulletPhysicsServer3D::soft_body_set_volume_stiffness(RID p_body, real_t p_stiffness) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_volume_stiffness(p_stiffness);
}
-real_t BulletPhysicsServer::soft_body_get_volume_stiffness(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_volume_stiffness(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_volume_stiffness();
}
-void BulletPhysicsServer::soft_body_set_pressure_coefficient(RID p_body, real_t p_pressure_coefficient) {
+void BulletPhysicsServer3D::soft_body_set_pressure_coefficient(RID p_body, real_t p_pressure_coefficient) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_pressure_coefficient(p_pressure_coefficient);
}
-real_t BulletPhysicsServer::soft_body_get_pressure_coefficient(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_pressure_coefficient(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_pressure_coefficient();
}
-void BulletPhysicsServer::soft_body_set_pose_matching_coefficient(RID p_body, real_t p_pose_matching_coefficient) {
+void BulletPhysicsServer3D::soft_body_set_pose_matching_coefficient(RID p_body, real_t p_pose_matching_coefficient) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
return body->set_pose_matching_coefficient(p_pose_matching_coefficient);
}
-real_t BulletPhysicsServer::soft_body_get_pose_matching_coefficient(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_pose_matching_coefficient(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_pose_matching_coefficient();
}
-void BulletPhysicsServer::soft_body_set_damping_coefficient(RID p_body, real_t p_damping_coefficient) {
+void BulletPhysicsServer3D::soft_body_set_damping_coefficient(RID p_body, real_t p_damping_coefficient) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_damping_coefficient(p_damping_coefficient);
}
-real_t BulletPhysicsServer::soft_body_get_damping_coefficient(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_damping_coefficient(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_damping_coefficient();
}
-void BulletPhysicsServer::soft_body_set_drag_coefficient(RID p_body, real_t p_drag_coefficient) {
+void BulletPhysicsServer3D::soft_body_set_drag_coefficient(RID p_body, real_t p_drag_coefficient) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_drag_coefficient(p_drag_coefficient);
}
-real_t BulletPhysicsServer::soft_body_get_drag_coefficient(RID p_body) {
+real_t BulletPhysicsServer3D::soft_body_get_drag_coefficient(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_drag_coefficient();
}
-void BulletPhysicsServer::soft_body_move_point(RID p_body, int p_point_index, const Vector3 &p_global_position) {
+void BulletPhysicsServer3D::soft_body_move_point(RID p_body, int p_point_index, const Vector3 &p_global_position) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_node_position(p_point_index, p_global_position);
}
-Vector3 BulletPhysicsServer::soft_body_get_point_global_position(RID p_body, int p_point_index) {
+Vector3 BulletPhysicsServer3D::soft_body_get_point_global_position(RID p_body, int p_point_index) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, Vector3(0., 0., 0.));
Vector3 pos;
@@ -1153,7 +1153,7 @@ Vector3 BulletPhysicsServer::soft_body_get_point_global_position(RID p_body, int
return pos;
}
-Vector3 BulletPhysicsServer::soft_body_get_point_offset(RID p_body, int p_point_index) const {
+Vector3 BulletPhysicsServer3D::soft_body_get_point_offset(RID p_body, int p_point_index) const {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, Vector3());
Vector3 res;
@@ -1161,60 +1161,60 @@ Vector3 BulletPhysicsServer::soft_body_get_point_offset(RID p_body, int p_point_
return res;
}
-void BulletPhysicsServer::soft_body_remove_all_pinned_points(RID p_body) {
+void BulletPhysicsServer3D::soft_body_remove_all_pinned_points(RID p_body) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->reset_all_node_mass();
}
-void BulletPhysicsServer::soft_body_pin_point(RID p_body, int p_point_index, bool p_pin) {
+void BulletPhysicsServer3D::soft_body_pin_point(RID p_body, int p_point_index, bool p_pin) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND(!body);
body->set_node_mass(p_point_index, p_pin ? 0 : 1);
}
-bool BulletPhysicsServer::soft_body_is_point_pinned(RID p_body, int p_point_index) {
+bool BulletPhysicsServer3D::soft_body_is_point_pinned(RID p_body, int p_point_index) {
SoftBodyBullet *body = soft_body_owner.getornull(p_body);
ERR_FAIL_COND_V(!body, 0.f);
return body->get_node_mass(p_point_index);
}
-PhysicsServer::JointType BulletPhysicsServer::joint_get_type(RID p_joint) const {
+PhysicsServer3D::JointType BulletPhysicsServer3D::joint_get_type(RID p_joint) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, JOINT_PIN);
return joint->get_type();
}
-void BulletPhysicsServer::joint_set_solver_priority(RID p_joint, int p_priority) {
+void BulletPhysicsServer3D::joint_set_solver_priority(RID p_joint, int p_priority) {
// Joint priority not supported by bullet
}
-int BulletPhysicsServer::joint_get_solver_priority(RID p_joint) const {
+int BulletPhysicsServer3D::joint_get_solver_priority(RID p_joint) const {
// Joint priority not supported by bullet
return 0;
}
-void BulletPhysicsServer::joint_disable_collisions_between_bodies(RID p_joint, const bool p_disable) {
+void BulletPhysicsServer3D::joint_disable_collisions_between_bodies(RID p_joint, const bool p_disable) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
joint->disable_collisions_between_bodies(p_disable);
}
-bool BulletPhysicsServer::joint_is_disabled_collisions_between_bodies(RID p_joint) const {
+bool BulletPhysicsServer3D::joint_is_disabled_collisions_between_bodies(RID p_joint) const {
JointBullet *joint(joint_owner.getornull(p_joint));
ERR_FAIL_COND_V(!joint, false);
return joint->is_disabled_collisions_between_bodies();
}
-RID BulletPhysicsServer::joint_create_pin(RID p_body_A, const Vector3 &p_local_A, RID p_body_B, const Vector3 &p_local_B) {
+RID BulletPhysicsServer3D::joint_create_pin(RID p_body_A, const Vector3 &p_local_A, RID p_body_B, const Vector3 &p_local_B) {
RigidBodyBullet *body_A = rigid_body_owner.getornull(p_body_A);
ERR_FAIL_COND_V(!body_A, RID());
JointAssertSpace(body_A, "A", RID());
- RigidBodyBullet *body_B = NULL;
+ RigidBodyBullet *body_B = nullptr;
if (p_body_B.is_valid()) {
body_B = rigid_body_owner.getornull(p_body_B);
JointAssertSpace(body_B, "B", RID());
@@ -1229,7 +1229,7 @@ RID BulletPhysicsServer::joint_create_pin(RID p_body_A, const Vector3 &p_local_A
CreateThenReturnRID(joint_owner, joint);
}
-void BulletPhysicsServer::pin_joint_set_param(RID p_joint, PinJointParam p_param, float p_value) {
+void BulletPhysicsServer3D::pin_joint_set_param(RID p_joint, PinJointParam p_param, float p_value) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_PIN);
@@ -1237,7 +1237,7 @@ void BulletPhysicsServer::pin_joint_set_param(RID p_joint, PinJointParam p_param
pin_joint->set_param(p_param, p_value);
}
-float BulletPhysicsServer::pin_joint_get_param(RID p_joint, PinJointParam p_param) const {
+float BulletPhysicsServer3D::pin_joint_get_param(RID p_joint, PinJointParam p_param) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, 0);
ERR_FAIL_COND_V(joint->get_type() != JOINT_PIN, 0);
@@ -1245,7 +1245,7 @@ float BulletPhysicsServer::pin_joint_get_param(RID p_joint, PinJointParam p_para
return pin_joint->get_param(p_param);
}
-void BulletPhysicsServer::pin_joint_set_local_a(RID p_joint, const Vector3 &p_A) {
+void BulletPhysicsServer3D::pin_joint_set_local_a(RID p_joint, const Vector3 &p_A) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_PIN);
@@ -1253,7 +1253,7 @@ void BulletPhysicsServer::pin_joint_set_local_a(RID p_joint, const Vector3 &p_A)
pin_joint->setPivotInA(p_A);
}
-Vector3 BulletPhysicsServer::pin_joint_get_local_a(RID p_joint) const {
+Vector3 BulletPhysicsServer3D::pin_joint_get_local_a(RID p_joint) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, Vector3());
ERR_FAIL_COND_V(joint->get_type() != JOINT_PIN, Vector3());
@@ -1261,7 +1261,7 @@ Vector3 BulletPhysicsServer::pin_joint_get_local_a(RID p_joint) const {
return pin_joint->getPivotInA();
}
-void BulletPhysicsServer::pin_joint_set_local_b(RID p_joint, const Vector3 &p_B) {
+void BulletPhysicsServer3D::pin_joint_set_local_b(RID p_joint, const Vector3 &p_B) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_PIN);
@@ -1269,7 +1269,7 @@ void BulletPhysicsServer::pin_joint_set_local_b(RID p_joint, const Vector3 &p_B)
pin_joint->setPivotInB(p_B);
}
-Vector3 BulletPhysicsServer::pin_joint_get_local_b(RID p_joint) const {
+Vector3 BulletPhysicsServer3D::pin_joint_get_local_b(RID p_joint) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, Vector3());
ERR_FAIL_COND_V(joint->get_type() != JOINT_PIN, Vector3());
@@ -1277,12 +1277,12 @@ Vector3 BulletPhysicsServer::pin_joint_get_local_b(RID p_joint) const {
return pin_joint->getPivotInB();
}
-RID BulletPhysicsServer::joint_create_hinge(RID p_body_A, const Transform &p_hinge_A, RID p_body_B, const Transform &p_hinge_B) {
+RID BulletPhysicsServer3D::joint_create_hinge(RID p_body_A, const Transform &p_hinge_A, RID p_body_B, const Transform &p_hinge_B) {
RigidBodyBullet *body_A = rigid_body_owner.getornull(p_body_A);
ERR_FAIL_COND_V(!body_A, RID());
JointAssertSpace(body_A, "A", RID());
- RigidBodyBullet *body_B = NULL;
+ RigidBodyBullet *body_B = nullptr;
if (p_body_B.is_valid()) {
body_B = rigid_body_owner.getornull(p_body_B);
JointAssertSpace(body_B, "B", RID());
@@ -1297,12 +1297,12 @@ RID BulletPhysicsServer::joint_create_hinge(RID p_body_A, const Transform &p_hin
CreateThenReturnRID(joint_owner, joint);
}
-RID BulletPhysicsServer::joint_create_hinge_simple(RID p_body_A, const Vector3 &p_pivot_A, const Vector3 &p_axis_A, RID p_body_B, const Vector3 &p_pivot_B, const Vector3 &p_axis_B) {
+RID BulletPhysicsServer3D::joint_create_hinge_simple(RID p_body_A, const Vector3 &p_pivot_A, const Vector3 &p_axis_A, RID p_body_B, const Vector3 &p_pivot_B, const Vector3 &p_axis_B) {
RigidBodyBullet *body_A = rigid_body_owner.getornull(p_body_A);
ERR_FAIL_COND_V(!body_A, RID());
JointAssertSpace(body_A, "A", RID());
- RigidBodyBullet *body_B = NULL;
+ RigidBodyBullet *body_B = nullptr;
if (p_body_B.is_valid()) {
body_B = rigid_body_owner.getornull(p_body_B);
JointAssertSpace(body_B, "B", RID());
@@ -1317,7 +1317,7 @@ RID BulletPhysicsServer::joint_create_hinge_simple(RID p_body_A, const Vector3 &
CreateThenReturnRID(joint_owner, joint);
}
-void BulletPhysicsServer::hinge_joint_set_param(RID p_joint, HingeJointParam p_param, float p_value) {
+void BulletPhysicsServer3D::hinge_joint_set_param(RID p_joint, HingeJointParam p_param, float p_value) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_HINGE);
@@ -1325,7 +1325,7 @@ void BulletPhysicsServer::hinge_joint_set_param(RID p_joint, HingeJointParam p_p
hinge_joint->set_param(p_param, p_value);
}
-float BulletPhysicsServer::hinge_joint_get_param(RID p_joint, HingeJointParam p_param) const {
+float BulletPhysicsServer3D::hinge_joint_get_param(RID p_joint, HingeJointParam p_param) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, 0);
ERR_FAIL_COND_V(joint->get_type() != JOINT_HINGE, 0);
@@ -1333,7 +1333,7 @@ float BulletPhysicsServer::hinge_joint_get_param(RID p_joint, HingeJointParam p_
return hinge_joint->get_param(p_param);
}
-void BulletPhysicsServer::hinge_joint_set_flag(RID p_joint, HingeJointFlag p_flag, bool p_value) {
+void BulletPhysicsServer3D::hinge_joint_set_flag(RID p_joint, HingeJointFlag p_flag, bool p_value) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_HINGE);
@@ -1341,7 +1341,7 @@ void BulletPhysicsServer::hinge_joint_set_flag(RID p_joint, HingeJointFlag p_fla
hinge_joint->set_flag(p_flag, p_value);
}
-bool BulletPhysicsServer::hinge_joint_get_flag(RID p_joint, HingeJointFlag p_flag) const {
+bool BulletPhysicsServer3D::hinge_joint_get_flag(RID p_joint, HingeJointFlag p_flag) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, false);
ERR_FAIL_COND_V(joint->get_type() != JOINT_HINGE, false);
@@ -1349,12 +1349,12 @@ bool BulletPhysicsServer::hinge_joint_get_flag(RID p_joint, HingeJointFlag p_fla
return hinge_joint->get_flag(p_flag);
}
-RID BulletPhysicsServer::joint_create_slider(RID p_body_A, const Transform &p_local_frame_A, RID p_body_B, const Transform &p_local_frame_B) {
+RID BulletPhysicsServer3D::joint_create_slider(RID p_body_A, const Transform &p_local_frame_A, RID p_body_B, const Transform &p_local_frame_B) {
RigidBodyBullet *body_A = rigid_body_owner.getornull(p_body_A);
ERR_FAIL_COND_V(!body_A, RID());
JointAssertSpace(body_A, "A", RID());
- RigidBodyBullet *body_B = NULL;
+ RigidBodyBullet *body_B = nullptr;
if (p_body_B.is_valid()) {
body_B = rigid_body_owner.getornull(p_body_B);
JointAssertSpace(body_B, "B", RID());
@@ -1369,7 +1369,7 @@ RID BulletPhysicsServer::joint_create_slider(RID p_body_A, const Transform &p_lo
CreateThenReturnRID(joint_owner, joint);
}
-void BulletPhysicsServer::slider_joint_set_param(RID p_joint, SliderJointParam p_param, float p_value) {
+void BulletPhysicsServer3D::slider_joint_set_param(RID p_joint, SliderJointParam p_param, float p_value) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_SLIDER);
@@ -1377,7 +1377,7 @@ void BulletPhysicsServer::slider_joint_set_param(RID p_joint, SliderJointParam p
slider_joint->set_param(p_param, p_value);
}
-float BulletPhysicsServer::slider_joint_get_param(RID p_joint, SliderJointParam p_param) const {
+float BulletPhysicsServer3D::slider_joint_get_param(RID p_joint, SliderJointParam p_param) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, 0);
ERR_FAIL_COND_V(joint->get_type() != JOINT_SLIDER, 0);
@@ -1385,12 +1385,12 @@ float BulletPhysicsServer::slider_joint_get_param(RID p_joint, SliderJointParam
return slider_joint->get_param(p_param);
}
-RID BulletPhysicsServer::joint_create_cone_twist(RID p_body_A, const Transform &p_local_frame_A, RID p_body_B, const Transform &p_local_frame_B) {
+RID BulletPhysicsServer3D::joint_create_cone_twist(RID p_body_A, const Transform &p_local_frame_A, RID p_body_B, const Transform &p_local_frame_B) {
RigidBodyBullet *body_A = rigid_body_owner.getornull(p_body_A);
ERR_FAIL_COND_V(!body_A, RID());
JointAssertSpace(body_A, "A", RID());
- RigidBodyBullet *body_B = NULL;
+ RigidBodyBullet *body_B = nullptr;
if (p_body_B.is_valid()) {
body_B = rigid_body_owner.getornull(p_body_B);
JointAssertSpace(body_B, "B", RID());
@@ -1403,7 +1403,7 @@ RID BulletPhysicsServer::joint_create_cone_twist(RID p_body_A, const Transform &
CreateThenReturnRID(joint_owner, joint);
}
-void BulletPhysicsServer::cone_twist_joint_set_param(RID p_joint, ConeTwistJointParam p_param, float p_value) {
+void BulletPhysicsServer3D::cone_twist_joint_set_param(RID p_joint, ConeTwistJointParam p_param, float p_value) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_CONE_TWIST);
@@ -1411,7 +1411,7 @@ void BulletPhysicsServer::cone_twist_joint_set_param(RID p_joint, ConeTwistJoint
coneTwist_joint->set_param(p_param, p_value);
}
-float BulletPhysicsServer::cone_twist_joint_get_param(RID p_joint, ConeTwistJointParam p_param) const {
+float BulletPhysicsServer3D::cone_twist_joint_get_param(RID p_joint, ConeTwistJointParam p_param) const {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, 0.);
ERR_FAIL_COND_V(joint->get_type() != JOINT_CONE_TWIST, 0.);
@@ -1419,12 +1419,12 @@ float BulletPhysicsServer::cone_twist_joint_get_param(RID p_joint, ConeTwistJoin
return coneTwist_joint->get_param(p_param);
}
-RID BulletPhysicsServer::joint_create_generic_6dof(RID p_body_A, const Transform &p_local_frame_A, RID p_body_B, const Transform &p_local_frame_B) {
+RID BulletPhysicsServer3D::joint_create_generic_6dof(RID p_body_A, const Transform &p_local_frame_A, RID p_body_B, const Transform &p_local_frame_B) {
RigidBodyBullet *body_A = rigid_body_owner.getornull(p_body_A);
ERR_FAIL_COND_V(!body_A, RID());
JointAssertSpace(body_A, "A", RID());
- RigidBodyBullet *body_B = NULL;
+ RigidBodyBullet *body_B = nullptr;
if (p_body_B.is_valid()) {
body_B = rigid_body_owner.getornull(p_body_B);
JointAssertSpace(body_B, "B", RID());
@@ -1439,7 +1439,7 @@ RID BulletPhysicsServer::joint_create_generic_6dof(RID p_body_A, const Transform
CreateThenReturnRID(joint_owner, joint);
}
-void BulletPhysicsServer::generic_6dof_joint_set_param(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisParam p_param, float p_value) {
+void BulletPhysicsServer3D::generic_6dof_joint_set_param(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisParam p_param, float p_value) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_6DOF);
@@ -1447,7 +1447,7 @@ void BulletPhysicsServer::generic_6dof_joint_set_param(RID p_joint, Vector3::Axi
generic_6dof_joint->set_param(p_axis, p_param, p_value);
}
-float BulletPhysicsServer::generic_6dof_joint_get_param(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisParam p_param) {
+float BulletPhysicsServer3D::generic_6dof_joint_get_param(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisParam p_param) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, 0);
ERR_FAIL_COND_V(joint->get_type() != JOINT_6DOF, 0);
@@ -1455,7 +1455,7 @@ float BulletPhysicsServer::generic_6dof_joint_get_param(RID p_joint, Vector3::Ax
return generic_6dof_joint->get_param(p_axis, p_param);
}
-void BulletPhysicsServer::generic_6dof_joint_set_flag(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisFlag p_flag, bool p_enable) {
+void BulletPhysicsServer3D::generic_6dof_joint_set_flag(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisFlag p_flag, bool p_enable) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_6DOF);
@@ -1463,7 +1463,7 @@ void BulletPhysicsServer::generic_6dof_joint_set_flag(RID p_joint, Vector3::Axis
generic_6dof_joint->set_flag(p_axis, p_flag, p_enable);
}
-bool BulletPhysicsServer::generic_6dof_joint_get_flag(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisFlag p_flag) {
+bool BulletPhysicsServer3D::generic_6dof_joint_get_flag(RID p_joint, Vector3::Axis p_axis, G6DOFJointAxisFlag p_flag) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, false);
ERR_FAIL_COND_V(joint->get_type() != JOINT_6DOF, false);
@@ -1471,7 +1471,7 @@ bool BulletPhysicsServer::generic_6dof_joint_get_flag(RID p_joint, Vector3::Axis
return generic_6dof_joint->get_flag(p_axis, p_flag);
}
-void BulletPhysicsServer::generic_6dof_joint_set_precision(RID p_joint, int p_precision) {
+void BulletPhysicsServer3D::generic_6dof_joint_set_precision(RID p_joint, int p_precision) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND(!joint);
ERR_FAIL_COND(joint->get_type() != JOINT_6DOF);
@@ -1479,7 +1479,7 @@ void BulletPhysicsServer::generic_6dof_joint_set_precision(RID p_joint, int p_pr
generic_6dof_joint->set_precision(p_precision);
}
-int BulletPhysicsServer::generic_6dof_joint_get_precision(RID p_joint) {
+int BulletPhysicsServer3D::generic_6dof_joint_get_precision(RID p_joint) {
JointBullet *joint = joint_owner.getornull(p_joint);
ERR_FAIL_COND_V(!joint, 0);
ERR_FAIL_COND_V(joint->get_type() != JOINT_6DOF, 0);
@@ -1487,7 +1487,7 @@ int BulletPhysicsServer::generic_6dof_joint_get_precision(RID p_joint) {
return generic_6dof_joint->get_precision();
}
-void BulletPhysicsServer::free(RID p_rid) {
+void BulletPhysicsServer3D::free(RID p_rid) {
if (shape_owner.owns(p_rid)) {
ShapeBullet *shape = shape_owner.getornull(p_rid);
@@ -1503,7 +1503,7 @@ void BulletPhysicsServer::free(RID p_rid) {
RigidBodyBullet *body = rigid_body_owner.getornull(p_rid);
- body->set_space(NULL);
+ body->set_space(nullptr);
body->remove_all_shapes(true, true);
@@ -1514,7 +1514,7 @@ void BulletPhysicsServer::free(RID p_rid) {
SoftBodyBullet *body = soft_body_owner.getornull(p_rid);
- body->set_space(NULL);
+ body->set_space(nullptr);
soft_body_owner.free(p_rid);
bulletdelete(body);
@@ -1523,7 +1523,7 @@ void BulletPhysicsServer::free(RID p_rid) {
AreaBullet *area = area_owner.getornull(p_rid);
- area->set_space(NULL);
+ area->set_space(nullptr);
area->remove_all_shapes(true, true);
@@ -1552,15 +1552,15 @@ void BulletPhysicsServer::free(RID p_rid) {
}
}
-void BulletPhysicsServer::init() {
- BulletPhysicsDirectBodyState::initSingleton();
+void BulletPhysicsServer3D::init() {
+ BulletPhysicsDirectBodyState3D::initSingleton();
}
-void BulletPhysicsServer::step(float p_deltaTime) {
+void BulletPhysicsServer3D::step(float p_deltaTime) {
if (!active)
return;
- BulletPhysicsDirectBodyState::singleton_setDeltaTime(p_deltaTime);
+ BulletPhysicsDirectBodyState3D::singleton_setDeltaTime(p_deltaTime);
for (int i = 0; i < active_spaces_count; ++i) {
@@ -1568,21 +1568,21 @@ void BulletPhysicsServer::step(float p_deltaTime) {
}
}
-void BulletPhysicsServer::sync() {
+void BulletPhysicsServer3D::sync() {
}
-void BulletPhysicsServer::flush_queries() {
+void BulletPhysicsServer3D::flush_queries() {
}
-void BulletPhysicsServer::finish() {
- BulletPhysicsDirectBodyState::destroySingleton();
+void BulletPhysicsServer3D::finish() {
+ BulletPhysicsDirectBodyState3D::destroySingleton();
}
-int BulletPhysicsServer::get_process_info(ProcessInfo p_info) {
+int BulletPhysicsServer3D::get_process_info(ProcessInfo p_info) {
return 0;
}
-CollisionObjectBullet *BulletPhysicsServer::get_collisin_object(RID p_object) const {
+CollisionObjectBullet *BulletPhysicsServer3D::get_collisin_object(RID p_object) const {
if (rigid_body_owner.owns(p_object)) {
return rigid_body_owner.getornull(p_object);
}
@@ -1592,15 +1592,15 @@ CollisionObjectBullet *BulletPhysicsServer::get_collisin_object(RID p_object) co
if (soft_body_owner.owns(p_object)) {
return soft_body_owner.getornull(p_object);
}
- return NULL;
+ return nullptr;
}
-RigidCollisionObjectBullet *BulletPhysicsServer::get_rigid_collisin_object(RID p_object) const {
+RigidCollisionObjectBullet *BulletPhysicsServer3D::get_rigid_collisin_object(RID p_object) const {
if (rigid_body_owner.owns(p_object)) {
return rigid_body_owner.getornull(p_object);
}
if (area_owner.owns(p_object)) {
return area_owner.getornull(p_object);
}
- return NULL;
+ return nullptr;
}
diff --git a/modules/bullet/bullet_physics_server.h b/modules/bullet/bullet_physics_server.h
index 6ea9a7a974..ea9c5e589e 100644
--- a/modules/bullet/bullet_physics_server.h
+++ b/modules/bullet/bullet_physics_server.h
@@ -36,7 +36,7 @@
#include "core/rid_owner.h"
#include "joint_bullet.h"
#include "rigid_body_bullet.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#include "shape_bullet.h"
#include "soft_body_bullet.h"
#include "space_bullet.h"
@@ -44,8 +44,8 @@
@author AndreaCatania
*/
-class BulletPhysicsServer : public PhysicsServer {
- GDCLASS(BulletPhysicsServer, PhysicsServer);
+class BulletPhysicsServer3D : public PhysicsServer3D {
+ GDCLASS(BulletPhysicsServer3D, PhysicsServer3D);
friend class BulletPhysicsDirectSpaceState;
@@ -64,8 +64,8 @@ protected:
static void _bind_methods();
public:
- BulletPhysicsServer();
- ~BulletPhysicsServer();
+ BulletPhysicsServer3D();
+ ~BulletPhysicsServer3D();
_FORCE_INLINE_ RID_PtrOwner<SpaceBullet> *get_space_owner() {
return &space_owner;
@@ -111,7 +111,7 @@ public:
/// Not supported
virtual real_t space_get_param(RID p_space, SpaceParameter p_param) const;
- virtual PhysicsDirectSpaceState *space_get_direct_state(RID p_space);
+ virtual PhysicsDirectSpaceState3D *space_get_direct_state(RID p_space);
virtual void space_set_debug_contacts(RID p_space, int p_max_contacts);
virtual Vector<Vector3> space_get_contacts(RID p_space) const;
@@ -252,16 +252,16 @@ public:
virtual bool body_is_ray_pickable(RID p_body) const;
// this function only works on physics process, errors and returns null otherwise
- virtual PhysicsDirectBodyState *body_get_direct_state(RID p_body);
+ virtual PhysicsDirectBodyState3D *body_get_direct_state(RID p_body);
- virtual bool body_test_motion(RID p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, MotionResult *r_result = NULL, bool p_exclude_raycast_shapes = true);
+ virtual bool body_test_motion(RID p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, MotionResult *r_result = nullptr, bool p_exclude_raycast_shapes = true);
virtual int body_test_ray_separation(RID p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, SeparationResult *r_results, int p_result_max, float p_margin = 0.001);
/* SOFT BODY API */
virtual RID soft_body_create(bool p_init_sleeping = false);
- virtual void soft_body_update_visual_server(RID p_body, class SoftBodyVisualServerHandler *p_visual_server_handler);
+ virtual void soft_body_update_rendering_server(RID p_body, class SoftBodyRenderingServerHandler *p_rendering_server_handler);
virtual void soft_body_set_space(RID p_body, RID p_space);
virtual RID soft_body_get_space(RID p_body) const;
@@ -387,7 +387,7 @@ public:
}
static bool singleton_isActive() {
- return static_cast<BulletPhysicsServer *>(get_singleton())->active;
+ return static_cast<BulletPhysicsServer3D *>(get_singleton())->active;
}
bool isActive() {
diff --git a/modules/bullet/bullet_utilities.h b/modules/bullet/bullet_utilities.h
index 968cb38ba2..a5e33d9829 100644
--- a/modules/bullet/bullet_utilities.h
+++ b/modules/bullet/bullet_utilities.h
@@ -41,6 +41,6 @@
#define bulletdelete(cl) \
{ \
delete cl; \
- cl = NULL; \
+ cl = nullptr; \
}
#endif
diff --git a/modules/bullet/collision_object_bullet.cpp b/modules/bullet/collision_object_bullet.cpp
index 5b7e7281e4..1b72c2f577 100644
--- a/modules/bullet/collision_object_bullet.cpp
+++ b/modules/bullet/collision_object_bullet.cpp
@@ -60,7 +60,7 @@ void CollisionObjectBullet::ShapeWrapper::set_transform(const btTransform &p_tra
}
btTransform CollisionObjectBullet::ShapeWrapper::get_adjusted_transform() const {
- if (shape->get_type() == PhysicsServer::SHAPE_HEIGHTMAP) {
+ if (shape->get_type() == PhysicsServer3D::SHAPE_HEIGHTMAP) {
const HeightMapShapeBullet *hm_shape = (const HeightMapShapeBullet *)shape; // should be safe to cast now
btTransform adjusted_transform;
@@ -96,10 +96,10 @@ CollisionObjectBullet::CollisionObjectBullet(Type p_type) :
collisionsEnabled(true),
m_isStatic(false),
ray_pickable(false),
- bt_collision_object(NULL),
+ bt_collision_object(nullptr),
body_scale(1., 1., 1.),
force_shape_reset(false),
- space(NULL),
+ space(nullptr),
isTransformChanged(false) {}
CollisionObjectBullet::~CollisionObjectBullet() {
@@ -227,7 +227,7 @@ void CollisionObjectBullet::notify_transform_changed() {
RigidCollisionObjectBullet::RigidCollisionObjectBullet(Type p_type) :
CollisionObjectBullet(p_type),
- mainShape(NULL) {
+ mainShape(nullptr) {
}
RigidCollisionObjectBullet::~RigidCollisionObjectBullet() {
@@ -332,7 +332,7 @@ bool RigidCollisionObjectBullet::is_shape_disabled(int p_index) {
void RigidCollisionObjectBullet::shape_changed(int p_shape_index) {
ShapeWrapper &shp = shapes.write[p_shape_index];
if (shp.bt_shape == mainShape) {
- mainShape = NULL;
+ mainShape = nullptr;
}
bulletdelete(shp.bt_shape);
reload_shapes();
@@ -345,7 +345,7 @@ void RigidCollisionObjectBullet::reload_shapes() {
bulletdelete(mainShape);
}
- mainShape = NULL;
+ mainShape = nullptr;
ShapeWrapper *shpWrapper;
const int shape_count = shapes.size();
@@ -398,7 +398,7 @@ void RigidCollisionObjectBullet::internal_shape_destroy(int p_index, bool p_perm
ShapeWrapper &shp = shapes.write[p_index];
shp.shape->remove_owner(this, p_permanentlyFromThisBody);
if (shp.bt_shape == mainShape) {
- mainShape = NULL;
+ mainShape = nullptr;
}
bulletdelete(shp.bt_shape);
}
diff --git a/modules/bullet/collision_object_bullet.h b/modules/bullet/collision_object_bullet.h
index 42ba4aa907..25176458a7 100644
--- a/modules/bullet/collision_object_bullet.h
+++ b/modules/bullet/collision_object_bullet.h
@@ -76,20 +76,20 @@ public:
bool active;
ShapeWrapper() :
- shape(NULL),
- bt_shape(NULL),
+ shape(nullptr),
+ bt_shape(nullptr),
active(true) {}
ShapeWrapper(ShapeBullet *p_shape, const btTransform &p_transform, bool p_active) :
shape(p_shape),
- bt_shape(NULL),
+ bt_shape(nullptr),
active(p_active) {
set_transform(p_transform);
}
ShapeWrapper(ShapeBullet *p_shape, const Transform &p_transform, bool p_active) :
shape(p_shape),
- bt_shape(NULL),
+ bt_shape(nullptr),
active(p_active) {
set_transform(p_transform);
}
diff --git a/modules/bullet/cone_twist_joint_bullet.cpp b/modules/bullet/cone_twist_joint_bullet.cpp
index 23eb39fe7e..aac51034b8 100644
--- a/modules/bullet/cone_twist_joint_bullet.cpp
+++ b/modules/bullet/cone_twist_joint_bullet.cpp
@@ -64,43 +64,43 @@ ConeTwistJointBullet::ConeTwistJointBullet(RigidBodyBullet *rbA, RigidBodyBullet
setup(coneConstraint);
}
-void ConeTwistJointBullet::set_param(PhysicsServer::ConeTwistJointParam p_param, real_t p_value) {
+void ConeTwistJointBullet::set_param(PhysicsServer3D::ConeTwistJointParam p_param, real_t p_value) {
switch (p_param) {
- case PhysicsServer::CONE_TWIST_JOINT_SWING_SPAN:
+ case PhysicsServer3D::CONE_TWIST_JOINT_SWING_SPAN:
coneConstraint->setLimit(5, p_value);
coneConstraint->setLimit(4, p_value);
break;
- case PhysicsServer::CONE_TWIST_JOINT_TWIST_SPAN:
+ case PhysicsServer3D::CONE_TWIST_JOINT_TWIST_SPAN:
coneConstraint->setLimit(3, p_value);
break;
- case PhysicsServer::CONE_TWIST_JOINT_BIAS:
+ case PhysicsServer3D::CONE_TWIST_JOINT_BIAS:
coneConstraint->setLimit(coneConstraint->getSwingSpan1(), coneConstraint->getSwingSpan2(), coneConstraint->getTwistSpan(), coneConstraint->getLimitSoftness(), p_value, coneConstraint->getRelaxationFactor());
break;
- case PhysicsServer::CONE_TWIST_JOINT_SOFTNESS:
+ case PhysicsServer3D::CONE_TWIST_JOINT_SOFTNESS:
coneConstraint->setLimit(coneConstraint->getSwingSpan1(), coneConstraint->getSwingSpan2(), coneConstraint->getTwistSpan(), p_value, coneConstraint->getBiasFactor(), coneConstraint->getRelaxationFactor());
break;
- case PhysicsServer::CONE_TWIST_JOINT_RELAXATION:
+ case PhysicsServer3D::CONE_TWIST_JOINT_RELAXATION:
coneConstraint->setLimit(coneConstraint->getSwingSpan1(), coneConstraint->getSwingSpan2(), coneConstraint->getTwistSpan(), coneConstraint->getLimitSoftness(), coneConstraint->getBiasFactor(), p_value);
break;
- case PhysicsServer::CONE_TWIST_MAX:
+ case PhysicsServer3D::CONE_TWIST_MAX:
// Internal size value, nothing to do.
break;
}
}
-real_t ConeTwistJointBullet::get_param(PhysicsServer::ConeTwistJointParam p_param) const {
+real_t ConeTwistJointBullet::get_param(PhysicsServer3D::ConeTwistJointParam p_param) const {
switch (p_param) {
- case PhysicsServer::CONE_TWIST_JOINT_SWING_SPAN:
+ case PhysicsServer3D::CONE_TWIST_JOINT_SWING_SPAN:
return coneConstraint->getSwingSpan1();
- case PhysicsServer::CONE_TWIST_JOINT_TWIST_SPAN:
+ case PhysicsServer3D::CONE_TWIST_JOINT_TWIST_SPAN:
return coneConstraint->getTwistSpan();
- case PhysicsServer::CONE_TWIST_JOINT_BIAS:
+ case PhysicsServer3D::CONE_TWIST_JOINT_BIAS:
return coneConstraint->getBiasFactor();
- case PhysicsServer::CONE_TWIST_JOINT_SOFTNESS:
+ case PhysicsServer3D::CONE_TWIST_JOINT_SOFTNESS:
return coneConstraint->getLimitSoftness();
- case PhysicsServer::CONE_TWIST_JOINT_RELAXATION:
+ case PhysicsServer3D::CONE_TWIST_JOINT_RELAXATION:
return coneConstraint->getRelaxationFactor();
- case PhysicsServer::CONE_TWIST_MAX:
+ case PhysicsServer3D::CONE_TWIST_MAX:
// Internal size value, nothing to do.
return 0;
}
diff --git a/modules/bullet/cone_twist_joint_bullet.h b/modules/bullet/cone_twist_joint_bullet.h
index 134706f8bb..ed4baa9d1b 100644
--- a/modules/bullet/cone_twist_joint_bullet.h
+++ b/modules/bullet/cone_twist_joint_bullet.h
@@ -45,9 +45,9 @@ class ConeTwistJointBullet : public JointBullet {
public:
ConeTwistJointBullet(RigidBodyBullet *rbA, RigidBodyBullet *rbB, const Transform &rbAFrame, const Transform &rbBFrame);
- virtual PhysicsServer::JointType get_type() const { return PhysicsServer::JOINT_CONE_TWIST; }
+ virtual PhysicsServer3D::JointType get_type() const { return PhysicsServer3D::JOINT_CONE_TWIST; }
- void set_param(PhysicsServer::ConeTwistJointParam p_param, real_t p_value);
- real_t get_param(PhysicsServer::ConeTwistJointParam p_param) const;
+ void set_param(PhysicsServer3D::ConeTwistJointParam p_param, real_t p_value);
+ real_t get_param(PhysicsServer3D::ConeTwistJointParam p_param) const;
};
#endif
diff --git a/modules/bullet/config.py b/modules/bullet/config.py
index 92dbcf5cb0..d22f9454ed 100644
--- a/modules/bullet/config.py
+++ b/modules/bullet/config.py
@@ -1,14 +1,6 @@
def can_build(env, platform):
return True
+
def configure(env):
pass
-
-def get_doc_classes():
- return [
- "BulletPhysicsDirectBodyState",
- "BulletPhysicsServer",
- ]
-
-def get_doc_path():
- return "doc_classes"
diff --git a/modules/bullet/constraint_bullet.cpp b/modules/bullet/constraint_bullet.cpp
index 7e90e2b488..469b58521e 100644
--- a/modules/bullet/constraint_bullet.cpp
+++ b/modules/bullet/constraint_bullet.cpp
@@ -38,8 +38,8 @@
*/
ConstraintBullet::ConstraintBullet() :
- space(NULL),
- constraint(NULL),
+ space(nullptr),
+ constraint(nullptr),
disabled_collisions_between_bodies(true) {}
void ConstraintBullet::setup(btTypedConstraint *p_constraint) {
diff --git a/modules/bullet/constraint_bullet.h b/modules/bullet/constraint_bullet.h
index 89ad150257..1946807bad 100644
--- a/modules/bullet/constraint_bullet.h
+++ b/modules/bullet/constraint_bullet.h
@@ -64,7 +64,7 @@ public:
public:
virtual ~ConstraintBullet() {
bulletdelete(constraint);
- constraint = NULL;
+ constraint = nullptr;
}
_FORCE_INLINE_ btTypedConstraint *get_bt_constraint() { return constraint; }
diff --git a/modules/bullet/doc_classes/BulletPhysicsDirectBodyState.xml b/modules/bullet/doc_classes/BulletPhysicsDirectBodyState.xml
deleted file mode 100644
index 5ea1b810a1..0000000000
--- a/modules/bullet/doc_classes/BulletPhysicsDirectBodyState.xml
+++ /dev/null
@@ -1,13 +0,0 @@
-<?xml version="1.0" encoding="UTF-8" ?>
-<class name="BulletPhysicsDirectBodyState" inherits="PhysicsDirectBodyState" version="4.0">
- <brief_description>
- </brief_description>
- <description>
- </description>
- <tutorials>
- </tutorials>
- <methods>
- </methods>
- <constants>
- </constants>
-</class>
diff --git a/modules/bullet/doc_classes/BulletPhysicsServer.xml b/modules/bullet/doc_classes/BulletPhysicsServer.xml
deleted file mode 100644
index af8fb3c02c..0000000000
--- a/modules/bullet/doc_classes/BulletPhysicsServer.xml
+++ /dev/null
@@ -1,13 +0,0 @@
-<?xml version="1.0" encoding="UTF-8" ?>
-<class name="BulletPhysicsServer" inherits="PhysicsServer" version="4.0">
- <brief_description>
- </brief_description>
- <description>
- </description>
- <tutorials>
- </tutorials>
- <methods>
- </methods>
- <constants>
- </constants>
-</class>
diff --git a/modules/bullet/generic_6dof_joint_bullet.cpp b/modules/bullet/generic_6dof_joint_bullet.cpp
index 45ab3d3bb2..638944df76 100644
--- a/modules/bullet/generic_6dof_joint_bullet.cpp
+++ b/modules/bullet/generic_6dof_joint_bullet.cpp
@@ -43,6 +43,12 @@
Generic6DOFJointBullet::Generic6DOFJointBullet(RigidBodyBullet *rbA, RigidBodyBullet *rbB, const Transform &frameInA, const Transform &frameInB) :
JointBullet() {
+ for (int i = 0; i < 3; i++) {
+ for (int j = 0; j < PhysicsServer3D::G6DOF_JOINT_FLAG_MAX; j++) {
+ flags[i][j] = false;
+ }
+ }
+
Transform scaled_AFrame(frameInA.scaled(rbA->get_body_scale()));
scaled_AFrame.basis.rotref_posscale_decomposition(scaled_AFrame.basis);
@@ -118,62 +124,62 @@ void Generic6DOFJointBullet::set_angular_upper_limit(const Vector3 &angularUpper
sixDOFConstraint->setAngularUpperLimit(btVec);
}
-void Generic6DOFJointBullet::set_param(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisParam p_param, real_t p_value) {
+void Generic6DOFJointBullet::set_param(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisParam p_param, real_t p_value) {
ERR_FAIL_INDEX(p_axis, 3);
switch (p_param) {
- case PhysicsServer::G6DOF_JOINT_LINEAR_LOWER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_LOWER_LIMIT:
limits_lower[0][p_axis] = p_value;
- set_flag(p_axis, PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT, flags[p_axis][PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT]); // Reload bullet parameter
+ set_flag(p_axis, PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT, flags[p_axis][PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT]); // Reload bullet parameter
break;
- case PhysicsServer::G6DOF_JOINT_LINEAR_UPPER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_UPPER_LIMIT:
limits_upper[0][p_axis] = p_value;
- set_flag(p_axis, PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT, flags[p_axis][PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT]); // Reload bullet parameter
+ set_flag(p_axis, PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT, flags[p_axis][PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT]); // Reload bullet parameter
break;
- case PhysicsServer::G6DOF_JOINT_LINEAR_MOTOR_TARGET_VELOCITY:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_MOTOR_TARGET_VELOCITY:
sixDOFConstraint->getTranslationalLimitMotor()->m_targetVelocity.m_floats[p_axis] = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_LINEAR_MOTOR_FORCE_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_MOTOR_FORCE_LIMIT:
sixDOFConstraint->getTranslationalLimitMotor()->m_maxMotorForce.m_floats[p_axis] = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_LINEAR_SPRING_DAMPING:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_SPRING_DAMPING:
sixDOFConstraint->getTranslationalLimitMotor()->m_springDamping.m_floats[p_axis] = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_LINEAR_SPRING_STIFFNESS:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_SPRING_STIFFNESS:
sixDOFConstraint->getTranslationalLimitMotor()->m_springStiffness.m_floats[p_axis] = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_LINEAR_SPRING_EQUILIBRIUM_POINT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_SPRING_EQUILIBRIUM_POINT:
sixDOFConstraint->getTranslationalLimitMotor()->m_equilibriumPoint.m_floats[p_axis] = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_LOWER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_LOWER_LIMIT:
limits_lower[1][p_axis] = p_value;
- set_flag(p_axis, PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT, flags[p_axis][PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT]); // Reload bullet parameter
+ set_flag(p_axis, PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT, flags[p_axis][PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT]); // Reload bullet parameter
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_UPPER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_UPPER_LIMIT:
limits_upper[1][p_axis] = p_value;
- set_flag(p_axis, PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT, flags[p_axis][PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT]); // Reload bullet parameter
+ set_flag(p_axis, PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT, flags[p_axis][PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT]); // Reload bullet parameter
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_RESTITUTION:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_RESTITUTION:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_bounce = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_ERP:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_ERP:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_stopERP = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_MOTOR_TARGET_VELOCITY:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_MOTOR_TARGET_VELOCITY:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_targetVelocity = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_MOTOR_FORCE_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_MOTOR_FORCE_LIMIT:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_maxMotorForce = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_SPRING_STIFFNESS:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_SPRING_STIFFNESS:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_springStiffness = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_SPRING_DAMPING:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_SPRING_DAMPING:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_springDamping = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_SPRING_EQUILIBRIUM_POINT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_SPRING_EQUILIBRIUM_POINT:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_equilibriumPoint = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_MAX:
+ case PhysicsServer3D::G6DOF_JOINT_MAX:
// Internal size value, nothing to do.
break;
default:
@@ -182,42 +188,42 @@ void Generic6DOFJointBullet::set_param(Vector3::Axis p_axis, PhysicsServer::G6DO
}
}
-real_t Generic6DOFJointBullet::get_param(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisParam p_param) const {
+real_t Generic6DOFJointBullet::get_param(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisParam p_param) const {
ERR_FAIL_INDEX_V(p_axis, 3, 0.);
switch (p_param) {
- case PhysicsServer::G6DOF_JOINT_LINEAR_LOWER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_LOWER_LIMIT:
return limits_lower[0][p_axis];
- case PhysicsServer::G6DOF_JOINT_LINEAR_UPPER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_UPPER_LIMIT:
return limits_upper[0][p_axis];
- case PhysicsServer::G6DOF_JOINT_LINEAR_MOTOR_TARGET_VELOCITY:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_MOTOR_TARGET_VELOCITY:
return sixDOFConstraint->getTranslationalLimitMotor()->m_targetVelocity.m_floats[p_axis];
- case PhysicsServer::G6DOF_JOINT_LINEAR_MOTOR_FORCE_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_MOTOR_FORCE_LIMIT:
return sixDOFConstraint->getTranslationalLimitMotor()->m_maxMotorForce.m_floats[p_axis];
- case PhysicsServer::G6DOF_JOINT_LINEAR_SPRING_DAMPING:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_SPRING_DAMPING:
return sixDOFConstraint->getTranslationalLimitMotor()->m_springDamping.m_floats[p_axis];
- case PhysicsServer::G6DOF_JOINT_LINEAR_SPRING_STIFFNESS:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_SPRING_STIFFNESS:
return sixDOFConstraint->getTranslationalLimitMotor()->m_springStiffness.m_floats[p_axis];
- case PhysicsServer::G6DOF_JOINT_LINEAR_SPRING_EQUILIBRIUM_POINT:
+ case PhysicsServer3D::G6DOF_JOINT_LINEAR_SPRING_EQUILIBRIUM_POINT:
return sixDOFConstraint->getTranslationalLimitMotor()->m_equilibriumPoint.m_floats[p_axis];
- case PhysicsServer::G6DOF_JOINT_ANGULAR_LOWER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_LOWER_LIMIT:
return limits_lower[1][p_axis];
- case PhysicsServer::G6DOF_JOINT_ANGULAR_UPPER_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_UPPER_LIMIT:
return limits_upper[1][p_axis];
- case PhysicsServer::G6DOF_JOINT_ANGULAR_RESTITUTION:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_RESTITUTION:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_bounce;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_ERP:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_ERP:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_stopERP;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_MOTOR_TARGET_VELOCITY:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_MOTOR_TARGET_VELOCITY:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_targetVelocity;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_MOTOR_FORCE_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_MOTOR_FORCE_LIMIT:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_maxMotorForce;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_SPRING_STIFFNESS:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_SPRING_STIFFNESS:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_springStiffness;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_SPRING_DAMPING:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_SPRING_DAMPING:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_springDamping;
- case PhysicsServer::G6DOF_JOINT_ANGULAR_SPRING_EQUILIBRIUM_POINT:
+ case PhysicsServer3D::G6DOF_JOINT_ANGULAR_SPRING_EQUILIBRIUM_POINT:
return sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_equilibriumPoint;
- case PhysicsServer::G6DOF_JOINT_MAX:
+ case PhysicsServer3D::G6DOF_JOINT_MAX:
// Internal size value, nothing to do.
return 0;
default:
@@ -226,45 +232,45 @@ real_t Generic6DOFJointBullet::get_param(Vector3::Axis p_axis, PhysicsServer::G6
}
}
-void Generic6DOFJointBullet::set_flag(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisFlag p_flag, bool p_value) {
+void Generic6DOFJointBullet::set_flag(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisFlag p_flag, bool p_value) {
ERR_FAIL_INDEX(p_axis, 3);
flags[p_axis][p_flag] = p_value;
switch (p_flag) {
- case PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_LIMIT:
if (flags[p_axis][p_flag]) {
sixDOFConstraint->setLimit(p_axis, limits_lower[0][p_axis], limits_upper[0][p_axis]);
} else {
sixDOFConstraint->setLimit(p_axis, 0, -1); // Free
}
break;
- case PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_LIMIT:
if (flags[p_axis][p_flag]) {
sixDOFConstraint->setLimit(p_axis + 3, limits_lower[1][p_axis], limits_upper[1][p_axis]);
} else {
sixDOFConstraint->setLimit(p_axis + 3, 0, -1); // Free
}
break;
- case PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_SPRING:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_ANGULAR_SPRING:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_enableSpring = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_SPRING:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_SPRING:
sixDOFConstraint->getTranslationalLimitMotor()->m_enableSpring[p_axis] = p_value;
break;
- case PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_MOTOR:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_MOTOR:
sixDOFConstraint->getRotationalLimitMotor(p_axis)->m_enableMotor = flags[p_axis][p_flag];
break;
- case PhysicsServer::G6DOF_JOINT_FLAG_ENABLE_LINEAR_MOTOR:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_ENABLE_LINEAR_MOTOR:
sixDOFConstraint->getTranslationalLimitMotor()->m_enableMotor[p_axis] = flags[p_axis][p_flag];
break;
- case PhysicsServer::G6DOF_JOINT_FLAG_MAX:
+ case PhysicsServer3D::G6DOF_JOINT_FLAG_MAX:
// Internal size value, nothing to do.
break;
}
}
-bool Generic6DOFJointBullet::get_flag(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisFlag p_flag) const {
+bool Generic6DOFJointBullet::get_flag(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisFlag p_flag) const {
ERR_FAIL_INDEX_V(p_axis, 3, false);
return flags[p_axis][p_flag];
}
diff --git a/modules/bullet/generic_6dof_joint_bullet.h b/modules/bullet/generic_6dof_joint_bullet.h
index 75c8005811..316708bb11 100644
--- a/modules/bullet/generic_6dof_joint_bullet.h
+++ b/modules/bullet/generic_6dof_joint_bullet.h
@@ -45,12 +45,12 @@ class Generic6DOFJointBullet : public JointBullet {
// First is linear second is angular
Vector3 limits_lower[2];
Vector3 limits_upper[2];
- bool flags[3][PhysicsServer::G6DOF_JOINT_FLAG_MAX];
+ bool flags[3][PhysicsServer3D::G6DOF_JOINT_FLAG_MAX];
public:
Generic6DOFJointBullet(RigidBodyBullet *rbA, RigidBodyBullet *rbB, const Transform &frameInA, const Transform &frameInB);
- virtual PhysicsServer::JointType get_type() const { return PhysicsServer::JOINT_6DOF; }
+ virtual PhysicsServer3D::JointType get_type() const { return PhysicsServer3D::JOINT_6DOF; }
Transform getFrameOffsetA() const;
Transform getFrameOffsetB() const;
@@ -63,11 +63,11 @@ public:
void set_angular_lower_limit(const Vector3 &angularLower);
void set_angular_upper_limit(const Vector3 &angularUpper);
- void set_param(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisParam p_param, real_t p_value);
- real_t get_param(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisParam p_param) const;
+ void set_param(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisParam p_param, real_t p_value);
+ real_t get_param(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisParam p_param) const;
- void set_flag(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisFlag p_flag, bool p_value);
- bool get_flag(Vector3::Axis p_axis, PhysicsServer::G6DOFJointAxisFlag p_flag) const;
+ void set_flag(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisFlag p_flag, bool p_value);
+ bool get_flag(Vector3::Axis p_axis, PhysicsServer3D::G6DOFJointAxisFlag p_flag) const;
void set_precision(int p_precision);
int get_precision() const;
diff --git a/modules/bullet/godot_collision_configuration.cpp b/modules/bullet/godot_collision_configuration.cpp
index f3e3a01a52..8e29845a36 100644
--- a/modules/bullet/godot_collision_configuration.cpp
+++ b/modules/bullet/godot_collision_configuration.cpp
@@ -42,7 +42,7 @@
GodotCollisionConfiguration::GodotCollisionConfiguration(const btDiscreteDynamicsWorld *world, const btDefaultCollisionConstructionInfo &constructionInfo) :
btDefaultCollisionConfiguration(constructionInfo) {
- void *mem = NULL;
+ void *mem = nullptr;
mem = btAlignedAlloc(sizeof(GodotRayWorldAlgorithm::CreateFunc), 16);
m_rayWorldCF = new (mem) GodotRayWorldAlgorithm::CreateFunc(world);
@@ -98,7 +98,7 @@ btCollisionAlgorithmCreateFunc *GodotCollisionConfiguration::getClosestPointsAlg
GodotSoftCollisionConfiguration::GodotSoftCollisionConfiguration(const btDiscreteDynamicsWorld *world, const btDefaultCollisionConstructionInfo &constructionInfo) :
btSoftBodyRigidBodyCollisionConfiguration(constructionInfo) {
- void *mem = NULL;
+ void *mem = nullptr;
mem = btAlignedAlloc(sizeof(GodotRayWorldAlgorithm::CreateFunc), 16);
m_rayWorldCF = new (mem) GodotRayWorldAlgorithm::CreateFunc(world);
diff --git a/modules/bullet/godot_result_callbacks.cpp b/modules/bullet/godot_result_callbacks.cpp
index 20467e3ef3..ad20a7e451 100644
--- a/modules/bullet/godot_result_callbacks.cpp
+++ b/modules/bullet/godot_result_callbacks.cpp
@@ -107,12 +107,12 @@ btScalar GodotAllConvexResultCallback::addSingleResult(btCollisionWorld::LocalCo
CollisionObjectBullet *gObj = static_cast<CollisionObjectBullet *>(convexResult.m_hitCollisionObject->getUserPointer());
- PhysicsDirectSpaceState::ShapeResult &result = m_results[count];
+ PhysicsDirectSpaceState3D::ShapeResult &result = m_results[count];
result.shape = convexResult.m_localShapeInfo->m_triangleIndex; // "m_triangleIndex" Is a odd name but contains the compound shape ID
result.rid = gObj->get_self();
result.collider_id = gObj->get_instance_id();
- result.collider = result.collider_id.is_null() ? NULL : ObjectDB::get_instance(result.collider_id);
+ result.collider = result.collider_id.is_null() ? nullptr : ObjectDB::get_instance(result.collider_id);
++count;
return 1; // not used by bullet
@@ -207,7 +207,7 @@ btScalar GodotAllContactResultCallback::addSingleResult(btManifoldPoint &cp, con
if (cp.getDistance() <= 0) {
- PhysicsDirectSpaceState::ShapeResult &result = m_results[m_count];
+ PhysicsDirectSpaceState3D::ShapeResult &result = m_results[m_count];
// Penetrated
CollisionObjectBullet *colObj;
@@ -220,7 +220,7 @@ btScalar GodotAllContactResultCallback::addSingleResult(btManifoldPoint &cp, con
}
result.collider_id = colObj->get_instance_id();
- result.collider = result.collider_id.is_null() ? NULL : ObjectDB::get_instance(result.collider_id);
+ result.collider = result.collider_id.is_null() ? nullptr : ObjectDB::get_instance(result.collider_id);
result.rid = colObj->get_self();
++m_count;
}
diff --git a/modules/bullet/godot_result_callbacks.h b/modules/bullet/godot_result_callbacks.h
index 4f634ed6f0..7e74a2b22e 100644
--- a/modules/bullet/godot_result_callbacks.h
+++ b/modules/bullet/godot_result_callbacks.h
@@ -31,7 +31,7 @@
#ifndef GODOT_RESULT_CALLBACKS_H
#define GODOT_RESULT_CALLBACKS_H
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#include <BulletCollision/BroadphaseCollision/btBroadphaseProxy.h>
#include <btBulletDynamicsCommon.h>
@@ -85,12 +85,12 @@ public:
// store all colliding object
struct GodotAllConvexResultCallback : public btCollisionWorld::ConvexResultCallback {
public:
- PhysicsDirectSpaceState::ShapeResult *m_results;
+ PhysicsDirectSpaceState3D::ShapeResult *m_results;
int m_resultMax;
const Set<RID> *m_exclude;
int count;
- GodotAllConvexResultCallback(PhysicsDirectSpaceState::ShapeResult *p_results, int p_resultMax, const Set<RID> *p_exclude) :
+ GodotAllConvexResultCallback(PhysicsDirectSpaceState3D::ShapeResult *p_results, int p_resultMax, const Set<RID> *p_exclude) :
m_results(p_results),
m_resultMax(p_resultMax),
m_exclude(p_exclude),
@@ -137,7 +137,7 @@ public:
struct GodotAllContactResultCallback : public btCollisionWorld::ContactResultCallback {
public:
const btCollisionObject *m_self_object;
- PhysicsDirectSpaceState::ShapeResult *m_results;
+ PhysicsDirectSpaceState3D::ShapeResult *m_results;
int m_resultMax;
const Set<RID> *m_exclude;
int m_count;
@@ -145,7 +145,7 @@ public:
bool collide_with_bodies;
bool collide_with_areas;
- GodotAllContactResultCallback(btCollisionObject *p_self_object, PhysicsDirectSpaceState::ShapeResult *p_results, int p_resultMax, const Set<RID> *p_exclude, bool p_collide_with_bodies, bool p_collide_with_areas) :
+ GodotAllContactResultCallback(btCollisionObject *p_self_object, PhysicsDirectSpaceState3D::ShapeResult *p_results, int p_resultMax, const Set<RID> *p_exclude, bool p_collide_with_bodies, bool p_collide_with_areas) :
m_self_object(p_self_object),
m_results(p_results),
m_resultMax(p_resultMax),
@@ -188,7 +188,7 @@ public:
struct GodotRestInfoContactResultCallback : public btCollisionWorld::ContactResultCallback {
public:
const btCollisionObject *m_self_object;
- PhysicsDirectSpaceState::ShapeRestInfo *m_result;
+ PhysicsDirectSpaceState3D::ShapeRestInfo *m_result;
const Set<RID> *m_exclude;
bool m_collided;
real_t m_min_distance;
@@ -197,7 +197,7 @@ public:
bool collide_with_bodies;
bool collide_with_areas;
- GodotRestInfoContactResultCallback(btCollisionObject *p_self_object, PhysicsDirectSpaceState::ShapeRestInfo *p_result, const Set<RID> *p_exclude, bool p_collide_with_bodies, bool p_collide_with_areas) :
+ GodotRestInfoContactResultCallback(btCollisionObject *p_self_object, PhysicsDirectSpaceState3D::ShapeRestInfo *p_result, const Set<RID> *p_exclude, bool p_collide_with_bodies, bool p_collide_with_areas) :
m_self_object(p_self_object),
m_result(p_result),
m_exclude(p_exclude),
diff --git a/modules/bullet/hinge_joint_bullet.cpp b/modules/bullet/hinge_joint_bullet.cpp
index 970732688a..4bea9f87c0 100644
--- a/modules/bullet/hinge_joint_bullet.cpp
+++ b/modules/bullet/hinge_joint_bullet.cpp
@@ -93,58 +93,58 @@ real_t HingeJointBullet::get_hinge_angle() {
return hingeConstraint->getHingeAngle();
}
-void HingeJointBullet::set_param(PhysicsServer::HingeJointParam p_param, real_t p_value) {
+void HingeJointBullet::set_param(PhysicsServer3D::HingeJointParam p_param, real_t p_value) {
switch (p_param) {
- case PhysicsServer::HINGE_JOINT_BIAS:
- WARN_DEPRECATED_MSG("The HingeJoint parameter \"bias\" is deprecated.");
+ case PhysicsServer3D::HINGE_JOINT_BIAS:
+ WARN_DEPRECATED_MSG("The HingeJoint3D parameter \"bias\" is deprecated.");
break;
- case PhysicsServer::HINGE_JOINT_LIMIT_UPPER:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_UPPER:
hingeConstraint->setLimit(hingeConstraint->getLowerLimit(), p_value, hingeConstraint->getLimitSoftness(), hingeConstraint->getLimitBiasFactor(), hingeConstraint->getLimitRelaxationFactor());
break;
- case PhysicsServer::HINGE_JOINT_LIMIT_LOWER:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_LOWER:
hingeConstraint->setLimit(p_value, hingeConstraint->getUpperLimit(), hingeConstraint->getLimitSoftness(), hingeConstraint->getLimitBiasFactor(), hingeConstraint->getLimitRelaxationFactor());
break;
- case PhysicsServer::HINGE_JOINT_LIMIT_BIAS:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_BIAS:
hingeConstraint->setLimit(hingeConstraint->getLowerLimit(), hingeConstraint->getUpperLimit(), hingeConstraint->getLimitSoftness(), p_value, hingeConstraint->getLimitRelaxationFactor());
break;
- case PhysicsServer::HINGE_JOINT_LIMIT_SOFTNESS:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_SOFTNESS:
hingeConstraint->setLimit(hingeConstraint->getLowerLimit(), hingeConstraint->getUpperLimit(), p_value, hingeConstraint->getLimitBiasFactor(), hingeConstraint->getLimitRelaxationFactor());
break;
- case PhysicsServer::HINGE_JOINT_LIMIT_RELAXATION:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_RELAXATION:
hingeConstraint->setLimit(hingeConstraint->getLowerLimit(), hingeConstraint->getUpperLimit(), hingeConstraint->getLimitSoftness(), hingeConstraint->getLimitBiasFactor(), p_value);
break;
- case PhysicsServer::HINGE_JOINT_MOTOR_TARGET_VELOCITY:
+ case PhysicsServer3D::HINGE_JOINT_MOTOR_TARGET_VELOCITY:
hingeConstraint->setMotorTargetVelocity(p_value);
break;
- case PhysicsServer::HINGE_JOINT_MOTOR_MAX_IMPULSE:
+ case PhysicsServer3D::HINGE_JOINT_MOTOR_MAX_IMPULSE:
hingeConstraint->setMaxMotorImpulse(p_value);
break;
- case PhysicsServer::HINGE_JOINT_MAX:
+ case PhysicsServer3D::HINGE_JOINT_MAX:
// Internal size value, nothing to do.
break;
}
}
-real_t HingeJointBullet::get_param(PhysicsServer::HingeJointParam p_param) const {
+real_t HingeJointBullet::get_param(PhysicsServer3D::HingeJointParam p_param) const {
switch (p_param) {
- case PhysicsServer::HINGE_JOINT_BIAS:
- WARN_DEPRECATED_MSG("The HingeJoint parameter \"bias\" is deprecated.");
+ case PhysicsServer3D::HINGE_JOINT_BIAS:
+ WARN_DEPRECATED_MSG("The HingeJoint3D parameter \"bias\" is deprecated.");
return 0;
- case PhysicsServer::HINGE_JOINT_LIMIT_UPPER:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_UPPER:
return hingeConstraint->getUpperLimit();
- case PhysicsServer::HINGE_JOINT_LIMIT_LOWER:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_LOWER:
return hingeConstraint->getLowerLimit();
- case PhysicsServer::HINGE_JOINT_LIMIT_BIAS:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_BIAS:
return hingeConstraint->getLimitBiasFactor();
- case PhysicsServer::HINGE_JOINT_LIMIT_SOFTNESS:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_SOFTNESS:
return hingeConstraint->getLimitSoftness();
- case PhysicsServer::HINGE_JOINT_LIMIT_RELAXATION:
+ case PhysicsServer3D::HINGE_JOINT_LIMIT_RELAXATION:
return hingeConstraint->getLimitRelaxationFactor();
- case PhysicsServer::HINGE_JOINT_MOTOR_TARGET_VELOCITY:
+ case PhysicsServer3D::HINGE_JOINT_MOTOR_TARGET_VELOCITY:
return hingeConstraint->getMotorTargetVelocity();
- case PhysicsServer::HINGE_JOINT_MOTOR_MAX_IMPULSE:
+ case PhysicsServer3D::HINGE_JOINT_MOTOR_MAX_IMPULSE:
return hingeConstraint->getMaxMotorImpulse();
- case PhysicsServer::HINGE_JOINT_MAX:
+ case PhysicsServer3D::HINGE_JOINT_MAX:
// Internal size value, nothing to do.
return 0;
}
@@ -152,25 +152,25 @@ real_t HingeJointBullet::get_param(PhysicsServer::HingeJointParam p_param) const
return 0;
}
-void HingeJointBullet::set_flag(PhysicsServer::HingeJointFlag p_flag, bool p_value) {
+void HingeJointBullet::set_flag(PhysicsServer3D::HingeJointFlag p_flag, bool p_value) {
switch (p_flag) {
- case PhysicsServer::HINGE_JOINT_FLAG_USE_LIMIT:
+ case PhysicsServer3D::HINGE_JOINT_FLAG_USE_LIMIT:
if (!p_value) {
hingeConstraint->setLimit(-Math_PI, Math_PI);
}
break;
- case PhysicsServer::HINGE_JOINT_FLAG_ENABLE_MOTOR:
+ case PhysicsServer3D::HINGE_JOINT_FLAG_ENABLE_MOTOR:
hingeConstraint->enableMotor(p_value);
break;
- case PhysicsServer::HINGE_JOINT_FLAG_MAX: break; // Can't happen, but silences warning
+ case PhysicsServer3D::HINGE_JOINT_FLAG_MAX: break; // Can't happen, but silences warning
}
}
-bool HingeJointBullet::get_flag(PhysicsServer::HingeJointFlag p_flag) const {
+bool HingeJointBullet::get_flag(PhysicsServer3D::HingeJointFlag p_flag) const {
switch (p_flag) {
- case PhysicsServer::HINGE_JOINT_FLAG_USE_LIMIT:
+ case PhysicsServer3D::HINGE_JOINT_FLAG_USE_LIMIT:
return true;
- case PhysicsServer::HINGE_JOINT_FLAG_ENABLE_MOTOR:
+ case PhysicsServer3D::HINGE_JOINT_FLAG_ENABLE_MOTOR:
return hingeConstraint->getEnableAngularMotor();
default:
return false;
diff --git a/modules/bullet/hinge_joint_bullet.h b/modules/bullet/hinge_joint_bullet.h
index d1061fe52f..120c40e5c0 100644
--- a/modules/bullet/hinge_joint_bullet.h
+++ b/modules/bullet/hinge_joint_bullet.h
@@ -44,14 +44,14 @@ public:
HingeJointBullet(RigidBodyBullet *rbA, RigidBodyBullet *rbB, const Transform &frameA, const Transform &frameB);
HingeJointBullet(RigidBodyBullet *rbA, RigidBodyBullet *rbB, const Vector3 &pivotInA, const Vector3 &pivotInB, const Vector3 &axisInA, const Vector3 &axisInB);
- virtual PhysicsServer::JointType get_type() const { return PhysicsServer::JOINT_HINGE; }
+ virtual PhysicsServer3D::JointType get_type() const { return PhysicsServer3D::JOINT_HINGE; }
real_t get_hinge_angle();
- void set_param(PhysicsServer::HingeJointParam p_param, real_t p_value);
- real_t get_param(PhysicsServer::HingeJointParam p_param) const;
+ void set_param(PhysicsServer3D::HingeJointParam p_param, real_t p_value);
+ real_t get_param(PhysicsServer3D::HingeJointParam p_param) const;
- void set_flag(PhysicsServer::HingeJointFlag p_flag, bool p_value);
- bool get_flag(PhysicsServer::HingeJointFlag p_flag) const;
+ void set_flag(PhysicsServer3D::HingeJointFlag p_flag, bool p_value);
+ bool get_flag(PhysicsServer3D::HingeJointFlag p_flag) const;
};
#endif
diff --git a/modules/bullet/joint_bullet.h b/modules/bullet/joint_bullet.h
index c840eb8f14..9cb8aab276 100644
--- a/modules/bullet/joint_bullet.h
+++ b/modules/bullet/joint_bullet.h
@@ -32,7 +32,7 @@
#define JOINT_BULLET_H
#include "constraint_bullet.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
/**
@author AndreaCatania
@@ -47,6 +47,6 @@ public:
JointBullet();
virtual ~JointBullet();
- virtual PhysicsServer::JointType get_type() const = 0;
+ virtual PhysicsServer3D::JointType get_type() const = 0;
};
#endif
diff --git a/modules/bullet/pin_joint_bullet.cpp b/modules/bullet/pin_joint_bullet.cpp
index 8d109f1866..68b40d7405 100644
--- a/modules/bullet/pin_joint_bullet.cpp
+++ b/modules/bullet/pin_joint_bullet.cpp
@@ -62,27 +62,27 @@ PinJointBullet::PinJointBullet(RigidBodyBullet *p_body_a, const Vector3 &p_pos_a
PinJointBullet::~PinJointBullet() {}
-void PinJointBullet::set_param(PhysicsServer::PinJointParam p_param, real_t p_value) {
+void PinJointBullet::set_param(PhysicsServer3D::PinJointParam p_param, real_t p_value) {
switch (p_param) {
- case PhysicsServer::PIN_JOINT_BIAS:
+ case PhysicsServer3D::PIN_JOINT_BIAS:
p2pConstraint->m_setting.m_tau = p_value;
break;
- case PhysicsServer::PIN_JOINT_DAMPING:
+ case PhysicsServer3D::PIN_JOINT_DAMPING:
p2pConstraint->m_setting.m_damping = p_value;
break;
- case PhysicsServer::PIN_JOINT_IMPULSE_CLAMP:
+ case PhysicsServer3D::PIN_JOINT_IMPULSE_CLAMP:
p2pConstraint->m_setting.m_impulseClamp = p_value;
break;
}
}
-real_t PinJointBullet::get_param(PhysicsServer::PinJointParam p_param) const {
+real_t PinJointBullet::get_param(PhysicsServer3D::PinJointParam p_param) const {
switch (p_param) {
- case PhysicsServer::PIN_JOINT_BIAS:
+ case PhysicsServer3D::PIN_JOINT_BIAS:
return p2pConstraint->m_setting.m_tau;
- case PhysicsServer::PIN_JOINT_DAMPING:
+ case PhysicsServer3D::PIN_JOINT_DAMPING:
return p2pConstraint->m_setting.m_damping;
- case PhysicsServer::PIN_JOINT_IMPULSE_CLAMP:
+ case PhysicsServer3D::PIN_JOINT_IMPULSE_CLAMP:
return p2pConstraint->m_setting.m_impulseClamp;
}
// Compiler doesn't seem to notice that all code paths are fulfilled...
diff --git a/modules/bullet/pin_joint_bullet.h b/modules/bullet/pin_joint_bullet.h
index d6e7a945b5..e7d05f34d4 100644
--- a/modules/bullet/pin_joint_bullet.h
+++ b/modules/bullet/pin_joint_bullet.h
@@ -46,10 +46,10 @@ public:
PinJointBullet(RigidBodyBullet *p_body_a, const Vector3 &p_pos_a, RigidBodyBullet *p_body_b, const Vector3 &p_pos_b);
~PinJointBullet();
- virtual PhysicsServer::JointType get_type() const { return PhysicsServer::JOINT_PIN; }
+ virtual PhysicsServer3D::JointType get_type() const { return PhysicsServer3D::JOINT_PIN; }
- void set_param(PhysicsServer::PinJointParam p_param, real_t p_value);
- real_t get_param(PhysicsServer::PinJointParam p_param) const;
+ void set_param(PhysicsServer3D::PinJointParam p_param, real_t p_value);
+ real_t get_param(PhysicsServer3D::PinJointParam p_param) const;
void setPivotInA(const Vector3 &p_pos);
void setPivotInB(const Vector3 &p_pos);
diff --git a/modules/bullet/register_types.cpp b/modules/bullet/register_types.cpp
index 7819b67cad..009d0dff63 100644
--- a/modules/bullet/register_types.cpp
+++ b/modules/bullet/register_types.cpp
@@ -39,15 +39,15 @@
*/
#ifndef _3D_DISABLED
-PhysicsServer *_createBulletPhysicsCallback() {
- return memnew(BulletPhysicsServer);
+PhysicsServer3D *_createBulletPhysicsCallback() {
+ return memnew(BulletPhysicsServer3D);
}
#endif
void register_bullet_types() {
#ifndef _3D_DISABLED
- PhysicsServerManager::register_server("Bullet", &_createBulletPhysicsCallback);
- PhysicsServerManager::set_default_server("Bullet", 1);
+ PhysicsServer3DManager::register_server("Bullet", &_createBulletPhysicsCallback);
+ PhysicsServer3DManager::set_default_server("Bullet", 1);
GLOBAL_DEF("physics/3d/active_soft_world", true);
ProjectSettings::get_singleton()->set_custom_property_info("physics/3d/active_soft_world", PropertyInfo(Variant::BOOL, "physics/3d/active_soft_world"));
diff --git a/modules/bullet/rid_bullet.h b/modules/bullet/rid_bullet.h
index b76641ca54..3551ca05f9 100644
--- a/modules/bullet/rid_bullet.h
+++ b/modules/bullet/rid_bullet.h
@@ -37,17 +37,17 @@
@author AndreaCatania
*/
-class BulletPhysicsServer;
+class BulletPhysicsServer3D;
class RIDBullet {
RID self;
- BulletPhysicsServer *physicsServer;
+ BulletPhysicsServer3D *physicsServer;
public:
_FORCE_INLINE_ void set_self(const RID &p_self) { self = p_self; }
_FORCE_INLINE_ RID get_self() const { return self; }
- _FORCE_INLINE_ void _set_physics_server(BulletPhysicsServer *p_physicsServer) { physicsServer = p_physicsServer; }
- _FORCE_INLINE_ BulletPhysicsServer *get_physics_server() const { return physicsServer; }
+ _FORCE_INLINE_ void _set_physics_server(BulletPhysicsServer3D *p_physicsServer) { physicsServer = p_physicsServer; }
+ _FORCE_INLINE_ BulletPhysicsServer3D *get_physics_server() const { return physicsServer; }
};
#endif
diff --git a/modules/bullet/rigid_body_bullet.cpp b/modules/bullet/rigid_body_bullet.cpp
index 80f42c8441..a4f9affa95 100644
--- a/modules/bullet/rigid_body_bullet.cpp
+++ b/modules/bullet/rigid_body_bullet.cpp
@@ -48,141 +48,141 @@
@author AndreaCatania
*/
-BulletPhysicsDirectBodyState *BulletPhysicsDirectBodyState::singleton = NULL;
+BulletPhysicsDirectBodyState3D *BulletPhysicsDirectBodyState3D::singleton = nullptr;
-Vector3 BulletPhysicsDirectBodyState::get_total_gravity() const {
+Vector3 BulletPhysicsDirectBodyState3D::get_total_gravity() const {
Vector3 gVec;
B_TO_G(body->btBody->getGravity(), gVec);
return gVec;
}
-float BulletPhysicsDirectBodyState::get_total_angular_damp() const {
+float BulletPhysicsDirectBodyState3D::get_total_angular_damp() const {
return body->btBody->getAngularDamping();
}
-float BulletPhysicsDirectBodyState::get_total_linear_damp() const {
+float BulletPhysicsDirectBodyState3D::get_total_linear_damp() const {
return body->btBody->getLinearDamping();
}
-Vector3 BulletPhysicsDirectBodyState::get_center_of_mass() const {
+Vector3 BulletPhysicsDirectBodyState3D::get_center_of_mass() const {
Vector3 gVec;
B_TO_G(body->btBody->getCenterOfMassPosition(), gVec);
return gVec;
}
-Basis BulletPhysicsDirectBodyState::get_principal_inertia_axes() const {
+Basis BulletPhysicsDirectBodyState3D::get_principal_inertia_axes() const {
return Basis();
}
-float BulletPhysicsDirectBodyState::get_inverse_mass() const {
+float BulletPhysicsDirectBodyState3D::get_inverse_mass() const {
return body->btBody->getInvMass();
}
-Vector3 BulletPhysicsDirectBodyState::get_inverse_inertia() const {
+Vector3 BulletPhysicsDirectBodyState3D::get_inverse_inertia() const {
Vector3 gVec;
B_TO_G(body->btBody->getInvInertiaDiagLocal(), gVec);
return gVec;
}
-Basis BulletPhysicsDirectBodyState::get_inverse_inertia_tensor() const {
+Basis BulletPhysicsDirectBodyState3D::get_inverse_inertia_tensor() const {
Basis gInertia;
B_TO_G(body->btBody->getInvInertiaTensorWorld(), gInertia);
return gInertia;
}
-void BulletPhysicsDirectBodyState::set_linear_velocity(const Vector3 &p_velocity) {
+void BulletPhysicsDirectBodyState3D::set_linear_velocity(const Vector3 &p_velocity) {
body->set_linear_velocity(p_velocity);
}
-Vector3 BulletPhysicsDirectBodyState::get_linear_velocity() const {
+Vector3 BulletPhysicsDirectBodyState3D::get_linear_velocity() const {
return body->get_linear_velocity();
}
-void BulletPhysicsDirectBodyState::set_angular_velocity(const Vector3 &p_velocity) {
+void BulletPhysicsDirectBodyState3D::set_angular_velocity(const Vector3 &p_velocity) {
body->set_angular_velocity(p_velocity);
}
-Vector3 BulletPhysicsDirectBodyState::get_angular_velocity() const {
+Vector3 BulletPhysicsDirectBodyState3D::get_angular_velocity() const {
return body->get_angular_velocity();
}
-void BulletPhysicsDirectBodyState::set_transform(const Transform &p_transform) {
+void BulletPhysicsDirectBodyState3D::set_transform(const Transform &p_transform) {
body->set_transform(p_transform);
}
-Transform BulletPhysicsDirectBodyState::get_transform() const {
+Transform BulletPhysicsDirectBodyState3D::get_transform() const {
return body->get_transform();
}
-void BulletPhysicsDirectBodyState::add_central_force(const Vector3 &p_force) {
+void BulletPhysicsDirectBodyState3D::add_central_force(const Vector3 &p_force) {
body->apply_central_force(p_force);
}
-void BulletPhysicsDirectBodyState::add_force(const Vector3 &p_force, const Vector3 &p_pos) {
+void BulletPhysicsDirectBodyState3D::add_force(const Vector3 &p_force, const Vector3 &p_pos) {
body->apply_force(p_force, p_pos);
}
-void BulletPhysicsDirectBodyState::add_torque(const Vector3 &p_torque) {
+void BulletPhysicsDirectBodyState3D::add_torque(const Vector3 &p_torque) {
body->apply_torque(p_torque);
}
-void BulletPhysicsDirectBodyState::apply_central_impulse(const Vector3 &p_impulse) {
+void BulletPhysicsDirectBodyState3D::apply_central_impulse(const Vector3 &p_impulse) {
body->apply_central_impulse(p_impulse);
}
-void BulletPhysicsDirectBodyState::apply_impulse(const Vector3 &p_pos, const Vector3 &p_impulse) {
+void BulletPhysicsDirectBodyState3D::apply_impulse(const Vector3 &p_pos, const Vector3 &p_impulse) {
body->apply_impulse(p_pos, p_impulse);
}
-void BulletPhysicsDirectBodyState::apply_torque_impulse(const Vector3 &p_impulse) {
+void BulletPhysicsDirectBodyState3D::apply_torque_impulse(const Vector3 &p_impulse) {
body->apply_torque_impulse(p_impulse);
}
-void BulletPhysicsDirectBodyState::set_sleep_state(bool p_enable) {
- body->set_activation_state(p_enable);
+void BulletPhysicsDirectBodyState3D::set_sleep_state(bool p_sleep) {
+ body->set_activation_state(!p_sleep);
}
-bool BulletPhysicsDirectBodyState::is_sleeping() const {
+bool BulletPhysicsDirectBodyState3D::is_sleeping() const {
return !body->is_active();
}
-int BulletPhysicsDirectBodyState::get_contact_count() const {
+int BulletPhysicsDirectBodyState3D::get_contact_count() const {
return body->collisionsCount;
}
-Vector3 BulletPhysicsDirectBodyState::get_contact_local_position(int p_contact_idx) const {
+Vector3 BulletPhysicsDirectBodyState3D::get_contact_local_position(int p_contact_idx) const {
return body->collisions[p_contact_idx].hitLocalLocation;
}
-Vector3 BulletPhysicsDirectBodyState::get_contact_local_normal(int p_contact_idx) const {
+Vector3 BulletPhysicsDirectBodyState3D::get_contact_local_normal(int p_contact_idx) const {
return body->collisions[p_contact_idx].hitNormal;
}
-float BulletPhysicsDirectBodyState::get_contact_impulse(int p_contact_idx) const {
+float BulletPhysicsDirectBodyState3D::get_contact_impulse(int p_contact_idx) const {
return body->collisions[p_contact_idx].appliedImpulse;
}
-int BulletPhysicsDirectBodyState::get_contact_local_shape(int p_contact_idx) const {
+int BulletPhysicsDirectBodyState3D::get_contact_local_shape(int p_contact_idx) const {
return body->collisions[p_contact_idx].local_shape;
}
-RID BulletPhysicsDirectBodyState::get_contact_collider(int p_contact_idx) const {
+RID BulletPhysicsDirectBodyState3D::get_contact_collider(int p_contact_idx) const {
return body->collisions[p_contact_idx].otherObject->get_self();
}
-Vector3 BulletPhysicsDirectBodyState::get_contact_collider_position(int p_contact_idx) const {
+Vector3 BulletPhysicsDirectBodyState3D::get_contact_collider_position(int p_contact_idx) const {
return body->collisions[p_contact_idx].hitWorldLocation;
}
-ObjectID BulletPhysicsDirectBodyState::get_contact_collider_id(int p_contact_idx) const {
+ObjectID BulletPhysicsDirectBodyState3D::get_contact_collider_id(int p_contact_idx) const {
return body->collisions[p_contact_idx].otherObject->get_instance_id();
}
-int BulletPhysicsDirectBodyState::get_contact_collider_shape(int p_contact_idx) const {
+int BulletPhysicsDirectBodyState3D::get_contact_collider_shape(int p_contact_idx) const {
return body->collisions[p_contact_idx].other_object_shape;
}
-Vector3 BulletPhysicsDirectBodyState::get_contact_collider_velocity_at_position(int p_contact_idx) const {
+Vector3 BulletPhysicsDirectBodyState3D::get_contact_collider_velocity_at_position(int p_contact_idx) const {
RigidBodyBullet::CollisionData &colDat = body->collisions.write[p_contact_idx];
btVector3 hitLocation;
@@ -194,7 +194,7 @@ Vector3 BulletPhysicsDirectBodyState::get_contact_collider_velocity_at_position(
return velocityAtPoint;
}
-PhysicsDirectSpaceState *BulletPhysicsDirectBodyState::get_space_state() {
+PhysicsDirectSpaceState3D *BulletPhysicsDirectBodyState3D::get_space_state() {
return body->get_space()->get_direct_state();
}
@@ -231,17 +231,17 @@ void RigidBodyBullet::KinematicUtilities::copyAllOwnerShapes() {
shapes.write[i].transform = shape_wrapper->transform;
shapes.write[i].transform.getOrigin() *= owner_scale;
switch (shape_wrapper->shape->get_type()) {
- case PhysicsServer::SHAPE_SPHERE:
- case PhysicsServer::SHAPE_BOX:
- case PhysicsServer::SHAPE_CAPSULE:
- case PhysicsServer::SHAPE_CYLINDER:
- case PhysicsServer::SHAPE_CONVEX_POLYGON:
- case PhysicsServer::SHAPE_RAY: {
+ case PhysicsServer3D::SHAPE_SPHERE:
+ case PhysicsServer3D::SHAPE_BOX:
+ case PhysicsServer3D::SHAPE_CAPSULE:
+ case PhysicsServer3D::SHAPE_CYLINDER:
+ case PhysicsServer3D::SHAPE_CONVEX_POLYGON:
+ case PhysicsServer3D::SHAPE_RAY: {
shapes.write[i].shape = static_cast<btConvexShape *>(shape_wrapper->shape->create_bt_shape(owner_scale * shape_wrapper->scale, safe_margin));
} break;
default:
WARN_PRINT("This shape is not supported for kinematic collision.");
- shapes.write[i].shape = NULL;
+ shapes.write[i].shape = nullptr;
}
}
}
@@ -257,7 +257,7 @@ void RigidBodyBullet::KinematicUtilities::just_delete_shapes(int new_size) {
RigidBodyBullet::RigidBodyBullet() :
RigidCollisionObjectBullet(CollisionObjectBullet::TYPE_RIGID_BODY),
- kinematic_utilities(NULL),
+ kinematic_utilities(nullptr),
locked_axis(0),
mass(1),
gravity_scale(1),
@@ -274,24 +274,24 @@ RigidBodyBullet::RigidBodyBullet() :
countGravityPointSpaces(0),
isScratchedSpaceOverrideModificator(false),
previousActiveState(true),
- force_integration_callback(NULL) {
+ force_integration_callback(nullptr) {
godotMotionState = bulletnew(GodotMotionState(this));
// Initial properties
const btVector3 localInertia(0, 0, 0);
- btRigidBody::btRigidBodyConstructionInfo cInfo(mass, godotMotionState, NULL, localInertia);
+ btRigidBody::btRigidBodyConstructionInfo cInfo(mass, godotMotionState, nullptr, localInertia);
btBody = bulletnew(btRigidBody(cInfo));
reload_shapes();
setupBulletCollisionObject(btBody);
- set_mode(PhysicsServer::BODY_MODE_RIGID);
+ set_mode(PhysicsServer3D::BODY_MODE_RIGID);
reload_axis_lock();
areasWhereIam.resize(maxAreasWhereIam);
for (int i = areasWhereIam.size() - 1; 0 <= i; --i) {
- areasWhereIam.write[i] = NULL;
+ areasWhereIam.write[i] = nullptr;
}
btBody->setSleepingThresholds(0.2, 0.2);
@@ -315,7 +315,7 @@ void RigidBodyBullet::init_kinematic_utilities() {
void RigidBodyBullet::destroy_kinematic_utilities() {
if (kinematic_utilities) {
memdelete(kinematic_utilities);
- kinematic_utilities = NULL;
+ kinematic_utilities = nullptr;
}
}
@@ -359,7 +359,7 @@ void RigidBodyBullet::dispatch_callbacks() {
if (omit_forces_integration)
btBody->clearForces();
- BulletPhysicsDirectBodyState *bodyDirect = BulletPhysicsDirectBodyState::get_singleton(this);
+ BulletPhysicsDirectBodyState3D *bodyDirect = BulletPhysicsDirectBodyState3D::get_singleton(this);
Variant variantBodyDirect = bodyDirect;
@@ -392,7 +392,7 @@ void RigidBodyBullet::set_force_integration_callback(ObjectID p_id, const String
if (force_integration_callback) {
memdelete(force_integration_callback);
- force_integration_callback = NULL;
+ force_integration_callback = nullptr;
}
if (p_id.is_valid()) {
@@ -487,29 +487,29 @@ void RigidBodyBullet::set_omit_forces_integration(bool p_omit) {
omit_forces_integration = p_omit;
}
-void RigidBodyBullet::set_param(PhysicsServer::BodyParameter p_param, real_t p_value) {
+void RigidBodyBullet::set_param(PhysicsServer3D::BodyParameter p_param, real_t p_value) {
switch (p_param) {
- case PhysicsServer::BODY_PARAM_BOUNCE:
+ case PhysicsServer3D::BODY_PARAM_BOUNCE:
btBody->setRestitution(p_value);
break;
- case PhysicsServer::BODY_PARAM_FRICTION:
+ case PhysicsServer3D::BODY_PARAM_FRICTION:
btBody->setFriction(p_value);
break;
- case PhysicsServer::BODY_PARAM_MASS: {
+ case PhysicsServer3D::BODY_PARAM_MASS: {
ERR_FAIL_COND(p_value < 0);
mass = p_value;
_internal_set_mass(p_value);
break;
}
- case PhysicsServer::BODY_PARAM_LINEAR_DAMP:
+ case PhysicsServer3D::BODY_PARAM_LINEAR_DAMP:
linearDamp = p_value;
btBody->setDamping(linearDamp, angularDamp);
break;
- case PhysicsServer::BODY_PARAM_ANGULAR_DAMP:
+ case PhysicsServer3D::BODY_PARAM_ANGULAR_DAMP:
angularDamp = p_value;
btBody->setDamping(linearDamp, angularDamp);
break;
- case PhysicsServer::BODY_PARAM_GRAVITY_SCALE:
+ case PhysicsServer3D::BODY_PARAM_GRAVITY_SCALE:
gravity_scale = p_value;
/// The Bullet gravity will be is set by reload_space_override_modificator
scratch_space_override_modificator();
@@ -519,21 +519,21 @@ void RigidBodyBullet::set_param(PhysicsServer::BodyParameter p_param, real_t p_v
}
}
-real_t RigidBodyBullet::get_param(PhysicsServer::BodyParameter p_param) const {
+real_t RigidBodyBullet::get_param(PhysicsServer3D::BodyParameter p_param) const {
switch (p_param) {
- case PhysicsServer::BODY_PARAM_BOUNCE:
+ case PhysicsServer3D::BODY_PARAM_BOUNCE:
return btBody->getRestitution();
- case PhysicsServer::BODY_PARAM_FRICTION:
+ case PhysicsServer3D::BODY_PARAM_FRICTION:
return btBody->getFriction();
- case PhysicsServer::BODY_PARAM_MASS: {
+ case PhysicsServer3D::BODY_PARAM_MASS: {
const btScalar invMass = btBody->getInvMass();
return 0 == invMass ? 0 : 1 / invMass;
}
- case PhysicsServer::BODY_PARAM_LINEAR_DAMP:
+ case PhysicsServer3D::BODY_PARAM_LINEAR_DAMP:
return linearDamp;
- case PhysicsServer::BODY_PARAM_ANGULAR_DAMP:
+ case PhysicsServer3D::BODY_PARAM_ANGULAR_DAMP:
return angularDamp;
- case PhysicsServer::BODY_PARAM_GRAVITY_SCALE:
+ case PhysicsServer3D::BODY_PARAM_GRAVITY_SCALE:
return gravity_scale;
default:
WARN_PRINT("Parameter " + itos(p_param) + " not supported by bullet");
@@ -541,31 +541,31 @@ real_t RigidBodyBullet::get_param(PhysicsServer::BodyParameter p_param) const {
}
}
-void RigidBodyBullet::set_mode(PhysicsServer::BodyMode p_mode) {
+void RigidBodyBullet::set_mode(PhysicsServer3D::BodyMode p_mode) {
// This is necessary to block force_integration untile next move
can_integrate_forces = false;
destroy_kinematic_utilities();
// The mode change is relevant to its mass
switch (p_mode) {
- case PhysicsServer::BODY_MODE_KINEMATIC:
- mode = PhysicsServer::BODY_MODE_KINEMATIC;
+ case PhysicsServer3D::BODY_MODE_KINEMATIC:
+ mode = PhysicsServer3D::BODY_MODE_KINEMATIC;
reload_axis_lock();
_internal_set_mass(0);
init_kinematic_utilities();
break;
- case PhysicsServer::BODY_MODE_STATIC:
- mode = PhysicsServer::BODY_MODE_STATIC;
+ case PhysicsServer3D::BODY_MODE_STATIC:
+ mode = PhysicsServer3D::BODY_MODE_STATIC;
reload_axis_lock();
_internal_set_mass(0);
break;
- case PhysicsServer::BODY_MODE_RIGID:
- mode = PhysicsServer::BODY_MODE_RIGID;
+ case PhysicsServer3D::BODY_MODE_RIGID:
+ mode = PhysicsServer3D::BODY_MODE_RIGID;
reload_axis_lock();
_internal_set_mass(0 == mass ? 1 : mass);
scratch_space_override_modificator();
break;
- case PhysicsServer::BODY_MODE_CHARACTER:
- mode = PhysicsServer::BODY_MODE_CHARACTER;
+ case PhysicsServer3D::BODY_MODE_CHARACTER:
+ mode = PhysicsServer3D::BODY_MODE_CHARACTER;
reload_axis_lock();
_internal_set_mass(0 == mass ? 1 : mass);
scratch_space_override_modificator();
@@ -575,26 +575,26 @@ void RigidBodyBullet::set_mode(PhysicsServer::BodyMode p_mode) {
btBody->setAngularVelocity(btVector3(0, 0, 0));
btBody->setLinearVelocity(btVector3(0, 0, 0));
}
-PhysicsServer::BodyMode RigidBodyBullet::get_mode() const {
+PhysicsServer3D::BodyMode RigidBodyBullet::get_mode() const {
return mode;
}
-void RigidBodyBullet::set_state(PhysicsServer::BodyState p_state, const Variant &p_variant) {
+void RigidBodyBullet::set_state(PhysicsServer3D::BodyState p_state, const Variant &p_variant) {
switch (p_state) {
- case PhysicsServer::BODY_STATE_TRANSFORM:
+ case PhysicsServer3D::BODY_STATE_TRANSFORM:
set_transform(p_variant);
break;
- case PhysicsServer::BODY_STATE_LINEAR_VELOCITY:
+ case PhysicsServer3D::BODY_STATE_LINEAR_VELOCITY:
set_linear_velocity(p_variant);
break;
- case PhysicsServer::BODY_STATE_ANGULAR_VELOCITY:
+ case PhysicsServer3D::BODY_STATE_ANGULAR_VELOCITY:
set_angular_velocity(p_variant);
break;
- case PhysicsServer::BODY_STATE_SLEEPING:
+ case PhysicsServer3D::BODY_STATE_SLEEPING:
set_activation_state(!bool(p_variant));
break;
- case PhysicsServer::BODY_STATE_CAN_SLEEP:
+ case PhysicsServer3D::BODY_STATE_CAN_SLEEP:
can_sleep = bool(p_variant);
if (!can_sleep) {
// Can't sleep
@@ -606,17 +606,17 @@ void RigidBodyBullet::set_state(PhysicsServer::BodyState p_state, const Variant
}
}
-Variant RigidBodyBullet::get_state(PhysicsServer::BodyState p_state) const {
+Variant RigidBodyBullet::get_state(PhysicsServer3D::BodyState p_state) const {
switch (p_state) {
- case PhysicsServer::BODY_STATE_TRANSFORM:
+ case PhysicsServer3D::BODY_STATE_TRANSFORM:
return get_transform();
- case PhysicsServer::BODY_STATE_LINEAR_VELOCITY:
+ case PhysicsServer3D::BODY_STATE_LINEAR_VELOCITY:
return get_linear_velocity();
- case PhysicsServer::BODY_STATE_ANGULAR_VELOCITY:
+ case PhysicsServer3D::BODY_STATE_ANGULAR_VELOCITY:
return get_angular_velocity();
- case PhysicsServer::BODY_STATE_SLEEPING:
+ case PhysicsServer3D::BODY_STATE_SLEEPING:
return !is_active();
- case PhysicsServer::BODY_STATE_CAN_SLEEP:
+ case PhysicsServer3D::BODY_STATE_CAN_SLEEP:
return can_sleep;
default:
WARN_PRINT("This state " + itos(p_state) + " is not supported by Bullet");
@@ -714,7 +714,7 @@ Vector3 RigidBodyBullet::get_applied_torque() const {
return gTotTorq;
}
-void RigidBodyBullet::set_axis_lock(PhysicsServer::BodyAxis p_axis, bool lock) {
+void RigidBodyBullet::set_axis_lock(PhysicsServer3D::BodyAxis p_axis, bool lock) {
if (lock) {
locked_axis |= p_axis;
} else {
@@ -724,18 +724,18 @@ void RigidBodyBullet::set_axis_lock(PhysicsServer::BodyAxis p_axis, bool lock) {
reload_axis_lock();
}
-bool RigidBodyBullet::is_axis_locked(PhysicsServer::BodyAxis p_axis) const {
+bool RigidBodyBullet::is_axis_locked(PhysicsServer3D::BodyAxis p_axis) const {
return locked_axis & p_axis;
}
void RigidBodyBullet::reload_axis_lock() {
- btBody->setLinearFactor(btVector3(float(!is_axis_locked(PhysicsServer::BODY_AXIS_LINEAR_X)), float(!is_axis_locked(PhysicsServer::BODY_AXIS_LINEAR_Y)), float(!is_axis_locked(PhysicsServer::BODY_AXIS_LINEAR_Z))));
- if (PhysicsServer::BODY_MODE_CHARACTER == mode) {
+ btBody->setLinearFactor(btVector3(float(!is_axis_locked(PhysicsServer3D::BODY_AXIS_LINEAR_X)), float(!is_axis_locked(PhysicsServer3D::BODY_AXIS_LINEAR_Y)), float(!is_axis_locked(PhysicsServer3D::BODY_AXIS_LINEAR_Z))));
+ if (PhysicsServer3D::BODY_MODE_CHARACTER == mode) {
/// When character angular is always locked
btBody->setAngularFactor(btVector3(0., 0., 0.));
} else {
- btBody->setAngularFactor(btVector3(float(!is_axis_locked(PhysicsServer::BODY_AXIS_ANGULAR_X)), float(!is_axis_locked(PhysicsServer::BODY_AXIS_ANGULAR_Y)), float(!is_axis_locked(PhysicsServer::BODY_AXIS_ANGULAR_Z))));
+ btBody->setAngularFactor(btVector3(float(!is_axis_locked(PhysicsServer3D::BODY_AXIS_ANGULAR_X)), float(!is_axis_locked(PhysicsServer3D::BODY_AXIS_ANGULAR_Y)), float(!is_axis_locked(PhysicsServer3D::BODY_AXIS_ANGULAR_Z))));
}
}
@@ -794,7 +794,7 @@ Vector3 RigidBodyBullet::get_angular_velocity() const {
}
void RigidBodyBullet::set_transform__bullet(const btTransform &p_global_transform) {
- if (mode == PhysicsServer::BODY_MODE_KINEMATIC) {
+ if (mode == PhysicsServer3D::BODY_MODE_KINEMATIC) {
if (space && space->get_delta_time() != 0)
btBody->setLinearVelocity((p_global_transform.getOrigin() - btBody->getWorldTransform().getOrigin()) / space->get_delta_time());
// The kinematic use MotionState class
@@ -847,7 +847,7 @@ void RigidBodyBullet::on_enter_area(AreaBullet *p_area) {
}
for (int i = 0; i < areaWhereIamCount; ++i) {
- if (NULL == areasWhereIam[i]) {
+ if (nullptr == areasWhereIam[i]) {
// This area has the highest priority
areasWhereIam.write[i] = p_area;
break;
@@ -862,7 +862,7 @@ void RigidBodyBullet::on_enter_area(AreaBullet *p_area) {
}
}
}
- if (PhysicsServer::AREA_SPACE_OVERRIDE_DISABLED != p_area->get_spOv_mode()) {
+ if (PhysicsServer3D::AREA_SPACE_OVERRIDE_DISABLED != p_area->get_spOv_mode()) {
scratch_space_override_modificator();
}
@@ -894,8 +894,8 @@ void RigidBodyBullet::on_exit_area(AreaBullet *p_area) {
}
--areaWhereIamCount;
- areasWhereIam.write[areaWhereIamCount] = NULL; // Even if this is not required, I clear the last element to be safe
- if (PhysicsServer::AREA_SPACE_OVERRIDE_DISABLED != p_area->get_spOv_mode()) {
+ areasWhereIam.write[areaWhereIamCount] = nullptr; // Even if this is not required, I clear the last element to be safe
+ if (PhysicsServer3D::AREA_SPACE_OVERRIDE_DISABLED != p_area->get_spOv_mode()) {
scratch_space_override_modificator();
}
}
@@ -904,7 +904,7 @@ void RigidBodyBullet::on_exit_area(AreaBullet *p_area) {
void RigidBodyBullet::reload_space_override_modificator() {
// Make sure that kinematic bodies have their total gravity calculated
- if (!is_active() && PhysicsServer::BODY_MODE_KINEMATIC != mode)
+ if (!is_active() && PhysicsServer3D::BODY_MODE_KINEMATIC != mode)
return;
Vector3 newGravity(space->get_gravity_direction() * space->get_gravity_magnitude());
@@ -920,7 +920,7 @@ void RigidBodyBullet::reload_space_override_modificator() {
currentArea = areasWhereIam[i];
- if (!currentArea || PhysicsServer::AREA_SPACE_OVERRIDE_DISABLED == currentArea->get_spOv_mode()) {
+ if (!currentArea || PhysicsServer3D::AREA_SPACE_OVERRIDE_DISABLED == currentArea->get_spOv_mode()) {
continue;
}
@@ -954,11 +954,11 @@ void RigidBodyBullet::reload_space_override_modificator() {
}
switch (currentArea->get_spOv_mode()) {
- case PhysicsServer::AREA_SPACE_OVERRIDE_DISABLED:
+ case PhysicsServer3D::AREA_SPACE_OVERRIDE_DISABLED:
/// This area does not affect gravity/damp. These are generally areas
/// that exist only to detect collisions, and objects entering or exiting them.
break;
- case PhysicsServer::AREA_SPACE_OVERRIDE_COMBINE:
+ case PhysicsServer3D::AREA_SPACE_OVERRIDE_COMBINE:
/// This area adds its gravity/damp values to whatever has been
/// calculated so far. This way, many overlapping areas can combine
/// their physics to make interesting
@@ -967,7 +967,7 @@ void RigidBodyBullet::reload_space_override_modificator() {
newAngularDamp += currentArea->get_spOv_angularDamp();
++countCombined;
break;
- case PhysicsServer::AREA_SPACE_OVERRIDE_COMBINE_REPLACE:
+ case PhysicsServer3D::AREA_SPACE_OVERRIDE_COMBINE_REPLACE:
/// This area adds its gravity/damp values to whatever has been calculated
/// so far. Then stops taking into account the rest of the areas, even the
/// default one.
@@ -976,7 +976,7 @@ void RigidBodyBullet::reload_space_override_modificator() {
newAngularDamp += currentArea->get_spOv_angularDamp();
++countCombined;
goto endAreasCycle;
- case PhysicsServer::AREA_SPACE_OVERRIDE_REPLACE:
+ case PhysicsServer3D::AREA_SPACE_OVERRIDE_REPLACE:
/// This area replaces any gravity/damp, even the default one, and
/// stops taking into account the rest of the areas.
newGravity = support_gravity;
@@ -984,7 +984,7 @@ void RigidBodyBullet::reload_space_override_modificator() {
newAngularDamp = currentArea->get_spOv_angularDamp();
countCombined = 1;
goto endAreasCycle;
- case PhysicsServer::AREA_SPACE_OVERRIDE_REPLACE_COMBINE:
+ case PhysicsServer3D::AREA_SPACE_OVERRIDE_REPLACE_COMBINE:
/// This area replaces any gravity/damp calculated so far, but keeps
/// calculating the rest of the areas, down to the default one.
newGravity = support_gravity;
@@ -1032,14 +1032,14 @@ void RigidBodyBullet::_internal_set_mass(real_t p_mass) {
const bool isDynamic = p_mass != 0.f;
if (isDynamic) {
- if (PhysicsServer::BODY_MODE_RIGID != mode && PhysicsServer::BODY_MODE_CHARACTER != mode)
+ if (PhysicsServer3D::BODY_MODE_RIGID != mode && PhysicsServer3D::BODY_MODE_CHARACTER != mode)
return;
m_isStatic = false;
if (mainShape)
mainShape->calculateLocalInertia(p_mass, localInertia);
- if (PhysicsServer::BODY_MODE_RIGID == mode) {
+ if (PhysicsServer3D::BODY_MODE_RIGID == mode) {
btBody->setCollisionFlags(clearedCurrentFlags); // Just set the flags without Kin and Static
} else {
@@ -1054,11 +1054,11 @@ void RigidBodyBullet::_internal_set_mass(real_t p_mass) {
}
} else {
- if (PhysicsServer::BODY_MODE_STATIC != mode && PhysicsServer::BODY_MODE_KINEMATIC != mode)
+ if (PhysicsServer3D::BODY_MODE_STATIC != mode && PhysicsServer3D::BODY_MODE_KINEMATIC != mode)
return;
m_isStatic = true;
- if (PhysicsServer::BODY_MODE_STATIC == mode) {
+ if (PhysicsServer3D::BODY_MODE_STATIC == mode) {
btBody->setCollisionFlags(clearedCurrentFlags | btCollisionObject::CF_STATIC_OBJECT);
} else {
diff --git a/modules/bullet/rigid_body_bullet.h b/modules/bullet/rigid_body_bullet.h
index ca599f7a77..420b5cc443 100644
--- a/modules/bullet/rigid_body_bullet.h
+++ b/modules/bullet/rigid_body_bullet.h
@@ -45,37 +45,37 @@ class AreaBullet;
class SpaceBullet;
class btRigidBody;
class GodotMotionState;
-class BulletPhysicsDirectBodyState;
+class BulletPhysicsDirectBodyState3D;
/// This class could be used in multi thread with few changes but currently
/// is set to be only in one single thread.
///
/// In the system there is only one object at a time that manage all bodies and is
-/// created by BulletPhysicsServer and is held by the "singleton" variable of this class
+/// created by BulletPhysicsServer3D and is held by the "singleton" variable of this class
/// Each time something require it, the body must be set again.
-class BulletPhysicsDirectBodyState : public PhysicsDirectBodyState {
- GDCLASS(BulletPhysicsDirectBodyState, PhysicsDirectBodyState);
+class BulletPhysicsDirectBodyState3D : public PhysicsDirectBodyState3D {
+ GDCLASS(BulletPhysicsDirectBodyState3D, PhysicsDirectBodyState3D);
- static BulletPhysicsDirectBodyState *singleton;
+ static BulletPhysicsDirectBodyState3D *singleton;
public:
/// This class avoid the creation of more object of this class
static void initSingleton() {
if (!singleton) {
- singleton = memnew(BulletPhysicsDirectBodyState);
+ singleton = memnew(BulletPhysicsDirectBodyState3D);
}
}
static void destroySingleton() {
memdelete(singleton);
- singleton = NULL;
+ singleton = nullptr;
}
static void singleton_setDeltaTime(real_t p_deltaTime) {
singleton->deltaTime = p_deltaTime;
}
- static BulletPhysicsDirectBodyState *get_singleton(RigidBodyBullet *p_body) {
+ static BulletPhysicsDirectBodyState3D *get_singleton(RigidBodyBullet *p_body) {
singleton->body = p_body;
return singleton;
}
@@ -85,7 +85,7 @@ public:
real_t deltaTime;
private:
- BulletPhysicsDirectBodyState() {}
+ BulletPhysicsDirectBodyState3D() {}
public:
virtual Vector3 get_total_gravity() const;
@@ -117,7 +117,7 @@ public:
virtual void apply_impulse(const Vector3 &p_pos, const Vector3 &p_impulse);
virtual void apply_torque_impulse(const Vector3 &p_impulse);
- virtual void set_sleep_state(bool p_enable);
+ virtual void set_sleep_state(bool p_sleep);
virtual bool is_sleeping() const;
virtual int get_contact_count() const;
@@ -138,7 +138,7 @@ public:
// Skip the execution of this function
}
- virtual PhysicsDirectSpaceState *get_space_state();
+ virtual PhysicsDirectSpaceState3D *get_space_state();
};
class RigidBodyBullet : public RigidCollisionObjectBullet {
@@ -166,7 +166,7 @@ public:
btTransform transform;
KinematicShape() :
- shape(NULL) {}
+ shape(nullptr) {}
bool is_active() const { return shape; }
};
@@ -187,12 +187,12 @@ public:
};
private:
- friend class BulletPhysicsDirectBodyState;
+ friend class BulletPhysicsDirectBodyState3D;
// This is required only for Kinematic movement
KinematicUtilities *kinematic_utilities;
- PhysicsServer::BodyMode mode;
+ PhysicsServer3D::BodyMode mode;
GodotMotionState *godotMotionState;
btRigidBody *btBody;
uint16_t locked_axis;
@@ -278,14 +278,14 @@ public:
void set_omit_forces_integration(bool p_omit);
_FORCE_INLINE_ bool get_omit_forces_integration() const { return omit_forces_integration; }
- void set_param(PhysicsServer::BodyParameter p_param, real_t);
- real_t get_param(PhysicsServer::BodyParameter p_param) const;
+ void set_param(PhysicsServer3D::BodyParameter p_param, real_t);
+ real_t get_param(PhysicsServer3D::BodyParameter p_param) const;
- void set_mode(PhysicsServer::BodyMode p_mode);
- PhysicsServer::BodyMode get_mode() const;
+ void set_mode(PhysicsServer3D::BodyMode p_mode);
+ PhysicsServer3D::BodyMode get_mode() const;
- void set_state(PhysicsServer::BodyState p_state, const Variant &p_variant);
- Variant get_state(PhysicsServer::BodyState p_state) const;
+ void set_state(PhysicsServer3D::BodyState p_state, const Variant &p_variant);
+ Variant get_state(PhysicsServer3D::BodyState p_state) const;
void apply_impulse(const Vector3 &p_pos, const Vector3 &p_impulse);
void apply_central_impulse(const Vector3 &p_impulse);
@@ -300,8 +300,8 @@ public:
void set_applied_torque(const Vector3 &p_torque);
Vector3 get_applied_torque() const;
- void set_axis_lock(PhysicsServer::BodyAxis p_axis, bool lock);
- bool is_axis_locked(PhysicsServer::BodyAxis p_axis) const;
+ void set_axis_lock(PhysicsServer3D::BodyAxis p_axis, bool lock);
+ bool is_axis_locked(PhysicsServer3D::BodyAxis p_axis) const;
void reload_axis_lock();
/// Doc:
diff --git a/modules/bullet/shape_bullet.cpp b/modules/bullet/shape_bullet.cpp
index 6780f89d9e..8ac26a0fdb 100644
--- a/modules/bullet/shape_bullet.cpp
+++ b/modules/bullet/shape_bullet.cpp
@@ -138,7 +138,7 @@ btScaledBvhTriangleMeshShape *ShapeBullet::create_shape_concave(btBvhTriangleMes
if (p_mesh_shape) {
return bulletnew(btScaledBvhTriangleMeshShape(p_mesh_shape, p_local_scaling));
} else {
- return NULL;
+ return nullptr;
}
}
@@ -150,7 +150,7 @@ btHeightfieldTerrainShape *ShapeBullet::create_shape_height_field(Vector<real_t>
btHeightfieldTerrainShape *heightfield = bulletnew(btHeightfieldTerrainShape(p_width, p_depth, heightsPtr, ignoredHeightScale, p_min_height, p_max_height, YAxis, PHY_FLOAT, flipQuadEdges));
- // The shape can be created without params when you do PhysicsServer.shape_create(PhysicsServer.SHAPE_HEIGHTMAP)
+ // The shape can be created without params when you do PhysicsServer3D.shape_create(PhysicsServer3D.SHAPE_HEIGHTMAP)
if (heightsPtr)
heightfield->buildAccelerator(16);
@@ -176,8 +176,8 @@ Variant PlaneShapeBullet::get_data() const {
return plane;
}
-PhysicsServer::ShapeType PlaneShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_PLANE;
+PhysicsServer3D::ShapeType PlaneShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_PLANE;
}
void PlaneShapeBullet::setup(const Plane &p_plane) {
@@ -204,8 +204,8 @@ Variant SphereShapeBullet::get_data() const {
return radius;
}
-PhysicsServer::ShapeType SphereShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_SPHERE;
+PhysicsServer3D::ShapeType SphereShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_SPHERE;
}
void SphereShapeBullet::setup(real_t p_radius) {
@@ -231,8 +231,8 @@ Variant BoxShapeBullet::get_data() const {
return g_half_extents;
}
-PhysicsServer::ShapeType BoxShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_BOX;
+PhysicsServer3D::ShapeType BoxShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_BOX;
}
void BoxShapeBullet::setup(const Vector3 &p_half_extents) {
@@ -263,8 +263,8 @@ Variant CapsuleShapeBullet::get_data() const {
return d;
}
-PhysicsServer::ShapeType CapsuleShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_CAPSULE;
+PhysicsServer3D::ShapeType CapsuleShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_CAPSULE;
}
void CapsuleShapeBullet::setup(real_t p_height, real_t p_radius) {
@@ -296,8 +296,8 @@ Variant CylinderShapeBullet::get_data() const {
return d;
}
-PhysicsServer::ShapeType CylinderShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_CYLINDER;
+PhysicsServer3D::ShapeType CylinderShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_CYLINDER;
}
void CylinderShapeBullet::setup(real_t p_height, real_t p_radius) {
@@ -334,8 +334,8 @@ Variant ConvexPolygonShapeBullet::get_data() const {
return out_vertices;
}
-PhysicsServer::ShapeType ConvexPolygonShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_CONVEX_POLYGON;
+PhysicsServer3D::ShapeType ConvexPolygonShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_CONVEX_POLYGON;
}
void ConvexPolygonShapeBullet::setup(const Vector<Vector3> &p_vertices) {
@@ -362,7 +362,7 @@ btCollisionShape *ConvexPolygonShapeBullet::create_bt_shape(const btVector3 &p_i
ConcavePolygonShapeBullet::ConcavePolygonShapeBullet() :
ShapeBullet(),
- meshShape(NULL) {}
+ meshShape(nullptr) {}
ConcavePolygonShapeBullet::~ConcavePolygonShapeBullet() {
if (meshShape) {
@@ -381,8 +381,8 @@ Variant ConcavePolygonShapeBullet::get_data() const {
return faces;
}
-PhysicsServer::ShapeType ConcavePolygonShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_CONCAVE_POLYGON;
+PhysicsServer3D::ShapeType ConcavePolygonShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_CONCAVE_POLYGON;
}
void ConcavePolygonShapeBullet::setup(Vector<Vector3> p_faces) {
@@ -425,7 +425,7 @@ void ConcavePolygonShapeBullet::setup(Vector<Vector3> p_faces) {
btGenerateInternalEdgeInfo(meshShape, triangleInfoMap);
}
} else {
- meshShape = NULL;
+ meshShape = nullptr;
ERR_PRINT("The faces count are 0, the mesh shape cannot be created");
}
notifyShapeChanged();
@@ -434,7 +434,7 @@ void ConcavePolygonShapeBullet::setup(Vector<Vector3> p_faces) {
btCollisionShape *ConcavePolygonShapeBullet::create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge) {
btCollisionShape *cs = ShapeBullet::create_shape_concave(meshShape);
if (!cs)
- // This is necessary since if 0 faces the creation of concave return NULL
+ // This is necessary since if 0 faces the creation of concave return null
cs = ShapeBullet::create_shape_empty();
cs->setLocalScaling(p_implicit_scale);
prepare(cs);
@@ -536,8 +536,8 @@ Variant HeightMapShapeBullet::get_data() const {
ERR_FAIL_V(Variant());
}
-PhysicsServer::ShapeType HeightMapShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_HEIGHTMAP;
+PhysicsServer3D::ShapeType HeightMapShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_HEIGHTMAP;
}
void HeightMapShapeBullet::setup(Vector<real_t> &p_heights, int p_width, int p_depth, real_t p_min_height, real_t p_max_height) {
@@ -580,8 +580,8 @@ Variant RayShapeBullet::get_data() const {
return d;
}
-PhysicsServer::ShapeType RayShapeBullet::get_type() const {
- return PhysicsServer::SHAPE_RAY;
+PhysicsServer3D::ShapeType RayShapeBullet::get_type() const {
+ return PhysicsServer3D::SHAPE_RAY;
}
void RayShapeBullet::setup(real_t p_length, bool p_slips_on_slope) {
diff --git a/modules/bullet/shape_bullet.h b/modules/bullet/shape_bullet.h
index c8b5ca102a..0dbc616fe5 100644
--- a/modules/bullet/shape_bullet.h
+++ b/modules/bullet/shape_bullet.h
@@ -34,7 +34,7 @@
#include "core/math/geometry.h"
#include "core/variant.h"
#include "rid_bullet.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#include <LinearMath/btAlignedObjectArray.h>
#include <LinearMath/btScalar.h>
@@ -78,7 +78,7 @@ public:
virtual void set_data(const Variant &p_data) = 0;
virtual Variant get_data() const = 0;
- virtual PhysicsServer::ShapeType get_type() const = 0;
+ virtual PhysicsServer3D::ShapeType get_type() const = 0;
public:
static class btEmptyShape *create_shape_empty();
@@ -103,7 +103,7 @@ public:
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -120,7 +120,7 @@ public:
_FORCE_INLINE_ real_t get_radius() { return radius; }
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -137,7 +137,7 @@ public:
_FORCE_INLINE_ const btVector3 &get_half_extents() { return half_extents; }
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -156,7 +156,7 @@ public:
_FORCE_INLINE_ real_t get_radius() { return radius; }
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -175,7 +175,7 @@ public:
_FORCE_INLINE_ real_t get_radius() { return radius; }
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_margin = 0);
private:
@@ -192,7 +192,7 @@ public:
virtual void set_data(const Variant &p_data);
void get_vertices(Vector<Vector3> &out_vertices);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -210,7 +210,7 @@ public:
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -230,7 +230,7 @@ public:
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
@@ -247,7 +247,7 @@ public:
virtual void set_data(const Variant &p_data);
virtual Variant get_data() const;
- virtual PhysicsServer::ShapeType get_type() const;
+ virtual PhysicsServer3D::ShapeType get_type() const;
virtual btCollisionShape *create_bt_shape(const btVector3 &p_implicit_scale, real_t p_extra_edge = 0);
private:
diff --git a/modules/bullet/slider_joint_bullet.cpp b/modules/bullet/slider_joint_bullet.cpp
index d9ebb9d580..f193daef39 100644
--- a/modules/bullet/slider_joint_bullet.cpp
+++ b/modules/bullet/slider_joint_bullet.cpp
@@ -342,58 +342,58 @@ real_t SliderJointBullet::getLinearPos() {
;
}
-void SliderJointBullet::set_param(PhysicsServer::SliderJointParam p_param, real_t p_value) {
+void SliderJointBullet::set_param(PhysicsServer3D::SliderJointParam p_param, real_t p_value) {
switch (p_param) {
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_UPPER: setUpperLinLimit(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_LOWER: setLowerLinLimit(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_SOFTNESS: setSoftnessLimLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_RESTITUTION: setRestitutionLimLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_DAMPING: setDampingLimLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_MOTION_SOFTNESS: setSoftnessDirLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_MOTION_RESTITUTION: setRestitutionDirLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_MOTION_DAMPING: setDampingDirLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_ORTHOGONAL_SOFTNESS: setSoftnessOrthoLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_ORTHOGONAL_RESTITUTION: setRestitutionOrthoLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_LINEAR_ORTHOGONAL_DAMPING: setDampingOrthoLin(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_UPPER: setUpperAngLimit(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_LOWER: setLowerAngLimit(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_SOFTNESS: setSoftnessLimAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_RESTITUTION: setRestitutionLimAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_DAMPING: setDampingLimAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_MOTION_SOFTNESS: setSoftnessDirAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_MOTION_RESTITUTION: setRestitutionDirAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_MOTION_DAMPING: setDampingDirAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_ORTHOGONAL_SOFTNESS: setSoftnessOrthoAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_ORTHOGONAL_RESTITUTION: setRestitutionOrthoAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_ANGULAR_ORTHOGONAL_DAMPING: setDampingOrthoAng(p_value); break;
- case PhysicsServer::SLIDER_JOINT_MAX: break; // Can't happen, but silences warning
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_UPPER: setUpperLinLimit(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_LOWER: setLowerLinLimit(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_SOFTNESS: setSoftnessLimLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_RESTITUTION: setRestitutionLimLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_DAMPING: setDampingLimLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_MOTION_SOFTNESS: setSoftnessDirLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_MOTION_RESTITUTION: setRestitutionDirLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_MOTION_DAMPING: setDampingDirLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_ORTHOGONAL_SOFTNESS: setSoftnessOrthoLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_ORTHOGONAL_RESTITUTION: setRestitutionOrthoLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_ORTHOGONAL_DAMPING: setDampingOrthoLin(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_UPPER: setUpperAngLimit(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_LOWER: setLowerAngLimit(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_SOFTNESS: setSoftnessLimAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_RESTITUTION: setRestitutionLimAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_DAMPING: setDampingLimAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_MOTION_SOFTNESS: setSoftnessDirAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_MOTION_RESTITUTION: setRestitutionDirAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_MOTION_DAMPING: setDampingDirAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_ORTHOGONAL_SOFTNESS: setSoftnessOrthoAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_ORTHOGONAL_RESTITUTION: setRestitutionOrthoAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_ORTHOGONAL_DAMPING: setDampingOrthoAng(p_value); break;
+ case PhysicsServer3D::SLIDER_JOINT_MAX: break; // Can't happen, but silences warning
}
}
-real_t SliderJointBullet::get_param(PhysicsServer::SliderJointParam p_param) const {
+real_t SliderJointBullet::get_param(PhysicsServer3D::SliderJointParam p_param) const {
switch (p_param) {
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_UPPER: return getUpperLinLimit();
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_LOWER: return getLowerLinLimit();
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_SOFTNESS: return getSoftnessLimLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_RESTITUTION: return getRestitutionLimLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_LIMIT_DAMPING: return getDampingLimLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_MOTION_SOFTNESS: return getSoftnessDirLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_MOTION_RESTITUTION: return getRestitutionDirLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_MOTION_DAMPING: return getDampingDirLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_ORTHOGONAL_SOFTNESS: return getSoftnessOrthoLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_ORTHOGONAL_RESTITUTION: return getRestitutionOrthoLin();
- case PhysicsServer::SLIDER_JOINT_LINEAR_ORTHOGONAL_DAMPING: return getDampingOrthoLin();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_UPPER: return getUpperAngLimit();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_LOWER: return getLowerAngLimit();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_SOFTNESS: return getSoftnessLimAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_RESTITUTION: return getRestitutionLimAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_LIMIT_DAMPING: return getDampingLimAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_MOTION_SOFTNESS: return getSoftnessDirAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_MOTION_RESTITUTION: return getRestitutionDirAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_MOTION_DAMPING: return getDampingDirAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_ORTHOGONAL_SOFTNESS: return getSoftnessOrthoAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_ORTHOGONAL_RESTITUTION: return getRestitutionOrthoAng();
- case PhysicsServer::SLIDER_JOINT_ANGULAR_ORTHOGONAL_DAMPING: return getDampingOrthoAng();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_UPPER: return getUpperLinLimit();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_LOWER: return getLowerLinLimit();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_SOFTNESS: return getSoftnessLimLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_RESTITUTION: return getRestitutionLimLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_LIMIT_DAMPING: return getDampingLimLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_MOTION_SOFTNESS: return getSoftnessDirLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_MOTION_RESTITUTION: return getRestitutionDirLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_MOTION_DAMPING: return getDampingDirLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_ORTHOGONAL_SOFTNESS: return getSoftnessOrthoLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_ORTHOGONAL_RESTITUTION: return getRestitutionOrthoLin();
+ case PhysicsServer3D::SLIDER_JOINT_LINEAR_ORTHOGONAL_DAMPING: return getDampingOrthoLin();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_UPPER: return getUpperAngLimit();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_LOWER: return getLowerAngLimit();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_SOFTNESS: return getSoftnessLimAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_RESTITUTION: return getRestitutionLimAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_LIMIT_DAMPING: return getDampingLimAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_MOTION_SOFTNESS: return getSoftnessDirAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_MOTION_RESTITUTION: return getRestitutionDirAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_MOTION_DAMPING: return getDampingDirAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_ORTHOGONAL_SOFTNESS: return getSoftnessOrthoAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_ORTHOGONAL_RESTITUTION: return getRestitutionOrthoAng();
+ case PhysicsServer3D::SLIDER_JOINT_ANGULAR_ORTHOGONAL_DAMPING: return getDampingOrthoAng();
default:
return 0;
}
diff --git a/modules/bullet/slider_joint_bullet.h b/modules/bullet/slider_joint_bullet.h
index d98a1b8c95..6410b952ed 100644
--- a/modules/bullet/slider_joint_bullet.h
+++ b/modules/bullet/slider_joint_bullet.h
@@ -46,7 +46,7 @@ public:
/// Reference frame is A
SliderJointBullet(RigidBodyBullet *rbA, RigidBodyBullet *rbB, const Transform &frameInA, const Transform &frameInB);
- virtual PhysicsServer::JointType get_type() const { return PhysicsServer::JOINT_SLIDER; }
+ virtual PhysicsServer3D::JointType get_type() const { return PhysicsServer3D::JOINT_SLIDER; }
const RigidBodyBullet *getRigidBodyA() const;
const RigidBodyBullet *getRigidBodyB() const;
@@ -115,7 +115,7 @@ public:
real_t getMaxAngMotorForce();
real_t getLinearPos();
- void set_param(PhysicsServer::SliderJointParam p_param, real_t p_value);
- real_t get_param(PhysicsServer::SliderJointParam p_param) const;
+ void set_param(PhysicsServer3D::SliderJointParam p_param, real_t p_value);
+ real_t get_param(PhysicsServer3D::SliderJointParam p_param) const;
};
#endif
diff --git a/modules/bullet/soft_body_bullet.cpp b/modules/bullet/soft_body_bullet.cpp
index f21206dd0d..236bdc7c8a 100644
--- a/modules/bullet/soft_body_bullet.cpp
+++ b/modules/bullet/soft_body_bullet.cpp
@@ -32,12 +32,12 @@
#include "bullet_types_converter.h"
#include "bullet_utilities.h"
-#include "scene/3d/soft_body.h"
+#include "scene/3d/soft_body_3d.h"
#include "space_bullet.h"
SoftBodyBullet::SoftBodyBullet() :
CollisionObjectBullet(CollisionObjectBullet::TYPE_SOFT_BODY),
- bt_soft_body(NULL),
+ bt_soft_body(nullptr),
isScratched(false),
simulation_precision(5),
total_mass(1.),
@@ -76,7 +76,7 @@ void SoftBodyBullet::on_enter_area(AreaBullet *p_area) {}
void SoftBodyBullet::on_exit_area(AreaBullet *p_area) {}
-void SoftBodyBullet::update_visual_server(SoftBodyVisualServerHandler *p_visual_server_handler) {
+void SoftBodyBullet::update_rendering_server(SoftBodyRenderingServerHandler *p_rendering_server_handler) {
if (!bt_soft_body)
return;
@@ -96,8 +96,8 @@ void SoftBodyBullet::update_visual_server(SoftBodyVisualServerHandler *p_visual_
const int vs_indices_size(vs_indices->size());
for (int x = 0; x < vs_indices_size; ++x) {
- p_visual_server_handler->set_vertex((*vs_indices)[x], vertex_position);
- p_visual_server_handler->set_normal((*vs_indices)[x], vertex_normal);
+ p_rendering_server_handler->set_vertex((*vs_indices)[x], vertex_position);
+ p_rendering_server_handler->set_normal((*vs_indices)[x], vertex_normal);
}
}
@@ -112,7 +112,7 @@ void SoftBodyBullet::update_visual_server(SoftBodyVisualServerHandler *p_visual_
B_TO_G(aabb_min, aabb.position);
B_TO_G(size, aabb.size);
- p_visual_server_handler->set_aabb(aabb);
+ p_rendering_server_handler->set_aabb(aabb);
}
void SoftBodyBullet::set_soft_mesh(const Ref<Mesh> &p_mesh) {
@@ -129,8 +129,8 @@ void SoftBodyBullet::set_soft_mesh(const Ref<Mesh> &p_mesh) {
}
Array arrays = soft_mesh->surface_get_arrays(0);
- ERR_FAIL_COND(!(soft_mesh->surface_get_format(0) & VS::ARRAY_FORMAT_INDEX));
- set_trimesh_body_shape(arrays[VS::ARRAY_INDEX], arrays[VS::ARRAY_VERTEX]);
+ ERR_FAIL_COND(!(soft_mesh->surface_get_format(0) & RS::ARRAY_FORMAT_INDEX));
+ set_trimesh_body_shape(arrays[RS::ARRAY_INDEX], arrays[RS::ARRAY_VERTEX]);
}
void SoftBodyBullet::destroy_soft_body() {
@@ -144,7 +144,7 @@ void SoftBodyBullet::destroy_soft_body() {
}
destroyBulletCollisionObject();
- bt_soft_body = NULL;
+ bt_soft_body = nullptr;
}
void SoftBodyBullet::set_soft_transform(const Transform &p_transform) {
@@ -184,7 +184,7 @@ void SoftBodyBullet::get_node_offset(int p_node_index, Vector3 &r_offset) const
return;
Array arrays = soft_mesh->surface_get_arrays(0);
- Vector<Vector3> vertices(arrays[VS::ARRAY_VERTEX]);
+ Vector<Vector3> vertices(arrays[RS::ARRAY_VERTEX]);
if (0 <= p_node_index && vertices.size() > p_node_index) {
r_offset = vertices[p_node_index];
@@ -230,7 +230,7 @@ void SoftBodyBullet::reset_all_node_positions() {
return;
Array arrays = soft_mesh->surface_get_arrays(0);
- Vector<Vector3> vs_vertices(arrays[VS::ARRAY_VERTEX]);
+ Vector<Vector3> vs_vertices(arrays[RS::ARRAY_VERTEX]);
const Vector3 *vs_vertices_read = vs_vertices.ptr();
for (int vertex_index = bt_soft_body->m_nodes.size() - 1; 0 <= vertex_index; --vertex_index) {
@@ -404,7 +404,7 @@ void SoftBodyBullet::setup_soft_body() {
// Soft body setup
setupBulletCollisionObject(bt_soft_body);
- bt_soft_body->m_worldInfo = NULL; // Remove fake world info
+ bt_soft_body->m_worldInfo = nullptr; // Remove fake world info
bt_soft_body->getCollisionShape()->setMargin(0.01);
bt_soft_body->setCollisionFlags(bt_soft_body->getCollisionFlags() & (~(btCollisionObject::CF_KINEMATIC_OBJECT | btCollisionObject::CF_STATIC_OBJECT)));
diff --git a/modules/bullet/soft_body_bullet.h b/modules/bullet/soft_body_bullet.h
index 05d7e6ce3f..3c6871e0d6 100644
--- a/modules/bullet/soft_body_bullet.h
+++ b/modules/bullet/soft_body_bullet.h
@@ -43,7 +43,7 @@
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "collision_object_bullet.h"
#include "scene/resources/mesh.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#ifdef x11_None
/// This is required to re add the macro None defined by x11 compiler
@@ -100,7 +100,7 @@ public:
_FORCE_INLINE_ btSoftBody *get_bt_soft_body() const { return bt_soft_body; }
- void update_visual_server(class SoftBodyVisualServerHandler *p_visual_server_handler);
+ void update_rendering_server(class SoftBodyRenderingServerHandler *p_rendering_server_handler);
void set_soft_mesh(const Ref<Mesh> &p_mesh);
void destroy_soft_body();
diff --git a/modules/bullet/space_bullet.cpp b/modules/bullet/space_bullet.cpp
index f6df97f11d..1659664ff9 100644
--- a/modules/bullet/space_bullet.cpp
+++ b/modules/bullet/space_bullet.cpp
@@ -39,7 +39,7 @@
#include "godot_collision_configuration.h"
#include "godot_collision_dispatcher.h"
#include "rigid_body_bullet.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#include "soft_body_bullet.h"
#include <BulletCollision/BroadphaseCollision/btBroadphaseProxy.h>
@@ -59,7 +59,7 @@
*/
BulletPhysicsDirectSpaceState::BulletPhysicsDirectSpaceState(SpaceBullet *p_space) :
- PhysicsDirectSpaceState(),
+ PhysicsDirectSpaceState3D(),
space(p_space) {}
int BulletPhysicsDirectSpaceState::intersect_point(const Vector3 &p_point, ShapeResult *r_results, int p_result_max, const Set<RID> &p_exclude, uint32_t p_collision_mask, bool p_collide_with_bodies, bool p_collide_with_areas) {
@@ -108,7 +108,7 @@ bool BulletPhysicsDirectSpaceState::intersect_ray(const Vector3 &p_from, const V
r_result.shape = btResult.m_shapeId;
r_result.rid = gObj->get_self();
r_result.collider_id = gObj->get_instance_id();
- r_result.collider = r_result.collider_id.is_null() ? NULL : ObjectDB::get_instance(r_result.collider_id);
+ r_result.collider = r_result.collider_id.is_null() ? nullptr : ObjectDB::get_instance(r_result.collider_id);
} else {
WARN_PRINT("The raycast performed has hit a collision object that is not part of Godot scene, please check it.");
}
@@ -309,7 +309,7 @@ Vector3 BulletPhysicsDirectSpaceState::get_closest_point_to_object_volume(RID p_
btPointCollector result;
btGjkPairDetector gjk_pair_detector(&point_shape, convex_shape, space->gjk_simplex_solver, space->gjk_epa_pen_solver);
- gjk_pair_detector.getClosestPoints(input, result, 0);
+ gjk_pair_detector.getClosestPoints(input, result, nullptr);
if (out_distance > result.m_distance) {
out_distance = result.m_distance;
@@ -332,14 +332,14 @@ Vector3 BulletPhysicsDirectSpaceState::get_closest_point_to_object_volume(RID p_
}
SpaceBullet::SpaceBullet() :
- broadphase(NULL),
- collisionConfiguration(NULL),
- dispatcher(NULL),
- solver(NULL),
- dynamicsWorld(NULL),
- soft_body_world_info(NULL),
- ghostPairCallback(NULL),
- godotFilterCallback(NULL),
+ broadphase(nullptr),
+ collisionConfiguration(nullptr),
+ dispatcher(nullptr),
+ solver(nullptr),
+ dynamicsWorld(nullptr),
+ soft_body_world_info(nullptr),
+ ghostPairCallback(nullptr),
+ godotFilterCallback(nullptr),
gravityDirection(0, -1, 0),
gravityMagnitude(10),
contactDebugCount(0),
@@ -366,27 +366,27 @@ void SpaceBullet::step(real_t p_delta_time) {
dynamicsWorld->stepSimulation(p_delta_time, 0, 0);
}
-void SpaceBullet::set_param(PhysicsServer::AreaParameter p_param, const Variant &p_value) {
+void SpaceBullet::set_param(PhysicsServer3D::AreaParameter p_param, const Variant &p_value) {
assert(dynamicsWorld);
switch (p_param) {
- case PhysicsServer::AREA_PARAM_GRAVITY:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY:
gravityMagnitude = p_value;
update_gravity();
break;
- case PhysicsServer::AREA_PARAM_GRAVITY_VECTOR:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_VECTOR:
gravityDirection = p_value;
update_gravity();
break;
- case PhysicsServer::AREA_PARAM_LINEAR_DAMP:
- case PhysicsServer::AREA_PARAM_ANGULAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_LINEAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_ANGULAR_DAMP:
break; // No damp
- case PhysicsServer::AREA_PARAM_PRIORITY:
+ case PhysicsServer3D::AREA_PARAM_PRIORITY:
// Priority is always 0, the lower
break;
- case PhysicsServer::AREA_PARAM_GRAVITY_IS_POINT:
- case PhysicsServer::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
- case PhysicsServer::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_IS_POINT:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
break;
default:
WARN_PRINT("This set parameter (" + itos(p_param) + ") is ignored, the SpaceBullet doesn't support it.");
@@ -394,22 +394,22 @@ void SpaceBullet::set_param(PhysicsServer::AreaParameter p_param, const Variant
}
}
-Variant SpaceBullet::get_param(PhysicsServer::AreaParameter p_param) {
+Variant SpaceBullet::get_param(PhysicsServer3D::AreaParameter p_param) {
switch (p_param) {
- case PhysicsServer::AREA_PARAM_GRAVITY:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY:
return gravityMagnitude;
- case PhysicsServer::AREA_PARAM_GRAVITY_VECTOR:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_VECTOR:
return gravityDirection;
- case PhysicsServer::AREA_PARAM_LINEAR_DAMP:
- case PhysicsServer::AREA_PARAM_ANGULAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_LINEAR_DAMP:
+ case PhysicsServer3D::AREA_PARAM_ANGULAR_DAMP:
return 0; // No damp
- case PhysicsServer::AREA_PARAM_PRIORITY:
+ case PhysicsServer3D::AREA_PARAM_PRIORITY:
return 0; // Priority is always 0, the lower
- case PhysicsServer::AREA_PARAM_GRAVITY_IS_POINT:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_IS_POINT:
return false;
- case PhysicsServer::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_DISTANCE_SCALE:
return 0;
- case PhysicsServer::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
+ case PhysicsServer3D::AREA_PARAM_GRAVITY_POINT_ATTENUATION:
return 0;
default:
WARN_PRINT("This get parameter (" + itos(p_param) + ") is ignored, the SpaceBullet doesn't support it.");
@@ -417,32 +417,32 @@ Variant SpaceBullet::get_param(PhysicsServer::AreaParameter p_param) {
}
}
-void SpaceBullet::set_param(PhysicsServer::SpaceParameter p_param, real_t p_value) {
+void SpaceBullet::set_param(PhysicsServer3D::SpaceParameter p_param, real_t p_value) {
switch (p_param) {
- case PhysicsServer::SPACE_PARAM_CONTACT_RECYCLE_RADIUS:
- case PhysicsServer::SPACE_PARAM_CONTACT_MAX_SEPARATION:
- case PhysicsServer::SPACE_PARAM_BODY_MAX_ALLOWED_PENETRATION:
- case PhysicsServer::SPACE_PARAM_BODY_LINEAR_VELOCITY_SLEEP_THRESHOLD:
- case PhysicsServer::SPACE_PARAM_BODY_ANGULAR_VELOCITY_SLEEP_THRESHOLD:
- case PhysicsServer::SPACE_PARAM_BODY_TIME_TO_SLEEP:
- case PhysicsServer::SPACE_PARAM_BODY_ANGULAR_VELOCITY_DAMP_RATIO:
- case PhysicsServer::SPACE_PARAM_CONSTRAINT_DEFAULT_BIAS:
+ case PhysicsServer3D::SPACE_PARAM_CONTACT_RECYCLE_RADIUS:
+ case PhysicsServer3D::SPACE_PARAM_CONTACT_MAX_SEPARATION:
+ case PhysicsServer3D::SPACE_PARAM_BODY_MAX_ALLOWED_PENETRATION:
+ case PhysicsServer3D::SPACE_PARAM_BODY_LINEAR_VELOCITY_SLEEP_THRESHOLD:
+ case PhysicsServer3D::SPACE_PARAM_BODY_ANGULAR_VELOCITY_SLEEP_THRESHOLD:
+ case PhysicsServer3D::SPACE_PARAM_BODY_TIME_TO_SLEEP:
+ case PhysicsServer3D::SPACE_PARAM_BODY_ANGULAR_VELOCITY_DAMP_RATIO:
+ case PhysicsServer3D::SPACE_PARAM_CONSTRAINT_DEFAULT_BIAS:
default:
WARN_PRINT("This set parameter (" + itos(p_param) + ") is ignored, the SpaceBullet doesn't support it.");
break;
}
}
-real_t SpaceBullet::get_param(PhysicsServer::SpaceParameter p_param) {
+real_t SpaceBullet::get_param(PhysicsServer3D::SpaceParameter p_param) {
switch (p_param) {
- case PhysicsServer::SPACE_PARAM_CONTACT_RECYCLE_RADIUS:
- case PhysicsServer::SPACE_PARAM_CONTACT_MAX_SEPARATION:
- case PhysicsServer::SPACE_PARAM_BODY_MAX_ALLOWED_PENETRATION:
- case PhysicsServer::SPACE_PARAM_BODY_LINEAR_VELOCITY_SLEEP_THRESHOLD:
- case PhysicsServer::SPACE_PARAM_BODY_ANGULAR_VELOCITY_SLEEP_THRESHOLD:
- case PhysicsServer::SPACE_PARAM_BODY_TIME_TO_SLEEP:
- case PhysicsServer::SPACE_PARAM_BODY_ANGULAR_VELOCITY_DAMP_RATIO:
- case PhysicsServer::SPACE_PARAM_CONSTRAINT_DEFAULT_BIAS:
+ case PhysicsServer3D::SPACE_PARAM_CONTACT_RECYCLE_RADIUS:
+ case PhysicsServer3D::SPACE_PARAM_CONTACT_MAX_SEPARATION:
+ case PhysicsServer3D::SPACE_PARAM_BODY_MAX_ALLOWED_PENETRATION:
+ case PhysicsServer3D::SPACE_PARAM_BODY_LINEAR_VELOCITY_SLEEP_THRESHOLD:
+ case PhysicsServer3D::SPACE_PARAM_BODY_ANGULAR_VELOCITY_SLEEP_THRESHOLD:
+ case PhysicsServer3D::SPACE_PARAM_BODY_TIME_TO_SLEEP:
+ case PhysicsServer3D::SPACE_PARAM_BODY_ANGULAR_VELOCITY_DAMP_RATIO:
+ case PhysicsServer3D::SPACE_PARAM_CONSTRAINT_DEFAULT_BIAS:
default:
WARN_PRINT("The SpaceBullet doesn't support this get parameter (" + itos(p_param) + "), 0 is returned.");
return 0.f;
@@ -511,7 +511,7 @@ void SpaceBullet::remove_soft_body(SoftBodyBullet *p_body) {
if (is_using_soft_world()) {
if (p_body->get_bt_soft_body()) {
static_cast<btSoftRigidDynamicsWorld *>(dynamicsWorld)->removeSoftBody(p_body->get_bt_soft_body());
- p_body->get_bt_soft_body()->m_worldInfo = NULL;
+ p_body->get_bt_soft_body()->m_worldInfo = nullptr;
}
}
}
@@ -539,7 +539,7 @@ void SpaceBullet::remove_all_collision_objects() {
for (int i = dynamicsWorld->getNumCollisionObjects() - 1; 0 <= i; --i) {
btCollisionObject *btObj = dynamicsWorld->getCollisionObjectArray()[i];
CollisionObjectBullet *colObj = static_cast<CollisionObjectBullet *>(btObj->getUserPointer());
- colObj->set_space(NULL);
+ colObj->set_space(nullptr);
}
}
@@ -636,8 +636,8 @@ void SpaceBullet::destroy_world() {
/// The world elements (like: Collision Objects, Constraints, Shapes) are managed by godot
- dynamicsWorld->getBroadphase()->getOverlappingPairCache()->setInternalGhostPairCallback(NULL);
- dynamicsWorld->getPairCache()->setOverlapFilterCallback(NULL);
+ dynamicsWorld->getBroadphase()->getOverlappingPairCache()->setInternalGhostPairCallback(nullptr);
+ dynamicsWorld->getPairCache()->setOverlapFilterCallback(nullptr);
bulletdelete(ghostPairCallback);
bulletdelete(godotFilterCallback);
@@ -645,7 +645,7 @@ void SpaceBullet::destroy_world() {
// Deallocate world
dynamicsWorld->~btDiscreteDynamicsWorld();
free(dynamicsWorld);
- dynamicsWorld = NULL;
+ dynamicsWorld = nullptr;
bulletdelete(solver);
bulletdelete(broadphase);
@@ -741,7 +741,7 @@ void SpaceBullet::check_ghost_overlaps() {
static_cast<btConvexShape *>(other_body_shape),
gjk_simplex_solver,
gjk_epa_pen_solver);
- gjk_pair_detector.getClosestPoints(gjk_input, result, 0);
+ gjk_pair_detector.getClosestPoints(gjk_input, result, nullptr);
if (0 >= result.m_distance) {
hasOverlap = true;
@@ -750,10 +750,10 @@ void SpaceBullet::check_ghost_overlaps() {
} else {
- btCollisionObjectWrapper obA(NULL, area_shape, area->get_bt_ghost(), gjk_input.m_transformA, -1, y);
- btCollisionObjectWrapper obB(NULL, other_body_shape, otherObject->get_bt_collision_object(), gjk_input.m_transformB, -1, z);
+ btCollisionObjectWrapper obA(nullptr, area_shape, area->get_bt_ghost(), gjk_input.m_transformA, -1, y);
+ btCollisionObjectWrapper obB(nullptr, other_body_shape, otherObject->get_bt_collision_object(), gjk_input.m_transformB, -1, z);
- btCollisionAlgorithm *algorithm = dispatcher->findAlgorithm(&obA, &obB, NULL, BT_CONTACT_POINT_ALGORITHMS);
+ btCollisionAlgorithm *algorithm = dispatcher->findAlgorithm(&obA, &obB, nullptr, BT_CONTACT_POINT_ALGORITHMS);
if (!algorithm)
continue;
@@ -885,20 +885,20 @@ void SpaceBullet::update_gravity() {
#include "scene/3d/immediate_geometry.h"
-static ImmediateGeometry *motionVec(NULL);
-static ImmediateGeometry *normalLine(NULL);
+static ImmediateGeometry3D *motionVec(nullptr);
+static ImmediateGeometry3D *normalLine(nullptr);
static Ref<StandardMaterial3D> red_mat;
static Ref<StandardMaterial3D> blue_mat;
#endif
-bool SpaceBullet::test_body_motion(RigidBodyBullet *p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, PhysicsServer::MotionResult *r_result, bool p_exclude_raycast_shapes) {
+bool SpaceBullet::test_body_motion(RigidBodyBullet *p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, PhysicsServer3D::MotionResult *r_result, bool p_exclude_raycast_shapes) {
#if debug_test_motion
/// Yes I know this is not good, but I've used it as fast debugging hack.
/// I'm leaving it here just for speedup the other eventual debugs
if (!normalLine) {
- motionVec = memnew(ImmediateGeometry);
- normalLine = memnew(ImmediateGeometry);
+ motionVec = memnew(ImmediateGeometry3D);
+ normalLine = memnew(ImmediateGeometry3D);
SceneTree::get_singleton()->get_current_scene()->add_child(motionVec);
SceneTree::get_singleton()->get_current_scene()->add_child(normalLine);
@@ -951,7 +951,7 @@ bool SpaceBullet::test_body_motion(RigidBodyBullet *p_body, const Transform &p_f
Vector3 sup_line;
B_TO_G(body_safe_position.getOrigin(), sup_line);
motionVec->clear();
- motionVec->begin(Mesh::PRIMITIVE_LINES, NULL);
+ motionVec->begin(Mesh::PRIMITIVE_LINES, nullptr);
motionVec->add_vertex(sup_line);
motionVec->add_vertex(sup_line + p_motion * 10);
motionVec->end();
@@ -1028,7 +1028,7 @@ bool SpaceBullet::test_body_motion(RigidBodyBullet *p_body, const Transform &p_f
Vector3 sup_line2;
B_TO_G(motion, sup_line2);
normalLine->clear();
- normalLine->begin(Mesh::PRIMITIVE_LINES, NULL);
+ normalLine->begin(Mesh::PRIMITIVE_LINES, nullptr);
normalLine->add_vertex(r_result->collision_point);
normalLine->add_vertex(r_result->collision_point + r_result->collision_normal * 10);
normalLine->end();
@@ -1042,7 +1042,7 @@ bool SpaceBullet::test_body_motion(RigidBodyBullet *p_body, const Transform &p_f
return has_penetration;
}
-int SpaceBullet::test_ray_separation(RigidBodyBullet *p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, PhysicsServer::SeparationResult *r_results, int p_result_max, float p_margin) {
+int SpaceBullet::test_ray_separation(RigidBodyBullet *p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, PhysicsServer3D::SeparationResult *r_results, int p_result_max, float p_margin) {
btTransform body_transform;
G_TO_B(p_transform, body_transform);
@@ -1054,7 +1054,7 @@ int SpaceBullet::test_ray_separation(RigidBodyBullet *p_body, const Transform &p
int rays_found_this_round = 0;
for (int t(RECOVERING_MOVEMENT_CYCLES); 0 < t; --t) {
- PhysicsServer::SeparationResult *next_results = &r_results[rays_found];
+ PhysicsServer3D::SeparationResult *next_results = &r_results[rays_found];
rays_found_this_round = recover_from_penetration_ray(p_body, body_transform, RECOVERING_MOVEMENT_SCALE, p_infinite_inertia, p_result_max - rays_found, recover_motion, next_results);
rays_found += rays_found_this_round;
@@ -1124,7 +1124,7 @@ public:
if (cs->getNumChildShapes() > 1) {
const btDbvt *tree = cs->getDynamicAabbTree();
- ERR_FAIL_COND_V(tree == NULL, true);
+ ERR_FAIL_COND_V(tree == nullptr, true);
// Transform bounds into compound shape local space
const btTransform other_in_compound_space = co->getWorldTransform().inverse();
@@ -1275,7 +1275,7 @@ bool SpaceBullet::RFP_convex_convex_test(const btConvexShape *p_shapeA, const bt
// Perform GJK test
btPointCollector result;
btGjkPairDetector gjk_pair_detector(p_shapeA, p_shapeB, gjk_simplex_solver, gjk_epa_pen_solver);
- gjk_pair_detector.getClosestPoints(gjk_input, result, 0);
+ gjk_pair_detector.getClosestPoints(gjk_input, result, nullptr);
if (0 > result.m_distance) {
// Has penetration
r_delta_recover_movement += result.m_normalOnBInWorld * (result.m_distance * -1 * p_recover_movement_scale);
@@ -1302,10 +1302,10 @@ bool SpaceBullet::RFP_convex_world_test(const btConvexShape *p_shapeA, const btC
btTransform tA(p_transformA);
- btCollisionObjectWrapper obA(NULL, p_shapeA, p_objectA, tA, -1, p_shapeId_A);
- btCollisionObjectWrapper obB(NULL, p_shapeB, p_objectB, p_transformB, -1, p_shapeId_B);
+ btCollisionObjectWrapper obA(nullptr, p_shapeA, p_objectA, tA, -1, p_shapeId_A);
+ btCollisionObjectWrapper obB(nullptr, p_shapeB, p_objectB, p_transformB, -1, p_shapeId_B);
- btCollisionAlgorithm *algorithm = dispatcher->findAlgorithm(&obA, &obB, NULL, BT_CONTACT_POINT_ALGORITHMS);
+ btCollisionAlgorithm *algorithm = dispatcher->findAlgorithm(&obA, &obB, nullptr, BT_CONTACT_POINT_ALGORITHMS);
if (algorithm) {
GodotDeepPenetrationContactResultCallback contactPointResult(&obA, &obB);
//discrete collision detection query
@@ -1333,7 +1333,7 @@ bool SpaceBullet::RFP_convex_world_test(const btConvexShape *p_shapeA, const btC
return false;
}
-int SpaceBullet::add_separation_result(PhysicsServer::SeparationResult *r_result, const SpaceBullet::RecoverResult &p_recover_result, int p_shape_id, const btCollisionObject *p_other_object) const {
+int SpaceBullet::add_separation_result(PhysicsServer3D::SeparationResult *r_result, const SpaceBullet::RecoverResult &p_recover_result, int p_shape_id, const btCollisionObject *p_other_object) const {
// optimize results (ignore non-colliding)
if (p_recover_result.penetration_distance < 0.0) {
@@ -1355,7 +1355,7 @@ int SpaceBullet::add_separation_result(PhysicsServer::SeparationResult *r_result
}
}
-int SpaceBullet::recover_from_penetration_ray(RigidBodyBullet *p_body, const btTransform &p_body_position, btScalar p_recover_movement_scale, bool p_infinite_inertia, int p_result_max, btVector3 &r_delta_recover_movement, PhysicsServer::SeparationResult *r_results) {
+int SpaceBullet::recover_from_penetration_ray(RigidBodyBullet *p_body, const btTransform &p_body_position, btScalar p_recover_movement_scale, bool p_infinite_inertia, int p_result_max, btVector3 &r_delta_recover_movement, PhysicsServer3D::SeparationResult *r_results) {
// Calculate the cumulative AABB of all shapes of the kinematic body
btVector3 aabb_min, aabb_max;
diff --git a/modules/bullet/space_bullet.h b/modules/bullet/space_bullet.h
index 32372f1630..f9a8c063fd 100644
--- a/modules/bullet/space_bullet.h
+++ b/modules/bullet/space_bullet.h
@@ -35,7 +35,7 @@
#include "core/vector.h"
#include "godot_result_callbacks.h"
#include "rid_bullet.h"
-#include "servers/physics_server.h"
+#include "servers/physics_server_3d.h"
#include <BulletCollision/BroadphaseCollision/btBroadphaseProxy.h>
#include <BulletCollision/BroadphaseCollision/btOverlappingPairCache.h>
@@ -67,8 +67,8 @@ class btGjkEpaPenetrationDepthSolver;
extern ContactAddedCallback gContactAddedCallback;
-class BulletPhysicsDirectSpaceState : public PhysicsDirectSpaceState {
- GDCLASS(BulletPhysicsDirectSpaceState, PhysicsDirectSpaceState);
+class BulletPhysicsDirectSpaceState : public PhysicsDirectSpaceState3D {
+ GDCLASS(BulletPhysicsDirectSpaceState, PhysicsDirectSpaceState3D);
private:
SpaceBullet *space;
@@ -79,7 +79,7 @@ public:
virtual int intersect_point(const Vector3 &p_point, ShapeResult *r_results, int p_result_max, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false);
virtual bool intersect_ray(const Vector3 &p_from, const Vector3 &p_to, RayResult &r_result, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false, bool p_pick_ray = false);
virtual int intersect_shape(const RID &p_shape, const Transform &p_xform, float p_margin, ShapeResult *r_results, int p_result_max, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false);
- virtual bool cast_motion(const RID &p_shape, const Transform &p_xform, const Vector3 &p_motion, float p_margin, float &r_closest_safe, float &r_closest_unsafe, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false, ShapeRestInfo *r_info = NULL);
+ virtual bool cast_motion(const RID &p_shape, const Transform &p_xform, const Vector3 &p_motion, float p_margin, float &r_closest_safe, float &r_closest_unsafe, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false, ShapeRestInfo *r_info = nullptr);
/// Returns the list of contacts pairs in this order: Local contact, other body contact
virtual bool collide_shape(RID p_shape, const Transform &p_shape_xform, float p_margin, Vector3 *r_results, int p_result_max, int &r_result_count, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false);
virtual bool rest_info(RID p_shape, const Transform &p_shape_xform, float p_margin, ShapeRestInfo *r_info, const Set<RID> &p_exclude = Set<RID>(), uint32_t p_collision_mask = 0xFFFFFFFF, bool p_collide_with_bodies = true, bool p_collide_with_areas = false);
@@ -131,15 +131,15 @@ public:
/// @param p_param:
/// AREA_PARAM_GRAVITY to set the gravity magnitude of entire world
/// AREA_PARAM_GRAVITY_VECTOR to set the gravity direction of entire world
- void set_param(PhysicsServer::AreaParameter p_param, const Variant &p_value);
+ void set_param(PhysicsServer3D::AreaParameter p_param, const Variant &p_value);
/// Used to get some parameters to Bullet world
/// @param p_param:
/// AREA_PARAM_GRAVITY to get the gravity magnitude of entire world
/// AREA_PARAM_GRAVITY_VECTOR to get the gravity direction of entire world
- Variant get_param(PhysicsServer::AreaParameter p_param);
+ Variant get_param(PhysicsServer3D::AreaParameter p_param);
- void set_param(PhysicsServer::SpaceParameter p_param, real_t p_value);
- real_t get_param(PhysicsServer::SpaceParameter p_param);
+ void set_param(PhysicsServer3D::SpaceParameter p_param, real_t p_value);
+ real_t get_param(PhysicsServer3D::SpaceParameter p_param);
void add_area(AreaBullet *p_area);
void remove_area(AreaBullet *p_area);
@@ -177,8 +177,8 @@ public:
void update_gravity();
- bool test_body_motion(RigidBodyBullet *p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, PhysicsServer::MotionResult *r_result, bool p_exclude_raycast_shapes);
- int test_ray_separation(RigidBodyBullet *p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, PhysicsServer::SeparationResult *r_results, int p_result_max, float p_margin);
+ bool test_body_motion(RigidBodyBullet *p_body, const Transform &p_from, const Vector3 &p_motion, bool p_infinite_inertia, PhysicsServer3D::MotionResult *r_result, bool p_exclude_raycast_shapes);
+ int test_ray_separation(RigidBodyBullet *p_body, const Transform &p_transform, bool p_infinite_inertia, Vector3 &r_recover_motion, PhysicsServer3D::SeparationResult *r_results, int p_result_max, float p_margin);
private:
void create_empty_world(bool p_create_soft_world);
@@ -201,19 +201,19 @@ private:
pointWorld(0, 0, 0),
penetration_distance(1e20),
other_compound_shape_index(0),
- other_collision_object(NULL),
+ other_collision_object(nullptr),
local_shape_most_recovered(0) {}
};
- bool recover_from_penetration(RigidBodyBullet *p_body, const btTransform &p_body_position, btScalar p_recover_movement_scale, bool p_infinite_inertia, btVector3 &r_delta_recover_movement, RecoverResult *r_recover_result = NULL);
+ bool recover_from_penetration(RigidBodyBullet *p_body, const btTransform &p_body_position, btScalar p_recover_movement_scale, bool p_infinite_inertia, btVector3 &r_delta_recover_movement, RecoverResult *r_recover_result = nullptr);
/// This is an API that recover a kinematic object from penetration
/// This allow only Convex Convex test and it always use GJK algorithm, With this API we don't benefit of Bullet special accelerated functions
- bool RFP_convex_convex_test(const btConvexShape *p_shapeA, const btConvexShape *p_shapeB, btCollisionObject *p_objectB, int p_shapeId_A, int p_shapeId_B, const btTransform &p_transformA, const btTransform &p_transformB, btScalar p_recover_movement_scale, btVector3 &r_delta_recover_movement, RecoverResult *r_recover_result = NULL);
+ bool RFP_convex_convex_test(const btConvexShape *p_shapeA, const btConvexShape *p_shapeB, btCollisionObject *p_objectB, int p_shapeId_A, int p_shapeId_B, const btTransform &p_transformA, const btTransform &p_transformB, btScalar p_recover_movement_scale, btVector3 &r_delta_recover_movement, RecoverResult *r_recover_result = nullptr);
/// This is an API that recover a kinematic object from penetration
/// Using this we leave Bullet to select the best algorithm, For example GJK in case we have Convex Convex, or a Bullet accelerated algorithm
- bool RFP_convex_world_test(const btConvexShape *p_shapeA, const btCollisionShape *p_shapeB, btCollisionObject *p_objectA, btCollisionObject *p_objectB, int p_shapeId_A, int p_shapeId_B, const btTransform &p_transformA, const btTransform &p_transformB, btScalar p_recover_movement_scale, btVector3 &r_delta_recover_movement, RecoverResult *r_recover_result = NULL);
+ bool RFP_convex_world_test(const btConvexShape *p_shapeA, const btCollisionShape *p_shapeB, btCollisionObject *p_objectA, btCollisionObject *p_objectB, int p_shapeId_A, int p_shapeId_B, const btTransform &p_transformA, const btTransform &p_transformB, btScalar p_recover_movement_scale, btVector3 &r_delta_recover_movement, RecoverResult *r_recover_result = nullptr);
- int add_separation_result(PhysicsServer::SeparationResult *r_results, const SpaceBullet::RecoverResult &p_recover_result, int p_shape_id, const btCollisionObject *p_other_object) const;
- int recover_from_penetration_ray(RigidBodyBullet *p_body, const btTransform &p_body_position, btScalar p_recover_movement_scale, bool p_infinite_inertia, int p_result_max, btVector3 &r_delta_recover_movement, PhysicsServer::SeparationResult *r_results);
+ int add_separation_result(PhysicsServer3D::SeparationResult *r_results, const SpaceBullet::RecoverResult &p_recover_result, int p_shape_id, const btCollisionObject *p_other_object) const;
+ int recover_from_penetration_ray(RigidBodyBullet *p_body, const btTransform &p_body_position, btScalar p_recover_movement_scale, bool p_infinite_inertia, int p_result_max, btVector3 &r_delta_recover_movement, PhysicsServer3D::SeparationResult *r_results);
};
#endif