Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJoseph Eagar <joeedh@gmail.com>2010-09-04 23:04:36 +0400
committerJoseph Eagar <joeedh@gmail.com>2010-09-04 23:04:36 +0400
commitda42a340b51bf55c1888f073fbfb35bf62a077b9 (patch)
treeef8c313194b73a7e588668ac87195a1bbab9f448 /source/gameengine/Physics/Bullet
parent2ff53caef237d2792de26b6e869146d5fc1c9cde (diff)
bleh
Diffstat (limited to 'source/gameengine/Physics/Bullet')
-rw-r--r--source/gameengine/Physics/Bullet/CMakeLists.txt49
-rw-r--r--source/gameengine/Physics/Bullet/CcdGraphicController.cpp149
-rw-r--r--source/gameengine/Physics/Bullet/CcdGraphicController.h88
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsController.cpp2165
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsController.h619
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp2721
-rw-r--r--source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h285
-rw-r--r--source/gameengine/Physics/Bullet/Makefile55
-rw-r--r--source/gameengine/Physics/Bullet/SConscript31
9 files changed, 0 insertions, 6162 deletions
diff --git a/source/gameengine/Physics/Bullet/CMakeLists.txt b/source/gameengine/Physics/Bullet/CMakeLists.txt
deleted file mode 100644
index 95888967b78..00000000000
--- a/source/gameengine/Physics/Bullet/CMakeLists.txt
+++ /dev/null
@@ -1,49 +0,0 @@
-# $Id$
-# ***** BEGIN GPL LICENSE BLOCK *****
-#
-# This program is free software; you can redistribute it and/or
-# modify it under the terms of the GNU General Public License
-# as published by the Free Software Foundation; either version 2
-# of the License, or (at your option) any later version.
-#
-# This program is distributed in the hope that it will be useful,
-# but WITHOUT ANY WARRANTY; without even the implied warranty of
-# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-# GNU General Public License for more details.
-#
-# You should have received a copy of the GNU General Public License
-# along with this program; if not, write to the Free Software Foundation,
-# Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
-#
-# The Original Code is Copyright (C) 2006, Blender Foundation
-# All rights reserved.
-#
-# The Original Code is: all of this file.
-#
-# Contributor(s): Jacques Beaurain.
-#
-# ***** END GPL LICENSE BLOCK *****
-
-SET(SRC CcdPhysicsEnvironment.cpp CcdPhysicsController.cpp CcdGraphicController.cpp)
-
-SET(INC
- .
- ../common
- ../../../../extern/bullet2/src
- ../../../../extern/glew/include
- ../../../../intern/moto/include
- ../../../../intern/guardedalloc
- ../../../kernel/gen_system
- ../../../../intern/string
- ../../Rasterizer
- ../../Ketsji
- ../../Expressions
- ../../GameLogic
- ../../SceneGraph
- ../../../../source/blender/makesdna
- ../../../../source/blender/blenlib
- ../../../../source/blender/blenkernel
- ${PYTHON_INC}
-)
-
-BLENDERLIB(bf_bullet "${SRC}" "${INC}")
diff --git a/source/gameengine/Physics/Bullet/CcdGraphicController.cpp b/source/gameengine/Physics/Bullet/CcdGraphicController.cpp
deleted file mode 100644
index 73ac789edf7..00000000000
--- a/source/gameengine/Physics/Bullet/CcdGraphicController.cpp
+++ /dev/null
@@ -1,149 +0,0 @@
-/*
-Bullet Continuous Collision Detection and Physics Library
-Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
-
-This software is provided 'as-is', without any express or implied warranty.
-In no event will the authors be held liable for any damages arising from the use of this software.
-Permission is granted to anyone to use this software for any purpose,
-including commercial applications, and to alter it and redistribute it freely,
-subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
-2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
-3. This notice may not be removed or altered from any source distribution.
-*/
-
-#include "CcdPhysicsEnvironment.h"
-#include "CcdGraphicController.h"
-#include "btBulletDynamicsCommon.h"
-#include "MT_Point3.h"
-
-
-CcdGraphicController::CcdGraphicController (CcdPhysicsEnvironment* phyEnv, PHY_IMotionState* motionState) :
- m_localAabbMin(0.f, 0.f, 0.f),
- m_localAabbMax(0.f, 0.f, 0.f),
- m_motionState(motionState),
- m_phyEnv(phyEnv),
- m_handle(NULL),
- m_newClientInfo(NULL)
-{
-}
-
-CcdGraphicController::~CcdGraphicController()
-{
- if (m_phyEnv)
- m_phyEnv->removeCcdGraphicController(this);
-
- if (m_motionState)
- delete m_motionState;
-}
-
-void CcdGraphicController::setLocalAabb(const btVector3& aabbMin,const btVector3& aabbMax)
-{
- m_localAabbMin = aabbMin;
- m_localAabbMax = aabbMax;
- SetGraphicTransform();
-}
-
-void CcdGraphicController::setLocalAabb(const MT_Point3& aabbMin,const MT_Point3& aabbMax)
-{
- m_localAabbMin.setValue(aabbMin[0],aabbMin[1],aabbMin[2]);
- m_localAabbMax.setValue(aabbMax[0],aabbMax[1],aabbMax[2]);
- SetGraphicTransform();
-}
-
-void CcdGraphicController::setLocalAabb(const PHY__Vector3& aabbMin,const PHY__Vector3& aabbMax)
-{
- m_localAabbMin.setValue(aabbMin[0],aabbMin[1],aabbMin[2]);
- m_localAabbMax.setValue(aabbMax[0],aabbMax[1],aabbMax[2]);
- SetGraphicTransform();
-}
-
-void CcdGraphicController::setLocalAabb(const float* aabbMin,const float* aabbMax)
-{
- m_localAabbMin.setValue(aabbMin[0],aabbMin[1],aabbMin[2]);
- m_localAabbMax.setValue(aabbMax[0],aabbMax[1],aabbMax[2]);
- SetGraphicTransform();
-}
-
-void CcdGraphicController::getAabb(btVector3& aabbMin, btVector3& aabbMax)
-{
- btVector3 pos;
- btVector3 scale;
- float ori[12];
- m_motionState->getWorldPosition(pos.m_floats[0],pos.m_floats[1],pos.m_floats[2]);
- m_motionState->getWorldScaling(scale.m_floats[0],scale.m_floats[1],scale.m_floats[2]);
- m_motionState->getWorldOrientation(ori);
- btMatrix3x3 rot(ori[0], ori[4], ori[8],
- ori[1], ori[5], ori[9],
- ori[2], ori[6], ori[10]);
-
- btVector3 localAabbMin = m_localAabbMin;
- btVector3 localAabbMax = m_localAabbMax;
- btVector3 tmpAabbMin = m_localAabbMin * scale;
- btVector3 tmpAabbMax = m_localAabbMax * scale;
-
- localAabbMin[0] = (scale.getX() >= 0.) ? tmpAabbMin[0] : tmpAabbMax[0];
- localAabbMin[1] = (scale.getY() >= 0.) ? tmpAabbMin[1] : tmpAabbMax[1];
- localAabbMin[2] = (scale.getZ() >= 0.) ? tmpAabbMin[2] : tmpAabbMax[2];
- localAabbMax[0] = (scale.getX() <= 0.) ? tmpAabbMin[0] : tmpAabbMax[0];
- localAabbMax[1] = (scale.getY() <= 0.) ? tmpAabbMin[1] : tmpAabbMax[1];
- localAabbMax[2] = (scale.getZ() <= 0.) ? tmpAabbMin[2] : tmpAabbMax[2];
-
- btVector3 localHalfExtents = btScalar(0.5)*(localAabbMax-localAabbMin);
- btVector3 localCenter = btScalar(0.5)*(localAabbMax+localAabbMin);
-
- btMatrix3x3 abs_b = rot.absolute();
- btVector3 center = rot*localCenter + pos;
- btVector3 extent = abs_b*localHalfExtents;
- aabbMin = center - extent;
- aabbMax = center + extent;
-}
-
-bool CcdGraphicController::SetGraphicTransform()
-{
- if (!m_handle)
- return false;
- btVector3 aabbMin;
- btVector3 aabbMax;
- getAabb(aabbMin, aabbMax);
- // update Aabb in broadphase
- m_phyEnv->getCullingTree()->setAabb(m_handle,aabbMin,aabbMax,NULL);
- return true;
-}
-
-PHY_IGraphicController* CcdGraphicController::GetReplica(class PHY_IMotionState* motionState)
-{
- CcdGraphicController* replica = new CcdGraphicController(*this);
- replica->m_motionState = motionState;
- replica->m_newClientInfo = NULL;
- replica->m_handle = NULL;
- // don't add the graphic controller now: work around a bug in Bullet with rescaling,
- // (the scale of the controller is not yet defined).
- //m_phyEnv->addCcdGraphicController(replica);
- return replica;
-}
-
-void CcdGraphicController::SetPhysicsEnvironment(class PHY_IPhysicsEnvironment* env)
-{
- CcdPhysicsEnvironment* phyEnv = static_cast<CcdPhysicsEnvironment*>(env);
- /* Updates the m_phyEnv's m_cullingTree & m_cullingCache */
- if(getBroadphaseHandle()) {
- /* insert into the new physics scene */
- Activate(false);
- m_phyEnv= phyEnv;
- Activate(true);
- }
- else {
- m_phyEnv= phyEnv;
- }
-}
-
-void CcdGraphicController::Activate(bool active)
-{
- if (active)
- m_phyEnv->addCcdGraphicController(this);
- else
- m_phyEnv->removeCcdGraphicController(this);
-
-}
diff --git a/source/gameengine/Physics/Bullet/CcdGraphicController.h b/source/gameengine/Physics/Bullet/CcdGraphicController.h
deleted file mode 100644
index 97893420d79..00000000000
--- a/source/gameengine/Physics/Bullet/CcdGraphicController.h
+++ /dev/null
@@ -1,88 +0,0 @@
-/*
-Bullet Continuous Collision Detection and Physics Library
-Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
-
-This software is provided 'as-is', without any express or implied warranty.
-In no event will the authors be held liable for any damages arising from the use of this software.
-Permission is granted to anyone to use this software for any purpose,
-including commercial applications, and to alter it and redistribute it freely,
-subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
-2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
-3. This notice may not be removed or altered from any source distribution.
-*/
-
-
-#ifndef BULLET2_GRAPHICCONTROLLER_H
-#define BULLET2_GRAPHICCONTROLLER_H
-
-#include "PHY_IGraphicController.h"
-
-#include "btBulletDynamicsCommon.h"
-#include "LinearMath/btTransform.h"
-
-#include "PHY_IMotionState.h"
-#include "MT_Point3.h"
-
-class CcdPhysicsEnvironment;
-class btCollisionObject;
-
-///CcdGraphicController is a graphic object that supports view frustrum culling and occlusion
-class CcdGraphicController : public PHY_IGraphicController
-{
-public:
- CcdGraphicController(CcdPhysicsEnvironment* phyEnv, PHY_IMotionState* motionState);
-
- virtual ~CcdGraphicController();
-
- void setLocalAabb(const btVector3& aabbMin,const btVector3& aabbMax);
- void setLocalAabb(const MT_Point3& aabbMin,const MT_Point3& aabbMax);
- virtual void setLocalAabb(const PHY__Vector3& aabbMin,const PHY__Vector3& aabbMax);
- virtual void setLocalAabb(const float aabbMin[3],const float aabbMax[3]);
-
- PHY_IMotionState* GetMotionState() { return m_motionState; }
- void getAabb(btVector3& aabbMin, btVector3& aabbMax);
-
- virtual void setBroadphaseHandle(btBroadphaseProxy* handle) { m_handle = handle; }
- virtual btBroadphaseProxy* getBroadphaseHandle() { return m_handle; }
-
- virtual void SetPhysicsEnvironment(class PHY_IPhysicsEnvironment* env);
-
- ////////////////////////////////////
- // PHY_IGraphicController interface
- ////////////////////////////////////
-
- /**
- * Updates the Aabb based on the motion state
- */
- virtual bool SetGraphicTransform();
- /**
- * Add/remove to environment
- */
- virtual void Activate(bool active);
-
- // client info for culling
- virtual void* getNewClientInfo() { return m_newClientInfo; }
- virtual void setNewClientInfo(void* clientinfo) { m_newClientInfo = clientinfo; }
- virtual PHY_IGraphicController* GetReplica(class PHY_IMotionState* motionstate);
-
-private:
- // unscaled aabb corner
- btVector3 m_localAabbMin;
- btVector3 m_localAabbMax;
-
- PHY_IMotionState* m_motionState;
- CcdPhysicsEnvironment* m_phyEnv;
- btBroadphaseProxy* m_handle;
- void* m_newClientInfo;
-
-
-#ifdef WITH_CXX_GUARDEDALLOC
-public:
- void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:CcdGraphicController"); }
- void operator delete( void *mem ) { MEM_freeN(mem); }
-#endif
-};
-
-#endif //BULLET2_PHYSICSCONTROLLER_H
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp b/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp
deleted file mode 100644
index dc8d31936ec..00000000000
--- a/source/gameengine/Physics/Bullet/CcdPhysicsController.cpp
+++ /dev/null
@@ -1,2165 +0,0 @@
-/*
-Bullet Continuous Collision Detection and Physics Library
-Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
-
-This software is provided 'as-is', without any express or implied warranty.
-In no event will the authors be held liable for any damages arising from the use of this software.
-Permission is granted to anyone to use this software for any purpose,
-including commercial applications, and to alter it and redistribute it freely,
-subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
-2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
-3. This notice may not be removed or altered from any source distribution.
-*/
-
-#include "CcdPhysicsController.h"
-#include "btBulletDynamicsCommon.h"
-#include "BulletCollision/CollisionShapes/btScaledBvhTriangleMeshShape.h"
-
-#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
-
-#include "PHY_IMotionState.h"
-#include "CcdPhysicsEnvironment.h"
-#include "RAS_MeshObject.h"
-#include "KX_GameObject.h"
-
-#include "BulletSoftBody/btSoftBody.h"
-#include "BulletSoftBody//btSoftBodyInternals.h"
-#include "BulletSoftBody/btSoftBodyHelpers.h"
-#include "LinearMath/btConvexHull.h"
-#include "BulletCollision/Gimpact/btGImpactShape.h"
-#include "BulletCollision/Gimpact/btGImpactShape.h"
-
-
-#include "BulletSoftBody/btSoftRigidDynamicsWorld.h"
-
-#include "DNA_mesh_types.h"
-#include "DNA_meshdata_types.h"
-
-extern "C"{
-#include "BKE_cdderivedmesh.h"
-}
-
-class BP_Proxy;
-
-///todo: fill all the empty CcdPhysicsController methods, hook them up to the btRigidBody class
-
-//'temporarily' global variables
-//float gDeactivationTime = 2.f;
-//bool gDisableDeactivation = false;
-extern float gDeactivationTime;
-extern bool gDisableDeactivation;
-
-
-float gLinearSleepingTreshold = 0.8f;
-float gAngularSleepingTreshold = 1.0f;
-
-
-btVector3 startVel(0,0,0);//-10000);
-
-CcdPhysicsController::CcdPhysicsController (const CcdConstructionInfo& ci)
-:m_cci(ci)
-{
- m_prototypeTransformInitialized = false;
- m_softbodyMappingDone = false;
- m_collisionDelay = 0;
- m_newClientInfo = 0;
- m_registerCount = 0;
- m_softBodyTransformInitialized = false;
- m_parentCtrl = 0;
- // copy pointers locally to allow smart release
- m_MotionState = ci.m_MotionState;
- m_collisionShape = ci.m_collisionShape;
- // apply scaling before creating rigid body
- m_collisionShape->setLocalScaling(m_cci.m_scaling);
- if (m_cci.m_mass)
- m_collisionShape->calculateLocalInertia(m_cci.m_mass, m_cci.m_localInertiaTensor);
- // shape info is shared, increment ref count
- m_shapeInfo = ci.m_shapeInfo;
- if (m_shapeInfo)
- m_shapeInfo->AddRef();
-
- m_bulletMotionState = 0;
-
-
- CreateRigidbody();
-
-
-///???
-/*#ifdef WIN32
- if (GetRigidBody() && !GetRigidBody()->isStaticObject())
- GetRigidBody()->setLinearVelocity(startVel);
-#endif*/
-
-}
-
-btTransform& CcdPhysicsController::GetTransformFromMotionState(PHY_IMotionState* motionState)
-{
- static btTransform trans;
- btVector3 tmp;
- motionState->getWorldPosition(tmp.m_floats[0], tmp.m_floats[1], tmp.m_floats[2]);
- trans.setOrigin(tmp);
-
- float ori[12];
- motionState->getWorldOrientation(ori);
- trans.getBasis().setFromOpenGLSubMatrix(ori);
- //btQuaternion orn;
- //motionState->getWorldOrientation(orn[0],orn[1],orn[2],orn[3]);
- //trans.setRotation(orn);
- return trans;
-
-}
-
-class BlenderBulletMotionState : public btMotionState
-{
- PHY_IMotionState* m_blenderMotionState;
-
-public:
-
- BlenderBulletMotionState(PHY_IMotionState* bms)
- :m_blenderMotionState(bms)
- {
-
- }
-
- void getWorldTransform(btTransform& worldTrans ) const
- {
- btVector3 pos;
- float ori[12];
-
- m_blenderMotionState->getWorldPosition(pos.m_floats[0],pos.m_floats[1],pos.m_floats[2]);
- m_blenderMotionState->getWorldOrientation(ori);
- worldTrans.setOrigin(pos);
- worldTrans.getBasis().setFromOpenGLSubMatrix(ori);
- }
-
- void setWorldTransform(const btTransform& worldTrans)
- {
- m_blenderMotionState->setWorldPosition(worldTrans.getOrigin().getX(),worldTrans.getOrigin().getY(),worldTrans.getOrigin().getZ());
- btQuaternion rotQuat = worldTrans.getRotation();
- m_blenderMotionState->setWorldOrientation(rotQuat[0],rotQuat[1],rotQuat[2],rotQuat[3]);
- m_blenderMotionState->calculateWorldTransformations();
- }
-
-};
-
-
-btRigidBody* CcdPhysicsController::GetRigidBody()
-{
- return btRigidBody::upcast(m_object);
-}
-btCollisionObject* CcdPhysicsController::GetCollisionObject()
-{
- return m_object;
-}
-btSoftBody* CcdPhysicsController::GetSoftBody()
-{
- return btSoftBody::upcast(m_object);
-}
-
-#include "BulletSoftBody/btSoftBodyHelpers.h"
-
-
-bool CcdPhysicsController::CreateSoftbody()
-{
- int shapeType = m_cci.m_collisionShape ? m_cci.m_collisionShape->getShapeType() : 0;
-
- //disable soft body until first sneak preview is ready
- if (!m_cci.m_bSoft || !m_cci.m_collisionShape ||
- ((shapeType != CONVEX_HULL_SHAPE_PROXYTYPE)&&
- (shapeType != TRIANGLE_MESH_SHAPE_PROXYTYPE) &&
- (shapeType != SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE)))
- {
- return false;
- }
-
- btRigidBody::btRigidBodyConstructionInfo rbci(m_cci.m_mass,m_bulletMotionState,m_collisionShape,m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
- rbci.m_linearDamping = m_cci.m_linearDamping;
- rbci.m_angularDamping = m_cci.m_angularDamping;
- rbci.m_friction = m_cci.m_friction;
- rbci.m_restitution = m_cci.m_restitution;
-
- btVector3 p(0,0,0);// = getOrigin();
- //btSoftBody* psb=btSoftBodyHelpers::CreateRope(worldInfo, btVector3(-10,0,i*0.25),btVector3(10,0,i*0.25), 16,1+2);
- btSoftBody* psb = 0;
- btSoftBodyWorldInfo& worldInfo = m_cci.m_physicsEnv->getDynamicsWorld()->getWorldInfo();
-
- if (m_cci.m_collisionShape->getShapeType() == CONVEX_HULL_SHAPE_PROXYTYPE)
- {
- btConvexHullShape* convexHull = (btConvexHullShape* )m_cci.m_collisionShape;
- {
- int nvertices = convexHull->getNumPoints();
- const btVector3* vertices = convexHull->getPoints();
-
- HullDesc hdsc(QF_TRIANGLES,nvertices,vertices);
- HullResult hres;
- HullLibrary hlib;/*??*/
- hdsc.mMaxVertices=nvertices;
- hlib.CreateConvexHull(hdsc,hres);
-
- psb=new btSoftBody(&worldInfo,(int)hres.mNumOutputVertices,
- &hres.m_OutputVertices[0],0);
- for(int i=0;i<(int)hres.mNumFaces;++i)
- {
- const int idx[]={ hres.m_Indices[i*3+0],
- hres.m_Indices[i*3+1],
- hres.m_Indices[i*3+2]};
- if(idx[0]<idx[1]) psb->appendLink( idx[0],idx[1]);
- if(idx[1]<idx[2]) psb->appendLink( idx[1],idx[2]);
- if(idx[2]<idx[0]) psb->appendLink( idx[2],idx[0]);
- psb->appendFace(idx[0],idx[1],idx[2]);
- }
- hlib.ReleaseResult(hres);
- }
- } else
- {
- int numtris = 0;
- if (m_cci.m_collisionShape->getShapeType() ==SCALED_TRIANGLE_MESH_SHAPE_PROXYTYPE)
- {
- btScaledBvhTriangleMeshShape* scaledtrimeshshape = (btScaledBvhTriangleMeshShape*) m_cci.m_collisionShape;
- btBvhTriangleMeshShape* trimeshshape = scaledtrimeshshape->getChildShape();
-
- ///only deal with meshes that have 1 sub part/component, for now
- if (trimeshshape->getMeshInterface()->getNumSubParts()==1)
- {
- unsigned char* vertexBase;
- PHY_ScalarType vertexType;
- int numverts;
- int vertexstride;
- unsigned char* indexbase;
- int indexstride;
- PHY_ScalarType indexType;
- trimeshshape->getMeshInterface()->getLockedVertexIndexBase(&vertexBase,numverts,vertexType,vertexstride,&indexbase,indexstride,numtris,indexType);
-
- psb = btSoftBodyHelpers::CreateFromTriMesh(worldInfo,(const btScalar*)vertexBase,(const int*)indexbase,numtris,false);
- }
- } else
- {
- btTriangleMeshShape* trimeshshape = (btTriangleMeshShape*) m_cci.m_collisionShape;
- ///only deal with meshes that have 1 sub part/component, for now
- if (trimeshshape->getMeshInterface()->getNumSubParts()==1)
- {
- unsigned char* vertexBase;
- PHY_ScalarType vertexType;
- int numverts;
- int vertexstride;
- unsigned char* indexbase;
- int indexstride;
- PHY_ScalarType indexType;
- trimeshshape->getMeshInterface()->getLockedVertexIndexBase(&vertexBase,numverts,vertexType,vertexstride,&indexbase,indexstride,numtris,indexType);
-
- psb = btSoftBodyHelpers::CreateFromTriMesh(worldInfo,(const btScalar*)vertexBase,(const int*)indexbase,numtris,false);
- }
- }
- // store face tag so that we can find our original face when doing ray casting
- btSoftBody::Face* ft;
- int i;
- for (i=0, ft=&psb->m_faces[0]; i<numtris; ++i, ++ft)
- {
- // Hack!! use m_tag to store the face number, normally it is a pointer
- // add 1 to make sure it is never 0
- ft->m_tag = (void*)((uintptr_t)(i+1));
- }
- }
- if (m_cci.m_margin > 0.f)
- {
- psb->getCollisionShape()->setMargin(m_cci.m_margin);
- psb->updateBounds();
- }
- m_object = psb;
-
- //btSoftBody::Material* pm=psb->appendMaterial();
- btSoftBody::Material* pm=psb->m_materials[0];
- pm->m_kLST = m_cci.m_soft_linStiff;
- pm->m_kAST = m_cci.m_soft_angStiff;
- pm->m_kVST = m_cci.m_soft_volume;
- psb->m_cfg.collisions = 0;
-
- if (m_cci.m_soft_collisionflags & CCD_BSB_COL_CL_RS)
- {
- psb->m_cfg.collisions += btSoftBody::fCollision::CL_RS;
- } else
- {
- psb->m_cfg.collisions += btSoftBody::fCollision::SDF_RS;
- }
- if (m_cci.m_soft_collisionflags & CCD_BSB_COL_CL_SS)
- {
- psb->m_cfg.collisions += btSoftBody::fCollision::CL_SS;
- } else
- {
- psb->m_cfg.collisions += btSoftBody::fCollision::VF_SS;
- }
-
-
- psb->m_cfg.kSRHR_CL = m_cci.m_soft_kSRHR_CL; /* Soft vs rigid hardness [0,1] (cluster only) */
- psb->m_cfg.kSKHR_CL = m_cci.m_soft_kSKHR_CL; /* Soft vs kinetic hardness [0,1] (cluster only) */
- psb->m_cfg.kSSHR_CL = m_cci.m_soft_kSSHR_CL; /* Soft vs soft hardness [0,1] (cluster only) */
- psb->m_cfg.kSR_SPLT_CL = m_cci.m_soft_kSR_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
-
- psb->m_cfg.kSK_SPLT_CL = m_cci.m_soft_kSK_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
- psb->m_cfg.kSS_SPLT_CL = m_cci.m_soft_kSS_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
- psb->m_cfg.kVCF = m_cci.m_soft_kVCF; /* Velocities correction factor (Baumgarte) */
- psb->m_cfg.kDP = m_cci.m_soft_kDP; /* Damping coefficient [0,1] */
-
- psb->m_cfg.kDG = m_cci.m_soft_kDG; /* Drag coefficient [0,+inf] */
- psb->m_cfg.kLF = m_cci.m_soft_kLF; /* Lift coefficient [0,+inf] */
- psb->m_cfg.kPR = m_cci.m_soft_kPR; /* Pressure coefficient [-inf,+inf] */
- psb->m_cfg.kVC = m_cci.m_soft_kVC; /* Volume conversation coefficient [0,+inf] */
-
- psb->m_cfg.kDF = m_cci.m_soft_kDF; /* Dynamic friction coefficient [0,1] */
- psb->m_cfg.kMT = m_cci.m_soft_kMT; /* Pose matching coefficient [0,1] */
- psb->m_cfg.kCHR = m_cci.m_soft_kCHR; /* Rigid contacts hardness [0,1] */
- psb->m_cfg.kKHR = m_cci.m_soft_kKHR; /* Kinetic contacts hardness [0,1] */
-
- psb->m_cfg.kSHR = m_cci.m_soft_kSHR; /* Soft contacts hardness [0,1] */
- psb->m_cfg.kAHR = m_cci.m_soft_kAHR; /* Anchors hardness [0,1] */
-
- if (m_cci.m_gamesoftFlag & CCD_BSB_BENDING_CONSTRAINTS)//OB_SB_GOAL)
- {
- psb->generateBendingConstraints(2,pm);
- }
-
- psb->m_cfg.piterations = m_cci.m_soft_piterations;
- psb->m_cfg.viterations = m_cci.m_soft_viterations;
- psb->m_cfg.diterations = m_cci.m_soft_diterations;
- psb->m_cfg.citerations = m_cci.m_soft_citerations;
-
- if (m_cci.m_gamesoftFlag & CCD_BSB_SHAPE_MATCHING)//OB_SB_GOAL)
- {
- psb->setPose(false,true);//
- } else
- {
- psb->setPose(true,false);
- }
-
- psb->randomizeConstraints();
-
- if (m_cci.m_soft_collisionflags & (CCD_BSB_COL_CL_RS+CCD_BSB_COL_CL_SS))
- {
- psb->generateClusters(m_cci.m_soft_numclusteriterations);
- }
-
- psb->setTotalMass(m_cci.m_mass);
-
- psb->setCollisionFlags(0);
-
- ///create a mapping between graphics mesh vertices and soft body vertices
- {
- RAS_MeshObject* rasMesh= GetShapeInfo()->GetMesh();
-
- if (rasMesh && !m_softbodyMappingDone)
- {
- //printf("apply\n");
- RAS_MeshSlot::iterator it;
- RAS_MeshMaterial *mmat;
- RAS_MeshSlot *slot;
- size_t i;
-
- //for each material
- for (int m=0;m<rasMesh->NumMaterials();m++)
- {
- mmat = rasMesh->GetMeshMaterial(m);
-
- slot = mmat->m_baseslot;
- for(slot->begin(it); !slot->end(it); slot->next(it))
- {
- int index = 0;
- for(i=it.startvertex; i<it.endvertex; i++,index++)
- {
- RAS_TexVert* vertex = &it.vertex[i];
- //search closest index, and store it in vertex
- vertex->setSoftBodyIndex(0);
- btScalar maxDistSqr = 1e30;
- btSoftBody::tNodeArray& nodes(psb->m_nodes);
- btVector3 xyz = btVector3(vertex->getXYZ()[0],vertex->getXYZ()[1],vertex->getXYZ()[2]);
- for (int n=0;n<nodes.size();n++)
- {
- btScalar distSqr = (nodes[n].m_x - xyz).length2();
- if (distSqr<maxDistSqr)
- {
- maxDistSqr = distSqr;
-
- vertex->setSoftBodyIndex(n);
- }
- }
- }
- }
- }
- }
- }
- m_softbodyMappingDone = true;
-
- btTransform startTrans;
- rbci.m_motionState->getWorldTransform(startTrans);
-
- m_MotionState->setWorldPosition(startTrans.getOrigin().getX(),startTrans.getOrigin().getY(),startTrans.getOrigin().getZ());
- m_MotionState->setWorldOrientation(0,0,0,1);
-
- if (!m_prototypeTransformInitialized)
- {
- m_prototypeTransformInitialized = true;
- m_softBodyTransformInitialized = true;
- psb->transform(startTrans);
- }
- m_object->setCollisionFlags(m_object->getCollisionFlags() | m_cci.m_collisionFlags);
- if (m_cci.m_do_anisotropic)
- m_object->setAnisotropicFriction(m_cci.m_anisotropicFriction);
- return true;
-}
-
-
-void CcdPhysicsController::CreateRigidbody()
-{
-
- //btTransform trans = GetTransformFromMotionState(m_MotionState);
- m_bulletMotionState = new BlenderBulletMotionState(m_MotionState);
-
- ///either create a btCollisionObject, btRigidBody or btSoftBody
- if (CreateSoftbody())
- // soft body created, done
- return;
-
- //create a rgid collision object
- btRigidBody::btRigidBodyConstructionInfo rbci(m_cci.m_mass,m_bulletMotionState,m_collisionShape,m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
- rbci.m_linearDamping = m_cci.m_linearDamping;
- rbci.m_angularDamping = m_cci.m_angularDamping;
- rbci.m_friction = m_cci.m_friction;
- rbci.m_restitution = m_cci.m_restitution;
- m_object = new btRigidBody(rbci);
-
- //
- // init the rigidbody properly
- //
-
- //setMassProps this also sets collisionFlags
- //convert collision flags!
- //special case: a near/radar sensor controller should not be defined static or it will
- //generate loads of static-static collision messages on the console
- if (m_cci.m_bSensor)
- {
- // reset the flags that have been set so far
- GetCollisionObject()->setCollisionFlags(0);
- // sensor must never go to sleep: they need to detect continously
- GetCollisionObject()->setActivationState(DISABLE_DEACTIVATION);
- }
- GetCollisionObject()->setCollisionFlags(m_object->getCollisionFlags() | m_cci.m_collisionFlags);
- btRigidBody* body = GetRigidBody();
-
- if (body)
- {
- body->setGravity( m_cci.m_gravity);
- body->setDamping(m_cci.m_linearDamping, m_cci.m_angularDamping);
-
- if (!m_cci.m_bRigid)
- {
- body->setAngularFactor(0.f);
- }
- body->setContactProcessingThreshold(m_cci.m_contactProcessingThreshold);
-
- }
- if (m_object && m_cci.m_do_anisotropic)
- {
- m_object->setAnisotropicFriction(m_cci.m_anisotropicFriction);
- }
-
-}
-
-static void DeleteBulletShape(btCollisionShape* shape, bool free)
-{
- if (shape->getShapeType() == TRIANGLE_MESH_SHAPE_PROXYTYPE)
- {
- // shapes based on meshes use an interface that contains the vertices.
- btTriangleMeshShape* meshShape = static_cast<btTriangleMeshShape*>(shape);
- btStridingMeshInterface* meshInterface = meshShape->getMeshInterface();
- if (meshInterface)
- delete meshInterface;
- }
- if(free) {
- delete shape;
- }
-}
-
-bool CcdPhysicsController::DeleteControllerShape( )
-{
- if (m_collisionShape)
- {
- // collision shape is always unique to the controller, can delete it here
- if (m_collisionShape->isCompound())
- {
- // bullet does not delete the child shape, must do it here
- btCompoundShape* compoundShape = (btCompoundShape*)m_collisionShape;
- int numChild = compoundShape->getNumChildShapes();
- for (int i=numChild-1 ; i >= 0; i--)
- {
- btCollisionShape* childShape = compoundShape->getChildShape(i);
- DeleteBulletShape(childShape, true);
- }
- }
- DeleteBulletShape(m_collisionShape, true);
-
- return true;
- }
-
- return false;
-}
-
-bool CcdPhysicsController::ReplaceControllerShape(btCollisionShape *newShape)
-{
-
- /* Note, deleting the previous collision shape must be done already */
- /* if (m_collisionShape) DeleteControllerShape(); */
-
- m_object->setCollisionShape(newShape);
- m_collisionShape= newShape;
- m_cci.m_collisionShape= newShape;
-
- if (GetSoftBody()) {
- // soft body must be recreated
- m_cci.m_physicsEnv->removeCcdPhysicsController(this);
- delete m_object;
- m_object = NULL;
- // force complete reinitialization
- m_softbodyMappingDone = false;
- m_prototypeTransformInitialized = false;
- m_softBodyTransformInitialized = false;
- CreateSoftbody();
- assert(m_object);
- // reinsert the new body
- m_cci.m_physicsEnv->addCcdPhysicsController(this);
- }
-
- /* Copied from CcdPhysicsEnvironment::addCcdPhysicsController() */
-
- /* without this, an object can rest on the old physics mesh
- * and not move to account for the physics mesh, even with 'nosleep' */
- btSoftRigidDynamicsWorld* dw= GetPhysicsEnvironment()->getDynamicsWorld();
- btCollisionObjectArray &obarr= dw->getCollisionObjectArray();
- btCollisionObject *ob;
- btBroadphaseProxy* proxy;
-
- for(int i= 0; i < obarr.size(); i++) {
- ob= obarr[i];
- if (ob->getCollisionShape() == newShape) {
- proxy = ob->getBroadphaseHandle();
-
- if(proxy)
- dw->getPairCache()->cleanProxyFromPairs(proxy,dw->getDispatcher());
- }
- }
-
- return true;
-}
-
-CcdPhysicsController::~CcdPhysicsController()
-{
- //will be reference counted, due to sharing
- if (m_cci.m_physicsEnv)
- m_cci.m_physicsEnv->removeCcdPhysicsController(this);
-
- if (m_MotionState)
- delete m_MotionState;
- if (m_bulletMotionState)
- delete m_bulletMotionState;
- delete m_object;
-
- DeleteControllerShape();
-
- if (m_shapeInfo)
- {
- m_shapeInfo->Release();
- }
-}
-
-
- /**
- SynchronizeMotionStates ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
- */
-bool CcdPhysicsController::SynchronizeMotionStates(float time)
-{
- //sync non-static to motionstate, and static from motionstate (todo: add kinematic etc.)
-
- btSoftBody* sb = GetSoftBody();
- if (sb)
- {
- if (sb->m_pose.m_bframe)
- {
- btVector3 worldPos = sb->m_pose.m_com;
- btQuaternion worldquat;
- btMatrix3x3 trs = sb->m_pose.m_rot*sb->m_pose.m_scl;
- trs.getRotation(worldquat);
- m_MotionState->setWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
- m_MotionState->setWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
- }
- else
- {
- btVector3 aabbMin,aabbMax;
- sb->getAabb(aabbMin,aabbMax);
- btVector3 worldPos = (aabbMax+aabbMin)*0.5f;
- m_MotionState->setWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
- }
- m_MotionState->calculateWorldTransformations();
- return true;
- }
-
- btRigidBody* body = GetRigidBody();
-
- if (body && !body->isStaticObject())
- {
-
- if ((m_cci.m_clamp_vel_max>0.0) || (m_cci.m_clamp_vel_min>0.0))
- {
- const btVector3& linvel = body->getLinearVelocity();
- float len= linvel.length();
-
- if((m_cci.m_clamp_vel_max>0.0) && (len > m_cci.m_clamp_vel_max))
- body->setLinearVelocity(linvel * (m_cci.m_clamp_vel_max / len));
-
- else if ((m_cci.m_clamp_vel_min>0.0) && btFuzzyZero(len)==0 && (len < m_cci.m_clamp_vel_min))
- body->setLinearVelocity(linvel * (m_cci.m_clamp_vel_min / len));
- }
-
- const btTransform& xform = body->getCenterOfMassTransform();
- const btMatrix3x3& worldOri = xform.getBasis();
- const btVector3& worldPos = xform.getOrigin();
- float ori[12];
- worldOri.getOpenGLSubMatrix(ori);
- m_MotionState->setWorldOrientation(ori);
- m_MotionState->setWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
- m_MotionState->calculateWorldTransformations();
-
- float scale[3];
- m_MotionState->getWorldScaling(scale[0],scale[1],scale[2]);
- btVector3 scaling(scale[0],scale[1],scale[2]);
- GetCollisionShape()->setLocalScaling(scaling);
- } else
- {
- btVector3 worldPos;
- btQuaternion worldquat;
-
-/* m_MotionState->getWorldPosition(worldPos[0],worldPos[1],worldPos[2]);
- m_MotionState->getWorldOrientation(worldquat[0],worldquat[1],worldquat[2],worldquat[3]);
- btTransform oldTrans = m_body->getCenterOfMassTransform();
- btTransform newTrans(worldquat,worldPos);
-
- SetCenterOfMassTransform(newTrans);
- //need to keep track of previous position for friction effects...
-
- m_MotionState->calculateWorldTransformations();
-*/
- float scale[3];
- m_MotionState->getWorldScaling(scale[0],scale[1],scale[2]);
- btVector3 scaling(scale[0],scale[1],scale[2]);
- GetCollisionShape()->setLocalScaling(scaling);
- }
- return true;
-
-}
-
- /**
- WriteMotionStateToDynamics synchronizes dynas, kinematic and deformable entities (and do 'late binding')
- */
-
-void CcdPhysicsController::WriteMotionStateToDynamics(bool nondynaonly)
-{
- btTransform& xform = CcdPhysicsController::GetTransformFromMotionState(m_MotionState);
- SetCenterOfMassTransform(xform);
-}
-
-void CcdPhysicsController::WriteDynamicsToMotionState()
-{
-}
- // controller replication
-void CcdPhysicsController::PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl)
-{
-
- m_softBodyTransformInitialized=false;
- m_MotionState = motionstate;
- m_registerCount = 0;
- m_collisionShape = NULL;
-
- // always create a new shape to avoid scaling bug
- if (m_shapeInfo)
- {
- m_shapeInfo->AddRef();
- m_collisionShape = m_shapeInfo->CreateBulletShape(m_cci.m_margin, m_cci.m_bGimpact, !m_cci.m_bSoft);
-
- if (m_collisionShape)
- {
- // new shape has no scaling, apply initial scaling
- //m_collisionShape->setMargin(m_cci.m_margin);
- m_collisionShape->setLocalScaling(m_cci.m_scaling);
-
- if (m_cci.m_mass)
- m_collisionShape->calculateLocalInertia(m_cci.m_mass, m_cci.m_localInertiaTensor);
- }
- }
-
- // load some characterists that are not
- btRigidBody* oldbody = GetRigidBody();
- m_object = 0;
- CreateRigidbody();
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- if (m_cci.m_mass)
- {
- body->setMassProps(m_cci.m_mass, m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
- }
-
- if (oldbody)
- {
- body->setLinearFactor(oldbody->getLinearFactor());
- body->setAngularFactor(oldbody->getAngularFactor());
- if (oldbody->getActivationState() == DISABLE_DEACTIVATION)
- body->setActivationState(DISABLE_DEACTIVATION);
- }
- }
- // sensor object are added when needed
- if (!m_cci.m_bSensor)
- m_cci.m_physicsEnv->addCcdPhysicsController(this);
-
-
-/* SM_Object* dynaparent=0;
- SumoPhysicsController* sumoparentctrl = (SumoPhysicsController* )parentctrl;
-
- if (sumoparentctrl)
- {
- dynaparent = sumoparentctrl->GetSumoObject();
- }
-
- SM_Object* orgsumoobject = m_sumoObj;
-
-
- m_sumoObj = new SM_Object(
- orgsumoobject->getShapeHandle(),
- orgsumoobject->getMaterialProps(),
- orgsumoobject->getShapeProps(),
- dynaparent);
-
- m_sumoObj->setRigidBody(orgsumoobject->isRigidBody());
-
- m_sumoObj->setMargin(orgsumoobject->getMargin());
- m_sumoObj->setPosition(orgsumoobject->getPosition());
- m_sumoObj->setOrientation(orgsumoobject->getOrientation());
- //if it is a dyna, register for a callback
- m_sumoObj->registerCallback(*this);
-
- m_sumoScene->add(* (m_sumoObj));
- */
-
-
-
-}
-
-void CcdPhysicsController::SetPhysicsEnvironment(class PHY_IPhysicsEnvironment *env)
-{
- // can safely assume CCD environment
- CcdPhysicsEnvironment *physicsEnv = static_cast<CcdPhysicsEnvironment*>(env);
-
- if (m_cci.m_physicsEnv != physicsEnv)
- {
- // since the environment is changing, we must also move the controler to the
- // new environement. Note that we don't handle sensor explicitely: this
- // function can be called on sensor but only when they are not registered
- if (m_cci.m_physicsEnv->removeCcdPhysicsController(this))
- {
- physicsEnv->addCcdPhysicsController(this);
- }
- m_cci.m_physicsEnv = physicsEnv;
- }
-}
-
-void CcdPhysicsController::SetCenterOfMassTransform(btTransform& xform)
-{
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- body->setCenterOfMassTransform(xform);
- } else
- {
- //either collision object or soft body?
- if (GetSoftBody())
- {
-
- } else
- {
-
- if (m_object->isStaticOrKinematicObject())
- {
- m_object->setInterpolationWorldTransform(m_object->getWorldTransform());
- } else
- {
- m_object->setInterpolationWorldTransform(xform);
- }
- if (body)
- {
- body->setInterpolationLinearVelocity(body->getLinearVelocity());
- body->setInterpolationAngularVelocity(body->getAngularVelocity());
- body->updateInertiaTensor();
- }
- m_object->setWorldTransform(xform);
- }
- }
-}
-
- // kinematic methods
-void CcdPhysicsController::RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local)
-{
- if (m_object)
- {
- m_object->activate(true);
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- // kinematic object should not set the transform, it disturbs the velocity interpolation
- return;
- }
-
- // btRigidBody* body = GetRigidBody(); // not used anymore
-
- btVector3 dloc(dlocX,dlocY,dlocZ);
- btTransform xform = m_object->getWorldTransform();
-
- if (local)
- {
- dloc = xform.getBasis()*dloc;
- }
-
- xform.setOrigin(xform.getOrigin() + dloc);
- SetCenterOfMassTransform(xform);
- }
-
-}
-
-void CcdPhysicsController::RelativeRotate(const float rotval[9],bool local)
-{
- if (m_object)
- {
- m_object->activate(true);
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- // kinematic object should not set the transform, it disturbs the velocity interpolation
- return;
- }
-
- btMatrix3x3 drotmat( rotval[0],rotval[4],rotval[8],
- rotval[1],rotval[5],rotval[9],
- rotval[2],rotval[6],rotval[10]);
-
-
- btMatrix3x3 currentOrn;
- GetWorldOrientation(currentOrn);
-
- btTransform xform = m_object->getWorldTransform();
-
- xform.setBasis(xform.getBasis()*(local ?
- drotmat : (currentOrn.inverse() * drotmat * currentOrn)));
-
- SetCenterOfMassTransform(xform);
- }
-}
-
-
-void CcdPhysicsController::GetWorldOrientation(btMatrix3x3& mat)
-{
- float ori[12];
- m_MotionState->getWorldOrientation(ori);
- mat.setFromOpenGLSubMatrix(ori);
-}
-
-void CcdPhysicsController::getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal)
-{
- btQuaternion q = m_object->getWorldTransform().getRotation();
- quatImag0 = q[0];
- quatImag1 = q[1];
- quatImag2 = q[2];
- quatReal = q[3];
-}
-void CcdPhysicsController::setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal)
-{
- if (m_object)
- {
- m_object->activate(true);
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- // kinematic object should not set the transform, it disturbs the velocity interpolation
- return;
- }
- // not required
- //m_MotionState->setWorldOrientation(quatImag0,quatImag1,quatImag2,quatReal);
- btTransform xform = m_object->getWorldTransform();
- xform.setRotation(btQuaternion(quatImag0,quatImag1,quatImag2,quatReal));
- SetCenterOfMassTransform(xform);
- // not required
- //m_bulletMotionState->setWorldTransform(xform);
-
-
-
- }
-
-}
-
-void CcdPhysicsController::setWorldOrientation(const btMatrix3x3& orn)
-{
- if (m_object)
- {
- m_object->activate(true);
- if (m_object->isStaticObject() && !m_cci.m_bSensor)
- {
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- }
- // not required
- //m_MotionState->setWorldOrientation(quatImag0,quatImag1,quatImag2,quatReal);
- btTransform xform = m_object->getWorldTransform();
- xform.setBasis(orn);
- SetCenterOfMassTransform(xform);
- // not required
- //m_bulletMotionState->setWorldTransform(xform);
- //only once!
- if (!m_softBodyTransformInitialized && GetSoftBody())
- {
- m_softbodyStartTrans.setBasis(orn);
- xform.setOrigin(m_softbodyStartTrans.getOrigin());
- GetSoftBody()->transform(xform);
- m_softBodyTransformInitialized = true;
- }
-
- }
-
-}
-
-void CcdPhysicsController::setPosition(float posX,float posY,float posZ)
-{
- if (m_object)
- {
- m_object->activate(true);
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- // kinematic object should not set the transform, it disturbs the velocity interpolation
- return;
- }
- // not required, this function is only used to update the physic controller
- //m_MotionState->setWorldPosition(posX,posY,posZ);
- btTransform xform = m_object->getWorldTransform();
- xform.setOrigin(btVector3(posX,posY,posZ));
- SetCenterOfMassTransform(xform);
- if (!m_softBodyTransformInitialized)
- m_softbodyStartTrans.setOrigin(xform.getOrigin());
- // not required
- //m_bulletMotionState->setWorldTransform(xform);
- }
-}
-
-void CcdPhysicsController::forceWorldTransform(const btMatrix3x3& mat, const btVector3& pos)
-{
- if (m_object)
- {
- btTransform& xform = m_object->getWorldTransform();
- xform.setBasis(mat);
- xform.setOrigin(pos);
- }
-}
-
-
-void CcdPhysicsController::resolveCombinedVelocities(float linvelX,float linvelY,float linvelZ,float angVelX,float angVelY,float angVelZ)
-{
-}
-
-void CcdPhysicsController::getPosition(PHY__Vector3& pos) const
-{
- const btTransform& xform = m_object->getWorldTransform();
- pos[0] = xform.getOrigin().x();
- pos[1] = xform.getOrigin().y();
- pos[2] = xform.getOrigin().z();
-}
-
-void CcdPhysicsController::setScaling(float scaleX,float scaleY,float scaleZ)
-{
- if (!btFuzzyZero(m_cci.m_scaling.x()-scaleX) ||
- !btFuzzyZero(m_cci.m_scaling.y()-scaleY) ||
- !btFuzzyZero(m_cci.m_scaling.z()-scaleZ))
- {
- m_cci.m_scaling = btVector3(scaleX,scaleY,scaleZ);
-
- if (m_object && m_object->getCollisionShape())
- {
- m_object->activate(true); // without this, sleeping objects scale wont be applied in bullet if python changes the scale - Campbell.
- m_object->getCollisionShape()->setLocalScaling(m_cci.m_scaling);
-
- //printf("no inertia recalc for fixed objects with mass=0\n");
- btRigidBody* body = GetRigidBody();
- if (body && m_cci.m_mass)
- {
- body->getCollisionShape()->calculateLocalInertia(m_cci.m_mass, m_cci.m_localInertiaTensor);
- body->setMassProps(m_cci.m_mass, m_cci.m_localInertiaTensor * m_cci.m_inertiaFactor);
- }
-
- }
- }
-}
-
- // physics methods
-void CcdPhysicsController::ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local)
-{
- btVector3 torque(torqueX,torqueY,torqueZ);
- btTransform xform = m_object->getWorldTransform();
-
-
- if (m_object && torque.length2() > (SIMD_EPSILON*SIMD_EPSILON))
- {
- btRigidBody* body = GetRigidBody();
- m_object->activate();
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- return;
- }
- if (local)
- {
- torque = xform.getBasis()*torque;
- }
- if (body)
- {
- if (m_cci.m_bRigid)
- {
- body->applyTorque(torque);
- }
- else
- {
- //workaround for incompatibility between 'DYNAMIC' game object, and angular factor
- //a DYNAMIC object has some inconsistency: it has no angular effect due to collisions, but still has torque
- const btVector3& angFac = body->getAngularFactor();
- btVector3 tmpFac(1,1,1);
- body->setAngularFactor(tmpFac);
- body->applyTorque(torque);
- body->setAngularFactor(angFac);
- }
- }
- }
-}
-
-void CcdPhysicsController::ApplyForce(float forceX,float forceY,float forceZ,bool local)
-{
- btVector3 force(forceX,forceY,forceZ);
-
-
- if (m_object && force.length2() > (SIMD_EPSILON*SIMD_EPSILON))
- {
- m_object->activate();
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- return;
- }
- btTransform xform = m_object->getWorldTransform();
-
- if (local)
- {
- force = xform.getBasis()*force;
- }
- btRigidBody* body = GetRigidBody();
- if (body)
- body->applyCentralForce(force);
- btSoftBody* soft = GetSoftBody();
- if (soft)
- {
- // the force is applied on each node, must reduce it in the same extend
- if (soft->m_nodes.size() > 0)
- force /= soft->m_nodes.size();
- soft->addForce(force);
- }
- }
-}
-void CcdPhysicsController::SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local)
-{
- btVector3 angvel(ang_velX,ang_velY,ang_velZ);
- if (m_object && angvel.length2() > (SIMD_EPSILON*SIMD_EPSILON))
- {
- m_object->activate(true);
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- return;
- }
- btTransform xform = m_object->getWorldTransform();
- if (local)
- {
- angvel = xform.getBasis()*angvel;
- }
- btRigidBody* body = GetRigidBody();
- if (body)
- body->setAngularVelocity(angvel);
- }
-
-}
-void CcdPhysicsController::SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local)
-{
-
- btVector3 linVel(lin_velX,lin_velY,lin_velZ);
- if (m_object/* && linVel.length2() > (SIMD_EPSILON*SIMD_EPSILON)*/)
- {
- m_object->activate(true);
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- return;
- }
-
- btSoftBody* soft = GetSoftBody();
- if (soft)
- {
- if (local)
- {
- linVel = m_softbodyStartTrans.getBasis()*linVel;
- }
- soft->setVelocity(linVel);
- } else
- {
- btTransform xform = m_object->getWorldTransform();
- if (local)
- {
- linVel = xform.getBasis()*linVel;
- }
- btRigidBody* body = GetRigidBody();
- if (body)
- body->setLinearVelocity(linVel);
- }
- }
-}
-void CcdPhysicsController::applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ)
-{
- btVector3 impulse(impulseX,impulseY,impulseZ);
-
- if (m_object && impulse.length2() > (SIMD_EPSILON*SIMD_EPSILON))
- {
- m_object->activate();
- if (m_object->isStaticObject())
- {
- if (!m_cci.m_bSensor)
- m_object->setCollisionFlags(m_object->getCollisionFlags() | btCollisionObject::CF_KINEMATIC_OBJECT);
- return;
- }
-
- btVector3 pos(attachX,attachY,attachZ);
- btRigidBody* body = GetRigidBody();
- if (body)
- body->applyImpulse(impulse,pos);
-
- }
-
-}
-void CcdPhysicsController::SetActive(bool active)
-{
-}
- // reading out information from physics
-void CcdPhysicsController::GetLinearVelocity(float& linvX,float& linvY,float& linvZ)
-{
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- const btVector3& linvel = body->getLinearVelocity();
- linvX = linvel.x();
- linvY = linvel.y();
- linvZ = linvel.z();
- } else
- {
- linvX = 0.f;
- linvY = 0.f;
- linvZ = 0.f;
- }
-
-}
-
-void CcdPhysicsController::GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ)
-{
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- const btVector3& angvel= body->getAngularVelocity();
- angVelX = angvel.x();
- angVelY = angvel.y();
- angVelZ = angvel.z();
- } else
- {
- angVelX = 0.f;
- angVelY = 0.f;
- angVelZ = 0.f;
- }
-}
-
-void CcdPhysicsController::GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ)
-{
- btVector3 pos(posX,posY,posZ);
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- btVector3 linvel = body->getVelocityInLocalPoint(pos);
- linvX = linvel.x();
- linvY = linvel.y();
- linvZ = linvel.z();
- } else
- {
- linvX = 0.f;
- linvY = 0.f;
- linvZ = 0.f;
- }
-}
-void CcdPhysicsController::getReactionForce(float& forceX,float& forceY,float& forceZ)
-{
-}
-
- // dyna's that are rigidbody are free in orientation, dyna's with non-rigidbody are restricted
-void CcdPhysicsController::setRigidBody(bool rigid)
-{
- if (!rigid)
- {
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- //fake it for now
- btVector3 inertia = body->getInvInertiaDiagLocal();
- inertia[1] = 0.f;
- body->setInvInertiaDiagLocal(inertia);
- body->updateInertiaTensor();
- }
- }
-}
-
- // clientinfo for raycasts for example
-void* CcdPhysicsController::getNewClientInfo()
-{
- return m_newClientInfo;
-}
-void CcdPhysicsController::setNewClientInfo(void* clientinfo)
-{
- m_newClientInfo = clientinfo;
-}
-
-
-void CcdPhysicsController::UpdateDeactivation(float timeStep)
-{
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- body->updateDeactivation( timeStep);
- }
-}
-
-bool CcdPhysicsController::wantsSleeping()
-{
- btRigidBody* body = GetRigidBody();
- if (body)
- {
- return body->wantsSleeping();
- }
- //check it out
- return true;
-}
-
-PHY_IPhysicsController* CcdPhysicsController::GetReplica()
-{
- // This is used only to replicate Near and Radar sensor controllers
- // The replication of object physics controller is done in KX_BulletPhysicsController::GetReplica()
- CcdConstructionInfo cinfo = m_cci;
- if (m_shapeInfo)
- {
- // This situation does not normally happen
- cinfo.m_collisionShape = m_shapeInfo->CreateBulletShape(m_cci.m_margin, m_cci.m_bGimpact, !m_cci.m_bSoft);
- }
- else if (m_collisionShape)
- {
- switch (m_collisionShape->getShapeType())
- {
- case SPHERE_SHAPE_PROXYTYPE:
- {
- btSphereShape* orgShape = (btSphereShape*)m_collisionShape;
- cinfo.m_collisionShape = new btSphereShape(*orgShape);
- break;
- }
-
- case CONE_SHAPE_PROXYTYPE:
- {
- btConeShape* orgShape = (btConeShape*)m_collisionShape;
- cinfo.m_collisionShape = new btConeShape(*orgShape);
- break;
- }
-
- default:
- {
- return 0;
- }
- }
- }
-
- cinfo.m_MotionState = new DefaultMotionState();
- cinfo.m_shapeInfo = m_shapeInfo;
-
- CcdPhysicsController* replica = new CcdPhysicsController(cinfo);
- return replica;
-}
-
-///////////////////////////////////////////////////////////
-///A small utility class, DefaultMotionState
-///
-///////////////////////////////////////////////////////////
-
-DefaultMotionState::DefaultMotionState()
-{
- m_worldTransform.setIdentity();
- m_localScaling.setValue(1.f,1.f,1.f);
-}
-
-
-DefaultMotionState::~DefaultMotionState()
-{
-
-}
-
-void DefaultMotionState::getWorldPosition(float& posX,float& posY,float& posZ)
-{
- posX = m_worldTransform.getOrigin().x();
- posY = m_worldTransform.getOrigin().y();
- posZ = m_worldTransform.getOrigin().z();
-}
-
-void DefaultMotionState::getWorldScaling(float& scaleX,float& scaleY,float& scaleZ)
-{
- scaleX = m_localScaling.getX();
- scaleY = m_localScaling.getY();
- scaleZ = m_localScaling.getZ();
-}
-
-void DefaultMotionState::getWorldOrientation(float& quatIma0,float& quatIma1,float& quatIma2,float& quatReal)
-{
- btQuaternion quat = m_worldTransform.getRotation();
- quatIma0 = quat.x();
- quatIma1 = quat.y();
- quatIma2 = quat.z();
- quatReal = quat[3];
-}
-
-void DefaultMotionState::getWorldOrientation(float* ori)
-{
- m_worldTransform.getBasis().getOpenGLSubMatrix(ori);
-}
-
-void DefaultMotionState::setWorldOrientation(const float* ori)
-{
- m_worldTransform.getBasis().setFromOpenGLSubMatrix(ori);
-}
-void DefaultMotionState::setWorldPosition(float posX,float posY,float posZ)
-{
- btVector3 pos(posX,posY,posZ);
- m_worldTransform.setOrigin( pos );
-}
-
-void DefaultMotionState::setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal)
-{
- btQuaternion orn(quatIma0,quatIma1,quatIma2,quatReal);
- m_worldTransform.setRotation( orn );
-}
-
-void DefaultMotionState::calculateWorldTransformations()
-{
-
-}
-
-// Shape constructor
-std::map<RAS_MeshObject*, CcdShapeConstructionInfo*> CcdShapeConstructionInfo::m_meshShapeMap;
-
-CcdShapeConstructionInfo* CcdShapeConstructionInfo::FindMesh(RAS_MeshObject* mesh, struct DerivedMesh* dm, bool polytope)
-{
- if (polytope || dm)
- // not yet supported
- return NULL;
-
- std::map<RAS_MeshObject*,CcdShapeConstructionInfo*>::const_iterator mit = m_meshShapeMap.find(mesh);
- if (mit != m_meshShapeMap.end())
- return mit->second;
- return NULL;
-}
-
-bool CcdShapeConstructionInfo::SetMesh(RAS_MeshObject* meshobj, DerivedMesh* dm, bool polytope)
-{
- int numpolys, numverts;
-
- // assume no shape information
- // no support for dynamic change of shape yet
- assert(IsUnused());
- m_shapeType = PHY_SHAPE_NONE;
- m_meshObject = NULL;
- bool free_dm = false;
-
- // No mesh object or mesh has no polys
- if (!meshobj || meshobj->HasColliderPolygon()==false) {
- m_vertexArray.clear();
- m_polygonIndexArray.clear();
- m_triFaceArray.clear();
- m_triFaceUVcoArray.clear();
- return false;
- }
-
- if (!dm) {
- free_dm = true;
- dm = CDDM_from_mesh(meshobj->GetMesh(), NULL);
- }
-
- MVert *mvert = dm->getVertArray(dm);
- MFace *mface = dm->getTessFaceArray(dm);
- numpolys = dm->getNumTessFaces(dm);
- numverts = dm->getNumVerts(dm);
- int* index = (int*)dm->getTessFaceDataArray(dm, CD_ORIGINDEX);
- MTFace *tface = (MTFace *)dm->getTessFaceDataArray(dm, CD_MTFACE);
-
- m_shapeType = (polytope) ? PHY_SHAPE_POLYTOPE : PHY_SHAPE_MESH;
-
- /* Convert blender geometry into bullet mesh, need these vars for mapping */
- vector<bool> vert_tag_array(numverts, false);
- unsigned int tot_bt_verts= 0;
-
- if (polytope)
- {
- // Tag verts we're using
- for (int p2=0; p2<numpolys; p2++)
- {
- MFace* mf = &mface[p2];
- RAS_Polygon* poly = meshobj->GetPolygon((index)? index[p2]: p2);
-
- // only add polygons that have the collision flag set
- if (poly->IsCollider())
- {
- if (vert_tag_array[mf->v1]==false) {vert_tag_array[mf->v1]= true;tot_bt_verts++;}
- if (vert_tag_array[mf->v2]==false) {vert_tag_array[mf->v2]= true;tot_bt_verts++;}
- if (vert_tag_array[mf->v3]==false) {vert_tag_array[mf->v3]= true;tot_bt_verts++;}
- if (mf->v4 && vert_tag_array[mf->v4]==false) {vert_tag_array[mf->v4]= true;tot_bt_verts++;}
- }
- }
-
- m_vertexArray.resize(tot_bt_verts*3);
-
- btScalar *bt= &m_vertexArray[0];
-
- for (int p2=0; p2<numpolys; p2++)
- {
- MFace* mf = &mface[p2];
- RAS_Polygon* poly= meshobj->GetPolygon((index)? index[p2]: p2);
-
- // only add polygons that have the collisionflag set
- if (poly->IsCollider())
- {
- if (vert_tag_array[mf->v1]==true)
- {
- const float* vtx = mvert[mf->v1].co;
- vert_tag_array[mf->v1]= false;
- *bt++ = vtx[0];
- *bt++ = vtx[1];
- *bt++ = vtx[2];
- }
- if (vert_tag_array[mf->v2]==true)
- {
- const float* vtx = mvert[mf->v2].co;
- vert_tag_array[mf->v2]= false;
- *bt++ = vtx[0];
- *bt++ = vtx[1];
- *bt++ = vtx[2];
- }
- if (vert_tag_array[mf->v3]==true)
- {
- const float* vtx = mvert[mf->v3].co;
- vert_tag_array[mf->v3]= false;
- *bt++ = vtx[0];
- *bt++ = vtx[1];
- *bt++ = vtx[2];
- }
- if (mf->v4 && vert_tag_array[mf->v4]==true)
- {
- const float* vtx = mvert[mf->v4].co;
- vert_tag_array[mf->v4]= false;
- *bt++ = vtx[0];
- *bt++ = vtx[1];
- *bt++ = vtx[2];
- }
- }
- }
- }
- else {
- unsigned int tot_bt_tris= 0;
- vector<int> vert_remap_array(numverts, 0);
-
- // Tag verts we're using
- for (int p2=0; p2<numpolys; p2++)
- {
- MFace* mf = &mface[p2];
- RAS_Polygon* poly= meshobj->GetPolygon((index)? index[p2]: p2);
-
- // only add polygons that have the collision flag set
- if (poly->IsCollider())
- {
- if (vert_tag_array[mf->v1]==false)
- {vert_tag_array[mf->v1]= true;vert_remap_array[mf->v1]= tot_bt_verts;tot_bt_verts++;}
- if (vert_tag_array[mf->v2]==false)
- {vert_tag_array[mf->v2]= true;vert_remap_array[mf->v2]= tot_bt_verts;tot_bt_verts++;}
- if (vert_tag_array[mf->v3]==false)
- {vert_tag_array[mf->v3]= true;vert_remap_array[mf->v3]= tot_bt_verts;tot_bt_verts++;}
- if (mf->v4 && vert_tag_array[mf->v4]==false)
- {vert_tag_array[mf->v4]= true;vert_remap_array[mf->v4]= tot_bt_verts;tot_bt_verts++;}
- tot_bt_tris += (mf->v4 ? 2:1); /* a quad or a tri */
- }
- }
-
- m_vertexArray.resize(tot_bt_verts*3);
- m_polygonIndexArray.resize(tot_bt_tris);
- m_triFaceArray.resize(tot_bt_tris*3);
- btScalar *bt= &m_vertexArray[0];
- int *poly_index_pt= &m_polygonIndexArray[0];
- int *tri_pt= &m_triFaceArray[0];
-
- UVco *uv_pt = NULL;
- if (tface)
- {
- m_triFaceUVcoArray.resize(tot_bt_tris*3);
- uv_pt = &m_triFaceUVcoArray[0];
- }
- else
- m_triFaceUVcoArray.clear();
-
- for (int p2=0; p2<numpolys; p2++)
- {
- MFace* mf = &mface[p2];
- MTFace* tf = (tface) ? &tface[p2] : NULL;
- RAS_Polygon* poly= meshobj->GetPolygon((index)? index[p2]: p2);
-
- // only add polygons that have the collisionflag set
- if (poly->IsCollider())
- {
- MVert *v1= &mvert[mf->v1];
- MVert *v2= &mvert[mf->v2];
- MVert *v3= &mvert[mf->v3];
-
- // the face indicies
- tri_pt[0]= vert_remap_array[mf->v1];
- tri_pt[1]= vert_remap_array[mf->v2];
- tri_pt[2]= vert_remap_array[mf->v3];
- tri_pt= tri_pt+3;
- if (tf)
- {
- uv_pt[0].uv[0] = tf->uv[0][0];
- uv_pt[0].uv[1] = tf->uv[0][1];
- uv_pt[1].uv[0] = tf->uv[1][0];
- uv_pt[1].uv[1] = tf->uv[1][1];
- uv_pt[2].uv[0] = tf->uv[2][0];
- uv_pt[2].uv[1] = tf->uv[2][1];
- uv_pt += 3;
- }
-
- // m_polygonIndexArray
- *poly_index_pt= (index)? index[p2]: p2;
- poly_index_pt++;
-
- // the vertex location
- if (vert_tag_array[mf->v1]==true) { /* *** v1 *** */
- vert_tag_array[mf->v1]= false;
- *bt++ = v1->co[0];
- *bt++ = v1->co[1];
- *bt++ = v1->co[2];
- }
- if (vert_tag_array[mf->v2]==true) { /* *** v2 *** */
- vert_tag_array[mf->v2]= false;
- *bt++ = v2->co[0];
- *bt++ = v2->co[1];
- *bt++ = v2->co[2];
- }
- if (vert_tag_array[mf->v3]==true) { /* *** v3 *** */
- vert_tag_array[mf->v3]= false;
- *bt++ = v3->co[0];
- *bt++ = v3->co[1];
- *bt++ = v3->co[2];
- }
-
- if (mf->v4)
- {
- MVert *v4= &mvert[mf->v4];
-
- tri_pt[0]= vert_remap_array[mf->v1];
- tri_pt[1]= vert_remap_array[mf->v3];
- tri_pt[2]= vert_remap_array[mf->v4];
- tri_pt= tri_pt+3;
- if (tf)
- {
- uv_pt[0].uv[0] = tf->uv[0][0];
- uv_pt[0].uv[1] = tf->uv[0][1];
- uv_pt[1].uv[0] = tf->uv[2][0];
- uv_pt[1].uv[1] = tf->uv[2][1];
- uv_pt[2].uv[0] = tf->uv[3][0];
- uv_pt[2].uv[1] = tf->uv[3][1];
- uv_pt += 3;
- }
-
- // m_polygonIndexArray
- *poly_index_pt= (index)? index[p2]: p2;
- poly_index_pt++;
-
- // the vertex location
- if (vert_tag_array[mf->v4]==true) { /* *** v4 *** */
- vert_tag_array[mf->v4]= false;
- *bt++ = v4->co[0];
- *bt++ = v4->co[1];
- *bt++ = v4->co[2];
- }
- }
- }
- }
-
-
- /* If this ever gets confusing, print out an OBJ file for debugging */
-#if 0
- printf("# vert count %d\n", m_vertexArray.size());
- for(i=0; i<m_vertexArray.size(); i+=1) {
- printf("v %.6f %.6f %.6f\n", m_vertexArray[i].x(), m_vertexArray[i].y(), m_vertexArray[i].z());
- }
-
- printf("# face count %d\n", m_triFaceArray.size());
- for(i=0; i<m_triFaceArray.size(); i+=3) {
- printf("f %d %d %d\n", m_triFaceArray[i]+1, m_triFaceArray[i+1]+1, m_triFaceArray[i+2]+1);
- }
-#endif
-
- }
-
-#if 0
- if (validpolys==false)
- {
- // should not happen
- m_shapeType = PHY_SHAPE_NONE;
- return false;
- }
-#endif
-
- m_meshObject = meshobj;
- if (free_dm) {
- dm->release(dm);
- dm = NULL;
- }
-
- // sharing only on static mesh at present, if you change that, you must also change in FindMesh
- if (!polytope && !dm)
- {
- // triangle shape can be shared, store the mesh object in the map
- m_meshShapeMap.insert(std::pair<RAS_MeshObject*,CcdShapeConstructionInfo*>(meshobj,this));
- }
- return true;
-}
-
-#include <cstdio>
-
-/* Updates the arrays used by CreateBulletShape(),
- * take care that recalcLocalAabb() runs after CreateBulletShape is called.
- * */
-bool CcdShapeConstructionInfo::UpdateMesh(class KX_GameObject* gameobj, class RAS_MeshObject* meshobj)
-{
- int numpolys;
- int numverts;
-
- unsigned int tot_bt_tris= 0;
- unsigned int tot_bt_verts= 0;
-
- int i, j;
- int v_orig;
-
- /* Use for looping over verts in a face as a try or 2 tris */
- const int quad_verts[7]= {0,1,2, 0,2,3, -1};
- const int tri_verts[4]= {0,1,2, -1};
- const int *fv_pt;
-
- if(gameobj==NULL && meshobj==NULL)
- return false;
-
- if(m_shapeType != PHY_SHAPE_MESH)
- return false;
-
- RAS_Deformer *deformer= gameobj ? gameobj->GetDeformer():NULL;
-
- /* get the mesh from the object if not defined */
- if(meshobj==NULL) {
-
- /* modifier mesh */
- if(deformer && deformer->GetFinalMesh())
- meshobj= deformer->GetRasMesh();
-
- /* game object first mesh */
- if(meshobj==NULL) {
- if(gameobj->GetMeshCount() > 0) {
- meshobj= gameobj->GetMesh(0);
- }
- }
- }
-
- if(deformer && deformer->GetFinalMesh() && deformer->GetRasMesh() == meshobj)
- { /*
- * Derived Mesh Update
- *
- * */
-
- DerivedMesh* dm= gameobj->GetDeformer()->GetFinalMesh();
-
- MVert *mvert = dm->getVertArray(dm);
- MFace *mface = dm->getTessFaceArray(dm);
- numpolys = dm->getNumTessFaces(dm);
- numverts = dm->getNumVerts(dm);
- int* index = (int*)dm->getTessFaceDataArray(dm, CD_ORIGINDEX);
-
- MFace *mf;
- MVert *mv;
-
- int flen;
-
- if(CustomData_has_layer(&dm->faceData, CD_MTFACE))
- {
- MTFace *tface = (MTFace *)dm->getTessFaceDataArray(dm, CD_MTFACE);
- MTFace *tf;
-
- vector<bool> vert_tag_array(numverts, false);
- vector<int> vert_remap_array(numverts, 0);
-
- for(mf= mface, tf= tface, i=0; i < numpolys; mf++, tf++, i++) {
- if(tf->mode & TF_DYNAMIC)
- {
- if(mf->v4) {
- tot_bt_tris+= 2;
- flen= 4;
- } else {
- tot_bt_tris++;
- flen= 3;
- }
-
- for(j=0; j<flen; j++)
- {
- v_orig = (*(&mf->v1 + j));
-
- if(vert_tag_array[v_orig]==false)
- {
- vert_tag_array[v_orig]= true;
- vert_remap_array[v_orig]= tot_bt_verts;
- tot_bt_verts++;
- }
- }
- }
- }
-
- m_vertexArray.resize(tot_bt_verts*3);
- btScalar *bt= &m_vertexArray[0];
-
- m_triFaceArray.resize(tot_bt_tris*3);
- int *tri_pt= &m_triFaceArray[0];
-
- m_triFaceUVcoArray.resize(tot_bt_tris*3);
- UVco *uv_pt= &m_triFaceUVcoArray[0];
-
- m_polygonIndexArray.resize(tot_bt_tris);
- int *poly_index_pt= &m_polygonIndexArray[0];
-
- for(mf= mface, tf= tface, i=0; i < numpolys; mf++, tf++, i++)
- {
- if(tf->mode & TF_DYNAMIC)
- {
- int origi = (index)? index[i]: i;
-
- if(mf->v4) {
- fv_pt= quad_verts;
- *poly_index_pt++ = origi;
- *poly_index_pt++ = origi;
- flen= 4;
- } else {
- fv_pt= tri_verts;
- *poly_index_pt++ = origi;
- flen= 3;
- }
-
- for(; *fv_pt > -1; fv_pt++)
- {
- v_orig = (*(&mf->v1 + (*fv_pt)));
-
- if(vert_tag_array[v_orig])
- {
- mv= mvert + v_orig;
- *bt++ = mv->co[0];
- *bt++ = mv->co[1];
- *bt++ = mv->co[2];
-
- vert_tag_array[v_orig]= false;
- }
- *tri_pt++ = vert_remap_array[v_orig];
- uv_pt->uv[0] = tf->uv[*fv_pt][0];
- uv_pt->uv[1] = tf->uv[*fv_pt][1];
- uv_pt++;
- }
- }
- }
- }
- else {
- /* no need for a vertex mapping. simple/fast */
-
- tot_bt_verts= numverts;
-
- for(mf= mface, i=0; i < numpolys; mf++, i++) {
- tot_bt_tris += (mf->v4 ? 2:1);
- }
-
- m_vertexArray.resize(tot_bt_verts*3);
- btScalar *bt= &m_vertexArray[0];
-
- m_triFaceArray.resize(tot_bt_tris*3);
- int *tri_pt= &m_triFaceArray[0];
-
- m_polygonIndexArray.resize(tot_bt_tris);
- int *poly_index_pt= &m_polygonIndexArray[0];
-
- m_triFaceUVcoArray.clear();
-
- for(mv= mvert, i=0; i < numverts; mv++, i++) {
- *bt++ = mv->co[0]; *bt++ = mv->co[1]; *bt++ = mv->co[2];
- }
-
- for(mf= mface, i=0; i < numpolys; mf++, i++) {
- int origi = (index)? index[i]: i;
-
- if(mf->v4) {
- fv_pt= quad_verts;
- *poly_index_pt++ = origi;
- *poly_index_pt++ = origi;
- }
- else {
- fv_pt= tri_verts;
- *poly_index_pt++ = origi;
- }
-
- for(; *fv_pt > -1; fv_pt++)
- *tri_pt++ = (*(&mf->v1 + (*fv_pt)));
- }
- }
- }
- else { /*
- * RAS Mesh Update
- *
- * */
-
- /* Note!, gameobj can be NULL here */
-
- /* transverts are only used for deformed RAS_Meshes, the RAS_TexVert data
- * is too hard to get at, see below for details */
- float (*transverts)[3]= NULL;
- int transverts_tot= 0; /* with deformed meshes - should always be greater then the max orginal index, or we get crashes */
-
- if(deformer) {
- /* map locations from the deformed array
- *
- * Could call deformer->Update(); but rely on redraw updating.
- * */
- transverts= deformer->GetTransVerts(&transverts_tot);
- }
-
- // Tag verts we're using
- numpolys= meshobj->NumPolygons();
- numverts= meshobj->m_sharedvertex_map.size();
- const float *xyz;
-
-
- vector<bool> vert_tag_array(numverts, false);
- vector<int> vert_remap_array(numverts, 0);
-
- for(int p=0; p<numpolys; p++)
- {
- RAS_Polygon* poly= meshobj->GetPolygon(p);
- if (poly->IsCollider())
- {
- for(i=0; i < poly->VertexCount(); i++)
- {
- v_orig= poly->GetVertex(i)->getOrigIndex();
- if(vert_tag_array[v_orig]==false)
- {
- vert_tag_array[v_orig]= true;
- vert_remap_array[v_orig]= tot_bt_verts;
- tot_bt_verts++;
- }
- }
- tot_bt_tris += (poly->VertexCount()==4 ? 2:1);
- }
- }
-
- m_vertexArray.resize(tot_bt_verts*3);
- btScalar *bt= &m_vertexArray[0];
-
- m_triFaceArray.resize(tot_bt_tris*3);
- int *tri_pt= &m_triFaceArray[0];
-
- /* cant be used for anything useful in this case, since we dont rely on the original mesh
- * will just be an array like pythons range(tot_bt_tris) */
- m_polygonIndexArray.resize(tot_bt_tris);
-
-
- for(int p=0; p<numpolys; p++)
- {
- RAS_Polygon* poly= meshobj->GetPolygon(p);
-
- if (poly->IsCollider())
- {
- /* quad or tri loop */
- fv_pt= (poly->VertexCount()==3 ? tri_verts:quad_verts);
-
- for(; *fv_pt > -1; fv_pt++)
- {
- v_orig= poly->GetVertex(*fv_pt)->getOrigIndex();
-
- if(vert_tag_array[v_orig])
- {
- if(transverts) {
- /* deformed mesh, using RAS_TexVert locations would be too troublesome
- * because they are use the gameob as a hash in the material slot */
- *bt++ = transverts[v_orig][0];
- *bt++ = transverts[v_orig][1];
- *bt++ = transverts[v_orig][2];
- }
- else {
- /* static mesh python may have modified */
- xyz= meshobj->GetVertexLocation( v_orig );
- *bt++ = xyz[0];
- *bt++ = xyz[1];
- *bt++ = xyz[2];
- }
-
- vert_tag_array[v_orig]= false;
- }
-
- *tri_pt++ = vert_remap_array[v_orig];
- }
- }
-
- m_polygonIndexArray[p]= p; /* dumb counting */
- }
- }
-
-#if 0
- /* needs #include <cstdio> */
- printf("# vert count %d\n", m_vertexArray.size());
- for(int i=0; i<m_vertexArray.size(); i+=3) {
- printf("v %.6f %.6f %.6f\n", m_vertexArray[i], m_vertexArray[i+1], m_vertexArray[i+2]);
- }
-
- printf("# face count %d\n", m_triFaceArray.size());
- for(int i=0; i<m_triFaceArray.size(); i+=3) {
- printf("f %d %d %d\n", m_triFaceArray[i]+1, m_triFaceArray[i+1]+1, m_triFaceArray[i+2]+1);
- }
-#endif
-
- /* force recreation of the m_unscaledShape.
- * If this has multiple users we cant delete */
- if(m_unscaledShape) {
- // dont free now so it can re-allocate under the same location and not break pointers.
- // DeleteBulletShape(m_unscaledShape);
- m_forceReInstance= true;
- }
-
- m_meshObject= meshobj;
-
- return true;
-}
-
-
-
-bool CcdShapeConstructionInfo::SetProxy(CcdShapeConstructionInfo* shapeInfo)
-{
- if (shapeInfo == NULL)
- return false;
- // no support for dynamic change
- assert(IsUnused());
- m_shapeType = PHY_SHAPE_PROXY;
- m_shapeProxy = shapeInfo;
- return true;
-}
-
-btCollisionShape* CcdShapeConstructionInfo::CreateBulletShape(btScalar margin, bool useGimpact, bool useBvh)
-{
- btCollisionShape* collisionShape = 0;
- btCompoundShape* compoundShape = 0;
-
- if (m_shapeType == PHY_SHAPE_PROXY && m_shapeProxy != NULL)
- return m_shapeProxy->CreateBulletShape(margin, useGimpact, useBvh);
-
- switch (m_shapeType)
- {
- default:
- break;
-
- case PHY_SHAPE_BOX:
- collisionShape = new btBoxShape(m_halfExtend);
- collisionShape->setMargin(margin);
- break;
-
- case PHY_SHAPE_SPHERE:
- collisionShape = new btSphereShape(m_radius);
- collisionShape->setMargin(margin);
- break;
-
- case PHY_SHAPE_CYLINDER:
- collisionShape = new btCylinderShapeZ(m_halfExtend);
- collisionShape->setMargin(margin);
- break;
-
- case PHY_SHAPE_CONE:
- collisionShape = new btConeShapeZ(m_radius, m_height);
- collisionShape->setMargin(margin);
- break;
-
- case PHY_SHAPE_POLYTOPE:
- collisionShape = new btConvexHullShape(&m_vertexArray[0], m_vertexArray.size()/3, 3*sizeof(btScalar));
- collisionShape->setMargin(margin);
- break;
-
- case PHY_SHAPE_MESH:
- // Let's use the latest btScaledBvhTriangleMeshShape: it allows true sharing of
- // triangle mesh information between duplicates => drastic performance increase when
- // duplicating complex mesh objects.
- // BUT it causes a small performance decrease when sharing is not required:
- // 9 multiplications/additions and one function call for each triangle that passes the mid phase filtering
- // One possible optimization is to use directly the btBvhTriangleMeshShape when the scale is 1,1,1
- // and btScaledBvhTriangleMeshShape otherwise.
- if (useGimpact)
- {
- btTriangleIndexVertexArray* indexVertexArrays = new btTriangleIndexVertexArray(
- m_polygonIndexArray.size(),
- &m_triFaceArray[0],
- 3*sizeof(int),
- m_vertexArray.size()/3,
- &m_vertexArray[0],
- 3*sizeof(btScalar)
- );
-
- btGImpactMeshShape* gimpactShape = new btGImpactMeshShape(indexVertexArrays);
- gimpactShape->setMargin(margin);
- collisionShape = gimpactShape;
- gimpactShape->updateBound();
-
- } else
- {
- if (!m_unscaledShape || m_forceReInstance)
- {
-
- btTriangleIndexVertexArray* indexVertexArrays = 0;
-
- ///enable welding, only for the objects that need it (such as soft bodies)
- if (0.f != m_weldingThreshold1)
- {
- btTriangleMesh* collisionMeshData = new btTriangleMesh(true,false);
- collisionMeshData->m_weldingThreshold = m_weldingThreshold1;
- bool removeDuplicateVertices=true;
- // m_vertexArray not in multiple of 3 anymore, use m_triFaceArray
- for(unsigned int i=0; i<m_triFaceArray.size(); i+=3) {
- btScalar *bt = &m_vertexArray[3*m_triFaceArray[i]];
- btVector3 v1(bt[0], bt[1], bt[2]);
- bt = &m_vertexArray[3*m_triFaceArray[i+1]];
- btVector3 v2(bt[0], bt[1], bt[2]);
- bt = &m_vertexArray[3*m_triFaceArray[i+2]];
- btVector3 v3(bt[0], bt[1], bt[2]);
- collisionMeshData->addTriangle(v1, v2, v3, removeDuplicateVertices);
- }
- indexVertexArrays = collisionMeshData;
-
- } else
- {
- indexVertexArrays = new btTriangleIndexVertexArray(
- m_polygonIndexArray.size(),
- &m_triFaceArray[0],
- 3*sizeof(int),
- m_vertexArray.size()/3,
- &m_vertexArray[0],
- 3*sizeof(btScalar));
- }
-
- // this shape will be shared and not deleted until shapeInfo is deleted
-
- // for UpdateMesh, reuse the last memory location so instancing wont crash.
- if(m_unscaledShape) {
- DeleteBulletShape(m_unscaledShape, false);
- m_unscaledShape->~btBvhTriangleMeshShape();
- m_unscaledShape = new(m_unscaledShape) btBvhTriangleMeshShape( indexVertexArrays, true, useBvh );
- } else {
- m_unscaledShape = new btBvhTriangleMeshShape( indexVertexArrays, true, useBvh );
- }
- m_forceReInstance= false;
- } else if (useBvh && m_unscaledShape->getOptimizedBvh() == NULL) {
- // the existing unscaledShape was not build with Bvh, do it now
- m_unscaledShape->buildOptimizedBvh();
- }
- collisionShape = new btScaledBvhTriangleMeshShape(m_unscaledShape, btVector3(1.0f,1.0f,1.0f));
- collisionShape->setMargin(margin);
- }
- break;
-
- case PHY_SHAPE_COMPOUND:
- if (m_shapeArray.size() > 0)
- {
- compoundShape = new btCompoundShape();
- for (std::vector<CcdShapeConstructionInfo*>::iterator sit = m_shapeArray.begin();
- sit != m_shapeArray.end();
- sit++)
- {
- collisionShape = (*sit)->CreateBulletShape(margin, useGimpact, useBvh);
- if (collisionShape)
- {
- collisionShape->setLocalScaling((*sit)->m_childScale);
- compoundShape->addChildShape((*sit)->m_childTrans, collisionShape);
- }
- }
- collisionShape = compoundShape;
- }
- }
- return collisionShape;
-}
-
-void CcdShapeConstructionInfo::AddShape(CcdShapeConstructionInfo* shapeInfo)
-{
- m_shapeArray.push_back(shapeInfo);
- shapeInfo->AddRef();
-}
-
-CcdShapeConstructionInfo::~CcdShapeConstructionInfo()
-{
- for (std::vector<CcdShapeConstructionInfo*>::iterator sit = m_shapeArray.begin();
- sit != m_shapeArray.end();
- sit++)
- {
- (*sit)->Release();
- }
- m_shapeArray.clear();
- if (m_unscaledShape)
- {
- DeleteBulletShape(m_unscaledShape, true);
- }
- m_vertexArray.clear();
- if (m_shapeType == PHY_SHAPE_MESH && m_meshObject != NULL)
- {
- std::map<RAS_MeshObject*,CcdShapeConstructionInfo*>::iterator mit = m_meshShapeMap.find(m_meshObject);
- if (mit != m_meshShapeMap.end() && mit->second == this)
- {
- m_meshShapeMap.erase(mit);
- }
- }
- if (m_shapeType == PHY_SHAPE_PROXY && m_shapeProxy != NULL)
- {
- m_shapeProxy->Release();
- }
-}
-
-
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsController.h b/source/gameengine/Physics/Bullet/CcdPhysicsController.h
deleted file mode 100644
index 3bbe17459c9..00000000000
--- a/source/gameengine/Physics/Bullet/CcdPhysicsController.h
+++ /dev/null
@@ -1,619 +0,0 @@
-/*
-Bullet Continuous Collision Detection and Physics Library
-Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
-
-This software is provided 'as-is', without any express or implied warranty.
-In no event will the authors be held liable for any damages arising from the use of this software.
-Permission is granted to anyone to use this software for any purpose,
-including commercial applications, and to alter it and redistribute it freely,
-subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
-2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
-3. This notice may not be removed or altered from any source distribution.
-*/
-
-
-#ifndef BULLET2_PHYSICSCONTROLLER_H
-#define BULLET2_PHYSICSCONTROLLER_H
-
-#include <vector>
-#include <map>
-
-#include "PHY_IPhysicsController.h"
-
-/// PHY_IPhysicsController is the abstract simplified Interface to a physical object.
-/// It contains the IMotionState and IDeformableMesh Interfaces.
-#include "btBulletDynamicsCommon.h"
-#include "LinearMath/btTransform.h"
-
-#include "PHY_IMotionState.h"
-
-extern float gDeactivationTime;
-extern float gLinearSleepingTreshold;
-extern float gAngularSleepingTreshold;
-extern bool gDisableDeactivation;
-class CcdPhysicsEnvironment;
-class btMotionState;
-class RAS_MeshObject;
-struct DerivedMesh;
-class btCollisionShape;
-
-
-#define CCD_BSB_SHAPE_MATCHING 2
-#define CCD_BSB_BENDING_CONSTRAINTS 8
-#define CCD_BSB_AERO_VPOINT 16 /* aero model, Vertex normals are oriented toward velocity*/
-#define CCD_BSB_AERO_VTWOSIDE 32 /* aero model, Vertex normals are flipped to match velocity */
-
-/* BulletSoftBody.collisionflags */
-#define CCD_BSB_COL_SDF_RS 2 /* SDF based rigid vs soft */
-#define CCD_BSB_COL_CL_RS 4 /* Cluster based rigid vs soft */
-#define CCD_BSB_COL_CL_SS 8 /* Cluster based soft vs soft */
-#define CCD_BSB_COL_VF_SS 16 /* Vertex/Face based soft vs soft */
-
-
-// Shape contructor
-// It contains all the information needed to create a simple bullet shape at runtime
-class CcdShapeConstructionInfo
-{
-public:
- struct UVco
- {
- float uv[2];
- };
-
- static CcdShapeConstructionInfo* FindMesh(class RAS_MeshObject* mesh, struct DerivedMesh* dm, bool polytope);
-
- CcdShapeConstructionInfo() :
- m_shapeType(PHY_SHAPE_NONE),
- m_radius(1.0),
- m_height(1.0),
- m_halfExtend(0.f,0.f,0.f),
- m_childScale(1.0f,1.0f,1.0f),
- m_userData(NULL),
- m_refCount(1),
- m_meshObject(NULL),
- m_unscaledShape(NULL),
- m_forceReInstance(false),
- m_weldingThreshold1(0.f),
- m_shapeProxy(NULL)
- {
- m_childTrans.setIdentity();
- }
-
- ~CcdShapeConstructionInfo();
-
- CcdShapeConstructionInfo* AddRef()
- {
- m_refCount++;
- return this;
- }
-
- int Release()
- {
- if (--m_refCount > 0)
- return m_refCount;
- delete this;
- return 0;
- }
-
- bool IsUnused(void)
- {
- return (m_meshObject==NULL && m_shapeArray.size() == 0 && m_shapeProxy == NULL);
- }
-
- void AddShape(CcdShapeConstructionInfo* shapeInfo);
-
- btTriangleMeshShape* GetMeshShape(void)
- {
- return (m_unscaledShape);
- }
- CcdShapeConstructionInfo* GetChildShape(int i)
- {
- if (i < 0 || i >= (int)m_shapeArray.size())
- return NULL;
-
- return m_shapeArray.at(i);
- }
- int FindChildShape(CcdShapeConstructionInfo* shapeInfo, void* userData)
- {
- if (shapeInfo == NULL)
- return -1;
- for (int i=0; i<(int)m_shapeArray.size(); i++)
- {
- CcdShapeConstructionInfo* childInfo = m_shapeArray.at(i);
- if ((userData == NULL || userData == childInfo->m_userData) &&
- (childInfo == shapeInfo ||
- (childInfo->m_shapeType == PHY_SHAPE_PROXY &&
- childInfo->m_shapeProxy == shapeInfo)))
- return i;
- }
- return -1;
- }
-
- bool RemoveChildShape(int i)
- {
- if (i < 0 || i >= (int)m_shapeArray.size())
- return false;
- m_shapeArray.at(i)->Release();
- if (i < (int)m_shapeArray.size()-1)
- m_shapeArray[i] = m_shapeArray.back();
- m_shapeArray.pop_back();
- return true;
- }
-
- bool SetMesh(class RAS_MeshObject* mesh, struct DerivedMesh* dm, bool polytope);
- RAS_MeshObject* GetMesh(void)
- {
- return m_meshObject;
- }
-
- bool UpdateMesh(class KX_GameObject* gameobj, class RAS_MeshObject* mesh);
-
-
- bool SetProxy(CcdShapeConstructionInfo* shapeInfo);
- CcdShapeConstructionInfo* GetProxy(void)
- {
- return m_shapeProxy;
- }
-
- btCollisionShape* CreateBulletShape(btScalar margin, bool useGimpact=false, bool useBvh=true);
-
- // member variables
- PHY_ShapeType m_shapeType;
- btScalar m_radius;
- btScalar m_height;
- btVector3 m_halfExtend;
- btTransform m_childTrans;
- btVector3 m_childScale;
- void* m_userData;
- btAlignedObjectArray<btScalar> m_vertexArray; // Contains both vertex array for polytope shape and
- // triangle array for concave mesh shape. Each vertex is 3 consecutive values
- // In this case a triangle is made of 3 consecutive points
- std::vector<int> m_polygonIndexArray; // Contains the array of polygon index in the
- // original mesh that correspond to shape triangles.
- // only set for concave mesh shape.
-
- std::vector<int> m_triFaceArray; // Contains an array of triplets of face indicies
- // quads turn into 2 tris
-
- std::vector<UVco> m_triFaceUVcoArray; // Contains an array of pair of UV coordinate for each vertex of faces
- // quads turn into 2 tris
-
- void setVertexWeldingThreshold1(float threshold)
- {
- m_weldingThreshold1 = threshold*threshold;
- }
-protected:
- static std::map<RAS_MeshObject*, CcdShapeConstructionInfo*> m_meshShapeMap;
- int m_refCount; // this class is shared between replicas
- // keep track of users so that we can release it
- RAS_MeshObject* m_meshObject; // Keep a pointer to the original mesh
- btBvhTriangleMeshShape* m_unscaledShape;// holds the shared unscale BVH mesh shape,
- // the actual shape is of type btScaledBvhTriangleMeshShape
- std::vector<CcdShapeConstructionInfo*> m_shapeArray; // for compound shapes
- bool m_forceReInstance; //use gimpact for concave dynamic/moving collision detection
- float m_weldingThreshold1; //welding closeby vertices together can improve softbody stability etc.
- CcdShapeConstructionInfo* m_shapeProxy; // only used for PHY_SHAPE_PROXY, pointer to actual shape info
-
-
-#ifdef WITH_CXX_GUARDEDALLOC
-public:
- void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:CcdShapeConstructionInfo"); }
- void operator delete( void *mem ) { MEM_freeN(mem); }
-#endif
-};
-
-struct CcdConstructionInfo
-{
-
- ///CollisionFilterGroups provides some optional usage of basic collision filtering
- ///this is done during broadphase, so very early in the pipeline
- ///more advanced collision filtering should be done in btCollisionDispatcher::NeedsCollision
- enum CollisionFilterGroups
- {
- DefaultFilter = 1,
- StaticFilter = 2,
- KinematicFilter = 4,
- DebrisFilter = 8,
- SensorFilter = 16,
- AllFilter = DefaultFilter | StaticFilter | KinematicFilter | DebrisFilter | SensorFilter,
- };
-
-
- CcdConstructionInfo()
- : m_localInertiaTensor(1.f, 1.f, 1.f),
- m_gravity(0,0,0),
- m_scaling(1.f,1.f,1.f),
- m_mass(0.f),
- m_clamp_vel_min(-1.f),
- m_clamp_vel_max(-1.f),
- m_restitution(0.1f),
- m_friction(0.5f),
- m_linearDamping(0.1f),
- m_angularDamping(0.1f),
- m_margin(0.06f),
- m_gamesoftFlag(0),
- m_collisionFlags(0),
- m_bRigid(false),
- m_bSoft(false),
- m_bSensor(false),
- m_bGimpact(false),
- m_collisionFilterGroup(DefaultFilter),
- m_collisionFilterMask(AllFilter),
- m_collisionShape(0),
- m_MotionState(0),
- m_shapeInfo(0),
- m_physicsEnv(0),
- m_inertiaFactor(1.f),
- m_do_anisotropic(false),
- m_anisotropicFriction(1.f,1.f,1.f),
- m_contactProcessingThreshold(1e10)
- {
- }
-
- btVector3 m_localInertiaTensor;
- btVector3 m_gravity;
- btVector3 m_scaling;
- btScalar m_mass;
- btScalar m_clamp_vel_min;
- btScalar m_clamp_vel_max;
- btScalar m_restitution;
- btScalar m_friction;
- btScalar m_linearDamping;
- btScalar m_angularDamping;
- btScalar m_margin;
-
- ////////////////////
- int m_gamesoftFlag;
- float m_soft_linStiff; /* linear stiffness 0..1 */
- float m_soft_angStiff; /* angular stiffness 0..1 */
- float m_soft_volume; /* volume preservation 0..1 */
-
- int m_soft_viterations; /* Velocities solver iterations */
- int m_soft_piterations; /* Positions solver iterations */
- int m_soft_diterations; /* Drift solver iterations */
- int m_soft_citerations; /* Cluster solver iterations */
-
- float m_soft_kSRHR_CL; /* Soft vs rigid hardness [0,1] (cluster only) */
- float m_soft_kSKHR_CL; /* Soft vs kinetic hardness [0,1] (cluster only) */
- float m_soft_kSSHR_CL; /* Soft vs soft hardness [0,1] (cluster only) */
- float m_soft_kSR_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
-
- float m_soft_kSK_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
- float m_soft_kSS_SPLT_CL; /* Soft vs rigid impulse split [0,1] (cluster only) */
- float m_soft_kVCF; /* Velocities correction factor (Baumgarte) */
- float m_soft_kDP; /* Damping coefficient [0,1] */
-
- float m_soft_kDG; /* Drag coefficient [0,+inf] */
- float m_soft_kLF; /* Lift coefficient [0,+inf] */
- float m_soft_kPR; /* Pressure coefficient [-inf,+inf] */
- float m_soft_kVC; /* Volume conversation coefficient [0,+inf] */
-
- float m_soft_kDF; /* Dynamic friction coefficient [0,1] */
- float m_soft_kMT; /* Pose matching coefficient [0,1] */
- float m_soft_kCHR; /* Rigid contacts hardness [0,1] */
- float m_soft_kKHR; /* Kinetic contacts hardness [0,1] */
-
- float m_soft_kSHR; /* Soft contacts hardness [0,1] */
- float m_soft_kAHR; /* Anchors hardness [0,1] */
- int m_soft_collisionflags; /* Vertex/Face or Signed Distance Field(SDF) or Clusters, Soft versus Soft or Rigid */
- int m_soft_numclusteriterations; /* number of iterations to refine collision clusters*/
-///////////////////
-
-
-
- int m_collisionFlags;
- bool m_bRigid;
- bool m_bSoft;
- bool m_bSensor;
- bool m_bGimpact; // use Gimpact for mesh body
-
- ///optional use of collision group/mask:
- ///only collision with object goups that match the collision mask.
- ///this is very basic early out. advanced collision filtering should be
- ///done in the btCollisionDispatcher::NeedsCollision and NeedsResponse
- ///both values default to 1
- short int m_collisionFilterGroup;
- short int m_collisionFilterMask;
-
- ///these pointers are used as argument passing for the CcdPhysicsController constructor
- ///and not anymore after that
- class btCollisionShape* m_collisionShape;
- class PHY_IMotionState* m_MotionState;
- class CcdShapeConstructionInfo* m_shapeInfo;
-
- CcdPhysicsEnvironment* m_physicsEnv; //needed for self-replication
- float m_inertiaFactor;//tweak the inertia (hooked up to Blender 'formfactor'
- bool m_do_anisotropic;
- btVector3 m_anisotropicFriction;
-
- bool m_do_fh; ///< Should the object have a linear Fh spring?
- bool m_do_rot_fh; ///< Should the object have an angular Fh spring?
- btScalar m_fh_spring; ///< Spring constant (both linear and angular)
- btScalar m_fh_damping; ///< Damping factor (linear and angular) in range [0, 1]
- btScalar m_fh_distance; ///< The range above the surface where Fh is active.
- bool m_fh_normal; ///< Should the object slide off slopes?
- float m_radius;//for fh backwards compatibility
-
- ///m_contactProcessingThreshold allows to process contact points with positive distance
- ///normally only contacts with negative distance (penetration) are solved
- ///however, rigid body stacking is more stable when positive contacts are still passed into the constraint solver
- ///this might sometimes lead to collisions with 'internal edges' such as a sliding character controller
- ///so disable/set m_contactProcessingThreshold to zero for sliding characters etc.
- float m_contactProcessingThreshold;///< Process contacts with positive distance in range [0..INF]
-
-};
-
-
-class btRigidBody;
-class btCollisionObject;
-class btSoftBody;
-
-///CcdPhysicsController is a physics object that supports continuous collision detection and time of impact based physics resolution.
-class CcdPhysicsController : public PHY_IPhysicsController
-{
-protected:
- btCollisionObject* m_object;
-
-
- class PHY_IMotionState* m_MotionState;
- btMotionState* m_bulletMotionState;
- class btCollisionShape* m_collisionShape;
- class CcdShapeConstructionInfo* m_shapeInfo;
-
- friend class CcdPhysicsEnvironment; // needed when updating the controller
-
- //some book keeping for replication
- bool m_softbodyMappingDone;
- bool m_softBodyTransformInitialized;
- bool m_prototypeTransformInitialized;
- btTransform m_softbodyStartTrans;
-
-
- void* m_newClientInfo;
- int m_registerCount; // needed when multiple sensors use the same controller
- CcdConstructionInfo m_cci;//needed for replication
-
- CcdPhysicsController* m_parentCtrl;
-
- void GetWorldOrientation(btMatrix3x3& mat);
-
- void CreateRigidbody();
- bool CreateSoftbody();
-
- bool Register() {
- return (m_registerCount++ == 0) ? true : false;
- }
- bool Unregister() {
- return (--m_registerCount == 0) ? true : false;
- }
-
- void setWorldOrientation(const btMatrix3x3& mat);
- void forceWorldTransform(const btMatrix3x3& mat, const btVector3& pos);
-
- public:
-
- int m_collisionDelay;
-
-
- CcdPhysicsController (const CcdConstructionInfo& ci);
-
- bool DeleteControllerShape();
- bool ReplaceControllerShape(btCollisionShape *newShape);
-
- virtual ~CcdPhysicsController();
-
- CcdConstructionInfo& getConstructionInfo()
- {
- return m_cci;
- }
- const CcdConstructionInfo& getConstructionInfo() const
- {
- return m_cci;
- }
-
-
- btRigidBody* GetRigidBody();
- btCollisionObject* GetCollisionObject();
- btSoftBody* GetSoftBody();
-
- CcdShapeConstructionInfo* GetShapeInfo() { return m_shapeInfo; }
-
- btCollisionShape* GetCollisionShape() {
- return m_object->getCollisionShape();
- }
- ////////////////////////////////////
- // PHY_IPhysicsController interface
- ////////////////////////////////////
-
-
- /**
- SynchronizeMotionStates ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
- */
- virtual bool SynchronizeMotionStates(float time);
- /**
- WriteMotionStateToDynamics ynchronizes dynas, kinematic and deformable entities (and do 'late binding')
- */
-
- virtual void WriteMotionStateToDynamics(bool nondynaonly);
- virtual void WriteDynamicsToMotionState();
-
- // controller replication
- virtual void PostProcessReplica(class PHY_IMotionState* motionstate,class PHY_IPhysicsController* parentctrl);
- virtual void SetPhysicsEnvironment(class PHY_IPhysicsEnvironment *env);
-
- // kinematic methods
- virtual void RelativeTranslate(float dlocX,float dlocY,float dlocZ,bool local);
- virtual void RelativeRotate(const float drot[9],bool local);
- virtual void getOrientation(float &quatImag0,float &quatImag1,float &quatImag2,float &quatReal);
- virtual void setOrientation(float quatImag0,float quatImag1,float quatImag2,float quatReal);
- virtual void setPosition(float posX,float posY,float posZ);
- virtual void getPosition(PHY__Vector3& pos) const;
-
- virtual void setScaling(float scaleX,float scaleY,float scaleZ);
-
- // physics methods
- virtual void ApplyTorque(float torqueX,float torqueY,float torqueZ,bool local);
- virtual void ApplyForce(float forceX,float forceY,float forceZ,bool local);
- virtual void SetAngularVelocity(float ang_velX,float ang_velY,float ang_velZ,bool local);
- virtual void SetLinearVelocity(float lin_velX,float lin_velY,float lin_velZ,bool local);
- virtual void applyImpulse(float attachX,float attachY,float attachZ, float impulseX,float impulseY,float impulseZ);
- virtual void SetActive(bool active);
-
- // reading out information from physics
- virtual void GetLinearVelocity(float& linvX,float& linvY,float& linvZ);
- virtual void GetAngularVelocity(float& angVelX,float& angVelY,float& angVelZ);
- virtual void GetVelocity(const float posX,const float posY,const float posZ,float& linvX,float& linvY,float& linvZ);
- virtual void getReactionForce(float& forceX,float& forceY,float& forceZ);
-
- // dyna's that are rigidbody are free in orientation, dyna's with non-rigidbody are restricted
- virtual void setRigidBody(bool rigid);
-
-
- virtual void resolveCombinedVelocities(float linvelX,float linvelY,float linvelZ,float angVelX,float angVelY,float angVelZ);
-
- // clientinfo for raycasts for example
- virtual void* getNewClientInfo();
- virtual void setNewClientInfo(void* clientinfo);
- virtual PHY_IPhysicsController* GetReplica();
-
- ///There should be no 'SetCollisionFilterGroup' method, as changing this during run-time is will result in errors
- short int GetCollisionFilterGroup() const
- {
- return m_cci.m_collisionFilterGroup;
- }
- ///There should be no 'SetCollisionFilterGroup' method, as changing this during run-time is will result in errors
- short int GetCollisionFilterMask() const
- {
- return m_cci.m_collisionFilterMask;
- }
-
- virtual void calcXform() {} ;
- virtual void SetMargin(float margin)
- {
- if (m_collisionShape)
- m_collisionShape->setMargin(btScalar(margin));
- }
- virtual float GetMargin() const
- {
- return (m_collisionShape) ? m_collisionShape->getMargin() : 0.f;
- }
- virtual float GetRadius() const
- {
- // this is not the actual shape radius, it's only used for Fh support
- return m_cci.m_radius;
- }
- virtual void SetRadius(float margin)
- {
- if (m_collisionShape && m_collisionShape->getShapeType() == SPHERE_SHAPE_PROXYTYPE)
- {
- btSphereShape* sphereShape = static_cast<btSphereShape*>(m_collisionShape);
- sphereShape->setUnscaledRadius(margin);
- }
- m_cci.m_radius = margin;
- }
-
- // velocity clamping
- virtual void SetLinVelocityMin(float val)
- {
- m_cci.m_clamp_vel_min= val;
- }
- virtual float GetLinVelocityMin() const
- {
- return m_cci.m_clamp_vel_min;
- }
- virtual void SetLinVelocityMax(float val)
- {
- m_cci.m_clamp_vel_max= val;
- }
- virtual float GetLinVelocityMax() const
- {
- return m_cci.m_clamp_vel_max;
- }
-
- bool wantsSleeping();
-
- void UpdateDeactivation(float timeStep);
-
- void SetCenterOfMassTransform(btTransform& xform);
-
- static btTransform& GetTransformFromMotionState(PHY_IMotionState* motionState);
-
- void setAabb(const btVector3& aabbMin,const btVector3& aabbMax);
-
-
- class PHY_IMotionState* GetMotionState()
- {
- return m_MotionState;
- }
-
- const class PHY_IMotionState* GetMotionState() const
- {
- return m_MotionState;
- }
-
- class CcdPhysicsEnvironment* GetPhysicsEnvironment()
- {
- return m_cci.m_physicsEnv;
- }
-
- void setParentCtrl(CcdPhysicsController* parentCtrl)
- {
- m_parentCtrl = parentCtrl;
- }
-
- CcdPhysicsController* getParentCtrl()
- {
- return m_parentCtrl;
- }
-
- const CcdPhysicsController* getParentCtrl() const
- {
- return m_parentCtrl;
- }
-
-
-#ifdef WITH_CXX_GUARDEDALLOC
-public:
- void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:CcdPhysicsController"); }
- void operator delete( void *mem ) { MEM_freeN(mem); }
-#endif
-};
-
-
-
-
-///DefaultMotionState implements standard motionstate, using btTransform
-class DefaultMotionState : public PHY_IMotionState
-
-{
- public:
- DefaultMotionState();
-
- virtual ~DefaultMotionState();
-
- virtual void getWorldPosition(float& posX,float& posY,float& posZ);
- virtual void getWorldScaling(float& scaleX,float& scaleY,float& scaleZ);
- virtual void getWorldOrientation(float& quatIma0,float& quatIma1,float& quatIma2,float& quatReal);
-
- virtual void setWorldPosition(float posX,float posY,float posZ);
- virtual void setWorldOrientation(float quatIma0,float quatIma1,float quatIma2,float quatReal);
- virtual void getWorldOrientation(float* ori);
- virtual void setWorldOrientation(const float* ori);
-
- virtual void calculateWorldTransformations();
-
- btTransform m_worldTransform;
- btVector3 m_localScaling;
-
-
-#ifdef WITH_CXX_GUARDEDALLOC
-public:
- void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:DefaultMotionState"); }
- void operator delete( void *mem ) { MEM_freeN(mem); }
-#endif
-};
-
-
-#endif //BULLET2_PHYSICSCONTROLLER_H
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp
deleted file mode 100644
index 477a2c35d4f..00000000000
--- a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.cpp
+++ /dev/null
@@ -1,2721 +0,0 @@
-/*
-Bullet Continuous Collision Detection and Physics Library
-Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
-
-This software is provided 'as-is', without any express or implied warranty.
-In no event will the authors be held liable for any damages arising from the use of this software.
-Permission is granted to anyone to use this software for any purpose,
-including commercial applications, and to alter it and redistribute it freely,
-subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
-2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
-3. This notice may not be removed or altered from any source distribution.
-*/
-
-
-
-
-#include "CcdPhysicsEnvironment.h"
-#include "CcdPhysicsController.h"
-#include "CcdGraphicController.h"
-
-#include <algorithm>
-#include "btBulletDynamicsCommon.h"
-#include "LinearMath/btIDebugDraw.h"
-#include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h"
-#include "BulletSoftBody/btSoftRigidDynamicsWorld.h"
-#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
-#include "BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h"
-
-//profiling/timings
-#include "LinearMath/btQuickprof.h"
-
-
-#include "PHY_IMotionState.h"
-#include "KX_GameObject.h"
-#include "RAS_MeshObject.h"
-#include "RAS_Polygon.h"
-#include "RAS_TexVert.h"
-
-#define CCD_CONSTRAINT_DISABLE_LINKED_COLLISION 0x80
-
-bool useIslands = true;
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
-#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
-#include "BulletDynamics/Vehicle/btVehicleRaycaster.h"
-#include "BulletDynamics/Vehicle/btWheelInfo.h"
-#include "PHY_IVehicle.h"
-btRaycastVehicle::btVehicleTuning gTuning;
-
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-#include "LinearMath/btAabbUtil2.h"
-#include "MT_Matrix4x4.h"
-#include "MT_Vector3.h"
-#include "GL/glew.h"
-
-#ifdef WIN32
-void DrawRasterizerLine(const float* from,const float* to,int color);
-#endif
-
-
-#include "BulletDynamics/ConstraintSolver/btContactConstraint.h"
-
-
-#include <stdio.h>
-#include <string.h> // for memset
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
-class WrapperVehicle : public PHY_IVehicle
-{
-
- btRaycastVehicle* m_vehicle;
- PHY_IPhysicsController* m_chassis;
-
-public:
-
- WrapperVehicle(btRaycastVehicle* vehicle,PHY_IPhysicsController* chassis)
- :m_vehicle(vehicle),
- m_chassis(chassis)
- {
- }
-
- btRaycastVehicle* GetVehicle()
- {
- return m_vehicle;
- }
-
- PHY_IPhysicsController* GetChassis()
- {
- return m_chassis;
- }
-
- virtual void AddWheel(
- PHY_IMotionState* motionState,
- PHY__Vector3 connectionPoint,
- PHY__Vector3 downDirection,
- PHY__Vector3 axleDirection,
- float suspensionRestLength,
- float wheelRadius,
- bool hasSteering
- )
- {
- btVector3 connectionPointCS0(connectionPoint[0],connectionPoint[1],connectionPoint[2]);
- btVector3 wheelDirectionCS0(downDirection[0],downDirection[1],downDirection[2]);
- btVector3 wheelAxle(axleDirection[0],axleDirection[1],axleDirection[2]);
-
-
- btWheelInfo& info = m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxle,
- suspensionRestLength,wheelRadius,gTuning,hasSteering);
- info.m_clientInfo = motionState;
-
- }
-
- void SyncWheels()
- {
- int numWheels = GetNumWheels();
- int i;
- for (i=0;i<numWheels;i++)
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(i);
- PHY_IMotionState* motionState = (PHY_IMotionState*)info.m_clientInfo ;
- // m_vehicle->updateWheelTransformsWS(info,false);
- m_vehicle->updateWheelTransform(i,false);
- btTransform trans = m_vehicle->getWheelInfo(i).m_worldTransform;
- btQuaternion orn = trans.getRotation();
- const btVector3& pos = trans.getOrigin();
- motionState->setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]);
- motionState->setWorldPosition(pos.x(),pos.y(),pos.z());
-
- }
- }
-
- virtual int GetNumWheels() const
- {
- return m_vehicle->getNumWheels();
- }
-
- virtual void GetWheelPosition(int wheelIndex,float& posX,float& posY,float& posZ) const
- {
- btTransform trans = m_vehicle->getWheelTransformWS(wheelIndex);
- posX = trans.getOrigin().x();
- posY = trans.getOrigin().y();
- posZ = trans.getOrigin().z();
- }
- virtual void GetWheelOrientationQuaternion(int wheelIndex,float& quatX,float& quatY,float& quatZ,float& quatW) const
- {
- btTransform trans = m_vehicle->getWheelTransformWS(wheelIndex);
- btQuaternion quat = trans.getRotation();
- btMatrix3x3 orn2(quat);
-
- quatX = trans.getRotation().x();
- quatY = trans.getRotation().y();
- quatZ = trans.getRotation().z();
- quatW = trans.getRotation()[3];
-
-
- //printf("test");
-
-
- }
-
- virtual float GetWheelRotation(int wheelIndex) const
- {
- float rotation = 0.f;
-
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- rotation = info.m_rotation;
- }
- return rotation;
-
- }
-
-
-
- virtual int GetUserConstraintId() const
- {
- return m_vehicle->getUserConstraintId();
- }
-
- virtual int GetUserConstraintType() const
- {
- return m_vehicle->getUserConstraintType();
- }
-
- virtual void SetSteeringValue(float steering,int wheelIndex)
- {
- m_vehicle->setSteeringValue(steering,wheelIndex);
- }
-
- virtual void ApplyEngineForce(float force,int wheelIndex)
- {
- m_vehicle->applyEngineForce(force,wheelIndex);
- }
-
- virtual void ApplyBraking(float braking,int wheelIndex)
- {
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- info.m_brake = braking;
- }
- }
-
- virtual void SetWheelFriction(float friction,int wheelIndex)
- {
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- info.m_frictionSlip = friction;
- }
-
- }
-
- virtual void SetSuspensionStiffness(float suspensionStiffness,int wheelIndex)
- {
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- info.m_suspensionStiffness = suspensionStiffness;
-
- }
- }
-
- virtual void SetSuspensionDamping(float suspensionDamping,int wheelIndex)
- {
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- info.m_wheelsDampingRelaxation = suspensionDamping;
- }
- }
-
- virtual void SetSuspensionCompression(float suspensionCompression,int wheelIndex)
- {
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- info.m_wheelsDampingCompression = suspensionCompression;
- }
- }
-
-
-
- virtual void SetRollInfluence(float rollInfluence,int wheelIndex)
- {
- if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels()))
- {
- btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex);
- info.m_rollInfluence = rollInfluence;
- }
- }
-
- virtual void SetCoordinateSystem(int rightIndex,int upIndex,int forwardIndex)
- {
- m_vehicle->setCoordinateSystem(rightIndex,upIndex,forwardIndex);
- }
-
-
-
-};
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
-class CcdOverlapFilterCallBack : public btOverlapFilterCallback
-{
-private:
- class CcdPhysicsEnvironment* m_physEnv;
-public:
- CcdOverlapFilterCallBack(CcdPhysicsEnvironment* env) :
- m_physEnv(env)
- {
- }
- virtual ~CcdOverlapFilterCallBack()
- {
- }
- // return true when pairs need collision
- virtual bool needBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const;
-};
-
-
-void CcdPhysicsEnvironment::setDebugDrawer(btIDebugDraw* debugDrawer)
-{
- if (debugDrawer && m_dynamicsWorld)
- m_dynamicsWorld->setDebugDrawer(debugDrawer);
- m_debugDrawer = debugDrawer;
-}
-
-static void DrawAabb(btIDebugDraw* debugDrawer,const btVector3& from,const btVector3& to,const btVector3& color)
-{
- btVector3 halfExtents = (to-from)* 0.5f;
- btVector3 center = (to+from) *0.5f;
- int i,j;
-
- btVector3 edgecoord(1.f,1.f,1.f),pa,pb;
- for (i=0;i<4;i++)
- {
- for (j=0;j<3;j++)
- {
- pa = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
- edgecoord[2]*halfExtents[2]);
- pa+=center;
-
- int othercoord = j%3;
- edgecoord[othercoord]*=-1.f;
- pb = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1],
- edgecoord[2]*halfExtents[2]);
- pb+=center;
-
- debugDrawer->drawLine(pa,pb,color);
- }
- edgecoord = btVector3(-1.f,-1.f,-1.f);
- if (i<3)
- edgecoord[i]*=-1.f;
- }
-
-
-}
-
-
-
-
-
-
-CcdPhysicsEnvironment::CcdPhysicsEnvironment(bool useDbvtCulling,btDispatcher* dispatcher,btOverlappingPairCache* pairCache)
-:m_cullingCache(NULL),
-m_cullingTree(NULL),
-m_numIterations(10),
-m_numTimeSubSteps(1),
-m_ccdMode(0),
-m_solverType(-1),
-m_profileTimings(0),
-m_enableSatCollisionDetection(false),
-m_solver(NULL),
-m_ownPairCache(NULL),
-m_filterCallback(NULL),
-m_ownDispatcher(NULL),
-m_scalingPropagated(false)
-{
-
- for (int i=0;i<PHY_NUM_RESPONSE;i++)
- {
- m_triggerCallbacks[i] = 0;
- }
-
-// m_collisionConfiguration = new btDefaultCollisionConfiguration();
- m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration();
- //m_collisionConfiguration->setConvexConvexMultipointIterations();
-
- if (!dispatcher)
- {
- btCollisionDispatcher* disp = new btCollisionDispatcher(m_collisionConfiguration);
- dispatcher = disp;
- btGImpactCollisionAlgorithm::registerAlgorithm(disp);
- m_ownDispatcher = dispatcher;
- }
-
- //m_broadphase = new btAxisSweep3(btVector3(-1000,-1000,-1000),btVector3(1000,1000,1000));
- //m_broadphase = new btSimpleBroadphase();
- m_broadphase = new btDbvtBroadphase();
- // avoid any collision in the culling tree
- if (useDbvtCulling) {
- m_cullingCache = new btNullPairCache();
- m_cullingTree = new btDbvtBroadphase(m_cullingCache);
- }
-
- m_filterCallback = new CcdOverlapFilterCallBack(this);
- m_broadphase->getOverlappingPairCache()->setOverlapFilterCallback(m_filterCallback);
-
- setSolverType(1);//issues with quickstep and memory allocations
-// m_dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
- m_dynamicsWorld = new btSoftRigidDynamicsWorld(dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
- //m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.01f;
- //m_dynamicsWorld->getSolverInfo().m_solverMode= SOLVER_USE_WARMSTARTING + SOLVER_USE_2_FRICTION_DIRECTIONS + SOLVER_RANDMIZE_ORDER + SOLVER_USE_FRICTION_WARMSTARTING;
-
- m_debugDrawer = 0;
- setGravity(0.f,0.f,-9.81f);
-}
-
-void CcdPhysicsEnvironment::addCcdPhysicsController(CcdPhysicsController* ctrl)
-{
- btRigidBody* body = ctrl->GetRigidBody();
- btCollisionObject* obj = ctrl->GetCollisionObject();
-
- //this m_userPointer is just used for triggers, see CallbackTriggers
- obj->setUserPointer(ctrl);
- if (body)
- body->setGravity( m_gravity );
-
- m_controllers.insert(ctrl);
-
- if (body)
- {
- //use explicit group/filter for finer control over collision in bullet => near/radar sensor
- m_dynamicsWorld->addRigidBody(body, ctrl->GetCollisionFilterGroup(), ctrl->GetCollisionFilterMask());
- } else
- {
- if (ctrl->GetSoftBody())
- {
- btSoftBody* softBody = ctrl->GetSoftBody();
- m_dynamicsWorld->addSoftBody(softBody);
- } else
- {
- if (obj->getCollisionShape())
- {
- m_dynamicsWorld->addCollisionObject(obj,ctrl->GetCollisionFilterGroup(), ctrl->GetCollisionFilterMask());
- }
- }
- }
- if (obj->isStaticOrKinematicObject())
- {
- obj->setActivationState(ISLAND_SLEEPING);
- }
-
- assert(obj->getBroadphaseHandle());
-}
-
-
-
-bool CcdPhysicsEnvironment::removeCcdPhysicsController(CcdPhysicsController* ctrl)
-{
- //also remove constraint
- btRigidBody* body = ctrl->GetRigidBody();
- if (body)
- {
- for (int i=body->getNumConstraintRefs()-1;i>=0;i--)
- {
- btTypedConstraint* con = body->getConstraintRef(i);
- m_dynamicsWorld->removeConstraint(con);
- body->removeConstraintRef(con);
- //delete con; //might be kept by python KX_ConstraintWrapper
- }
- m_dynamicsWorld->removeRigidBody(ctrl->GetRigidBody());
- } else
- {
- //if a softbody
- if (ctrl->GetSoftBody())
- {
- m_dynamicsWorld->removeSoftBody(ctrl->GetSoftBody());
- } else
- {
- m_dynamicsWorld->removeCollisionObject(ctrl->GetCollisionObject());
- }
- }
- if (ctrl->m_registerCount != 0)
- printf("Warning: removing controller with non-zero m_registerCount: %d\n", ctrl->m_registerCount);
-
- //remove it from the triggers
- m_triggerControllers.erase(ctrl);
-
- return (m_controllers.erase(ctrl) != 0);
-}
-
-void CcdPhysicsEnvironment::updateCcdPhysicsController(CcdPhysicsController* ctrl, btScalar newMass, int newCollisionFlags, short int newCollisionGroup, short int newCollisionMask)
-{
- // this function is used when the collisionning group of a controller is changed
- // remove and add the collistioning object
- btRigidBody* body = ctrl->GetRigidBody();
- btCollisionObject* obj = ctrl->GetCollisionObject();
- if (obj)
- {
- btVector3 inertia(0.0,0.0,0.0);
- m_dynamicsWorld->removeCollisionObject(obj);
- obj->setCollisionFlags(newCollisionFlags);
- if (body)
- {
- if (newMass)
- body->getCollisionShape()->calculateLocalInertia(newMass, inertia);
- body->setMassProps(newMass, inertia);
- }
- m_dynamicsWorld->addCollisionObject(obj, newCollisionGroup, newCollisionMask);
- }
- // to avoid nasty interaction, we must update the property of the controller as well
- ctrl->m_cci.m_mass = newMass;
- ctrl->m_cci.m_collisionFilterGroup = newCollisionGroup;
- ctrl->m_cci.m_collisionFilterMask = newCollisionMask;
- ctrl->m_cci.m_collisionFlags = newCollisionFlags;
-}
-
-void CcdPhysicsEnvironment::enableCcdPhysicsController(CcdPhysicsController* ctrl)
-{
- if (m_controllers.insert(ctrl).second)
- {
- btCollisionObject* obj = ctrl->GetCollisionObject();
- obj->setUserPointer(ctrl);
- // update the position of the object from the user
- if (ctrl->GetMotionState())
- {
- btTransform xform = CcdPhysicsController::GetTransformFromMotionState(ctrl->GetMotionState());
- ctrl->SetCenterOfMassTransform(xform);
- }
- m_dynamicsWorld->addCollisionObject(obj,
- ctrl->GetCollisionFilterGroup(), ctrl->GetCollisionFilterMask());
- }
-}
-
-void CcdPhysicsEnvironment::disableCcdPhysicsController(CcdPhysicsController* ctrl)
-{
- if (m_controllers.erase(ctrl))
- {
- btRigidBody* body = ctrl->GetRigidBody();
- if (body)
- {
- m_dynamicsWorld->removeRigidBody(body);
- } else
- {
- if (ctrl->GetSoftBody())
- {
- } else
- {
- m_dynamicsWorld->removeCollisionObject(ctrl->GetCollisionObject());
- }
- }
- }
-}
-
-void CcdPhysicsEnvironment::refreshCcdPhysicsController(CcdPhysicsController* ctrl)
-{
- btCollisionObject* obj = ctrl->GetCollisionObject();
- if (obj)
- {
- btBroadphaseProxy* proxy = obj->getBroadphaseHandle();
- if (proxy)
- {
- m_dynamicsWorld->getPairCache()->cleanProxyFromPairs(proxy,m_dynamicsWorld->getDispatcher());
- }
- }
-}
-
-void CcdPhysicsEnvironment::addCcdGraphicController(CcdGraphicController* ctrl)
-{
- if (m_cullingTree && !ctrl->getBroadphaseHandle())
- {
- btVector3 minAabb;
- btVector3 maxAabb;
- ctrl->getAabb(minAabb, maxAabb);
-
- ctrl->setBroadphaseHandle(m_cullingTree->createProxy(
- minAabb,
- maxAabb,
- INVALID_SHAPE_PROXYTYPE, // this parameter is not used
- ctrl,
- 0, // this object does not collision with anything
- 0,
- NULL, // dispatcher => this parameter is not used
- 0));
-
- assert(ctrl->getBroadphaseHandle());
- }
-}
-
-void CcdPhysicsEnvironment::removeCcdGraphicController(CcdGraphicController* ctrl)
-{
- if (m_cullingTree)
- {
- btBroadphaseProxy* bp = ctrl->getBroadphaseHandle();
- if (bp)
- {
- m_cullingTree->destroyProxy(bp,NULL);
- ctrl->setBroadphaseHandle(0);
- }
- }
-}
-
-void CcdPhysicsEnvironment::beginFrame()
-{
-
-}
-
-void CcdPhysicsEnvironment::debugDrawWorld()
-{
- if (m_dynamicsWorld->getDebugDrawer() && m_dynamicsWorld->getDebugDrawer()->getDebugMode() >0)
- m_dynamicsWorld->debugDrawWorld();
-}
-
-bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep,float interval)
-{
- std::set<CcdPhysicsController*>::iterator it;
- int i;
-
- for (it=m_controllers.begin(); it!=m_controllers.end(); it++)
- {
- (*it)->SynchronizeMotionStates(timeStep);
- }
-
- float subStep = timeStep / float(m_numTimeSubSteps);
- i = m_dynamicsWorld->stepSimulation(interval,25,subStep);//perform always a full simulation step
- processFhSprings(curTime,i*subStep);
-
- for (it=m_controllers.begin(); it!=m_controllers.end(); it++)
- {
- (*it)->SynchronizeMotionStates(timeStep);
- }
-
- //for (it=m_controllers.begin(); it!=m_controllers.end(); it++)
- //{
- // (*it)->SynchronizeMotionStates(timeStep);
- //}
-
- for (i=0;i<m_wrapperVehicles.size();i++)
- {
- WrapperVehicle* veh = m_wrapperVehicles[i];
- veh->SyncWheels();
- }
-
-
- CallbackTriggers();
-
- return true;
-}
-
-class ClosestRayResultCallbackNotMe : public btCollisionWorld::ClosestRayResultCallback
-{
- btCollisionObject* m_owner;
- btCollisionObject* m_parent;
-
-public:
- ClosestRayResultCallbackNotMe(const btVector3& rayFromWorld,const btVector3& rayToWorld,btCollisionObject* owner,btCollisionObject* parent)
- :btCollisionWorld::ClosestRayResultCallback(rayFromWorld,rayToWorld),
- m_owner(owner),
- m_parent(parent)
- {
-
- }
-
- virtual bool needsCollision(btBroadphaseProxy* proxy0) const
- {
- //don't collide with self
- if (proxy0->m_clientObject == m_owner)
- return false;
-
- if (proxy0->m_clientObject == m_parent)
- return false;
-
- return btCollisionWorld::ClosestRayResultCallback::needsCollision(proxy0);
- }
-
-};
-
-void CcdPhysicsEnvironment::processFhSprings(double curTime,float interval)
-{
- std::set<CcdPhysicsController*>::iterator it;
- // dynamic of Fh spring is based on a timestep of 1/60
- int numIter = (int)(interval*60.0001f);
-
- for (it=m_controllers.begin(); it!=m_controllers.end(); it++)
- {
- CcdPhysicsController* ctrl = (*it);
- btRigidBody* body = ctrl->GetRigidBody();
-
- if (body && (ctrl->getConstructionInfo().m_do_fh || ctrl->getConstructionInfo().m_do_rot_fh))
- {
- //printf("has Fh or RotFh\n");
- //re-implement SM_FhObject.cpp using btCollisionWorld::rayTest and info from ctrl->getConstructionInfo()
- //send a ray from {0.0, 0.0, 0.0} towards {0.0, 0.0, -10.0}, in local coordinates
- CcdPhysicsController* parentCtrl = ctrl->getParentCtrl();
- btRigidBody* parentBody = parentCtrl?parentCtrl->GetRigidBody() : 0;
- btRigidBody* cl_object = parentBody ? parentBody : body;
-
- if (body->isStaticOrKinematicObject())
- continue;
-
- btVector3 rayDirLocal(0,0,-10);
-
- //m_dynamicsWorld
- //ctrl->GetRigidBody();
- btVector3 rayFromWorld = body->getCenterOfMassPosition();
- //btVector3 rayToWorld = rayFromWorld + body->getCenterOfMassTransform().getBasis() * rayDirLocal;
- //ray always points down the z axis in world space...
- btVector3 rayToWorld = rayFromWorld + rayDirLocal;
-
- ClosestRayResultCallbackNotMe resultCallback(rayFromWorld,rayToWorld,body,parentBody);
-
- m_dynamicsWorld->rayTest(rayFromWorld,rayToWorld,resultCallback);
- if (resultCallback.hasHit())
- {
- //we hit this one: resultCallback.m_collisionObject;
- CcdPhysicsController* controller = static_cast<CcdPhysicsController*>(resultCallback.m_collisionObject->getUserPointer());
-
- if (controller)
- {
- if (controller->getConstructionInfo().m_fh_distance < SIMD_EPSILON)
- continue;
-
- btRigidBody* hit_object = controller->GetRigidBody();
- if (!hit_object)
- continue;
-
- CcdConstructionInfo& hitObjShapeProps = controller->getConstructionInfo();
-
- float distance = resultCallback.m_closestHitFraction*rayDirLocal.length()-ctrl->getConstructionInfo().m_radius;
- if (distance >= hitObjShapeProps.m_fh_distance)
- continue;
-
-
-
- //btVector3 ray_dir = cl_object->getCenterOfMassTransform().getBasis()* rayDirLocal.normalized();
- btVector3 ray_dir = rayDirLocal.normalized();
- btVector3 normal = resultCallback.m_hitNormalWorld;
- normal.normalize();
-
- for (int i=0; i<numIter; i++)
- {
- if (ctrl->getConstructionInfo().m_do_fh)
- {
- btVector3 lspot = cl_object->getCenterOfMassPosition()
- + rayDirLocal * resultCallback.m_closestHitFraction;
-
-
-
-
- lspot -= hit_object->getCenterOfMassPosition();
- btVector3 rel_vel = cl_object->getLinearVelocity() - hit_object->getVelocityInLocalPoint(lspot);
- btScalar rel_vel_ray = ray_dir.dot(rel_vel);
- btScalar spring_extent = 1.0 - distance / hitObjShapeProps.m_fh_distance;
-
- btScalar i_spring = spring_extent * hitObjShapeProps.m_fh_spring;
- btScalar i_damp = rel_vel_ray * hitObjShapeProps.m_fh_damping;
-
- cl_object->setLinearVelocity(cl_object->getLinearVelocity() + (-(i_spring + i_damp) * ray_dir));
- if (hitObjShapeProps.m_fh_normal)
- {
- cl_object->setLinearVelocity(cl_object->getLinearVelocity()+(i_spring + i_damp) *(normal - normal.dot(ray_dir) * ray_dir));
- }
-
- btVector3 lateral = rel_vel - rel_vel_ray * ray_dir;
-
-
- if (ctrl->getConstructionInfo().m_do_anisotropic) {
- //Bullet basis contains no scaling/shear etc.
- const btMatrix3x3& lcs = cl_object->getCenterOfMassTransform().getBasis();
- btVector3 loc_lateral = lateral * lcs;
- const btVector3& friction_scaling = cl_object->getAnisotropicFriction();
- loc_lateral *= friction_scaling;
- lateral = lcs * loc_lateral;
- }
-
- btScalar rel_vel_lateral = lateral.length();
-
- if (rel_vel_lateral > SIMD_EPSILON) {
- btScalar friction_factor = hit_object->getFriction();//cl_object->getFriction();
-
- btScalar max_friction = friction_factor * btMax(btScalar(0.0), i_spring);
-
- btScalar rel_mom_lateral = rel_vel_lateral / cl_object->getInvMass();
-
- btVector3 friction = (rel_mom_lateral > max_friction) ?
- -lateral * (max_friction / rel_vel_lateral) :
- -lateral;
-
- cl_object->applyCentralImpulse(friction);
- }
- }
-
-
- if (ctrl->getConstructionInfo().m_do_rot_fh) {
- btVector3 up2 = cl_object->getWorldTransform().getBasis().getColumn(2);
-
- btVector3 t_spring = up2.cross(normal) * hitObjShapeProps.m_fh_spring;
- btVector3 ang_vel = cl_object->getAngularVelocity();
-
- // only rotations that tilt relative to the normal are damped
- ang_vel -= ang_vel.dot(normal) * normal;
-
- btVector3 t_damp = ang_vel * hitObjShapeProps.m_fh_damping;
-
- cl_object->setAngularVelocity(cl_object->getAngularVelocity() + (t_spring - t_damp));
- }
- }
- }
- }
- }
- }
-}
-
-void CcdPhysicsEnvironment::setDebugMode(int debugMode)
-{
- if (m_debugDrawer){
- m_debugDrawer->setDebugMode(debugMode);
- }
-}
-
-void CcdPhysicsEnvironment::setNumIterations(int numIter)
-{
- m_numIterations = numIter;
-}
-void CcdPhysicsEnvironment::setDeactivationTime(float dTime)
-{
- gDeactivationTime = dTime;
-}
-void CcdPhysicsEnvironment::setDeactivationLinearTreshold(float linTresh)
-{
- gLinearSleepingTreshold = linTresh;
-}
-void CcdPhysicsEnvironment::setDeactivationAngularTreshold(float angTresh)
-{
- gAngularSleepingTreshold = angTresh;
-}
-
-void CcdPhysicsEnvironment::setContactBreakingTreshold(float contactBreakingTreshold)
-{
- gContactBreakingThreshold = contactBreakingTreshold;
-
-}
-
-
-void CcdPhysicsEnvironment::setCcdMode(int ccdMode)
-{
- m_ccdMode = ccdMode;
-}
-
-
-void CcdPhysicsEnvironment::setSolverSorConstant(float sor)
-{
- m_solverInfo.m_sor = sor;
-}
-
-void CcdPhysicsEnvironment::setSolverTau(float tau)
-{
- m_solverInfo.m_tau = tau;
-}
-void CcdPhysicsEnvironment::setSolverDamping(float damping)
-{
- m_solverInfo.m_damping = damping;
-}
-
-
-void CcdPhysicsEnvironment::setLinearAirDamping(float damping)
-{
- //gLinearAirDamping = damping;
-}
-
-void CcdPhysicsEnvironment::setUseEpa(bool epa)
-{
- //gUseEpa = epa;
-}
-
-void CcdPhysicsEnvironment::setSolverType(int solverType)
-{
-
- switch (solverType)
- {
- case 1:
- {
- if (m_solverType != solverType)
- {
-
- m_solver = new btSequentialImpulseConstraintSolver();
-
-
- break;
- }
- }
-
- case 0:
- default:
- if (m_solverType != solverType)
- {
-// m_solver = new OdeConstraintSolver();
-
- break;
- }
-
- };
-
- m_solverType = solverType ;
-}
-
-
-
-void CcdPhysicsEnvironment::getGravity(PHY__Vector3& grav)
-{
- const btVector3& gravity = m_dynamicsWorld->getGravity();
- grav[0] = gravity.getX();
- grav[1] = gravity.getY();
- grav[2] = gravity.getZ();
-}
-
-
-void CcdPhysicsEnvironment::setGravity(float x,float y,float z)
-{
- m_gravity = btVector3(x,y,z);
- m_dynamicsWorld->setGravity(m_gravity);
- m_dynamicsWorld->getWorldInfo().m_gravity.setValue(x,y,z);
-}
-
-
-
-
-static int gConstraintUid = 1;
-
-//Following the COLLADA physics specification for constraints
-int CcdPhysicsEnvironment::createUniversalD6Constraint(
- class PHY_IPhysicsController* ctrlRef,class PHY_IPhysicsController* ctrlOther,
- btTransform& frameInA,
- btTransform& frameInB,
- const btVector3& linearMinLimits,
- const btVector3& linearMaxLimits,
- const btVector3& angularMinLimits,
- const btVector3& angularMaxLimits,int flags
-)
-{
-
- bool disableCollisionBetweenLinkedBodies = (0!=(flags & CCD_CONSTRAINT_DISABLE_LINKED_COLLISION));
-
- //we could either add some logic to recognize ball-socket and hinge, or let that up to the user
- //perhaps some warning or hint that hinge/ball-socket is more efficient?
-
-
- btGeneric6DofConstraint* genericConstraint = 0;
- CcdPhysicsController* ctrl0 = (CcdPhysicsController*) ctrlRef;
- CcdPhysicsController* ctrl1 = (CcdPhysicsController*) ctrlOther;
-
- btRigidBody* rb0 = ctrl0->GetRigidBody();
- btRigidBody* rb1 = ctrl1->GetRigidBody();
-
- if (rb1)
- {
-
-
- bool useReferenceFrameA = true;
- genericConstraint = new btGeneric6DofSpringConstraint(
- *rb0,*rb1,
- frameInA,frameInB,useReferenceFrameA);
- genericConstraint->setLinearLowerLimit(linearMinLimits);
- genericConstraint->setLinearUpperLimit(linearMaxLimits);
- genericConstraint->setAngularLowerLimit(angularMinLimits);
- genericConstraint->setAngularUpperLimit(angularMaxLimits);
- } else
- {
- // TODO: Implement single body case...
- //No, we can use a fixed rigidbody in above code, rather then unnecessary duplation of code
-
- }
-
- if (genericConstraint)
- {
- // m_constraints.push_back(genericConstraint);
- m_dynamicsWorld->addConstraint(genericConstraint,disableCollisionBetweenLinkedBodies);
-
- genericConstraint->setUserConstraintId(gConstraintUid++);
- genericConstraint->setUserConstraintType(PHY_GENERIC_6DOF_CONSTRAINT);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return genericConstraint->getUserConstraintId();
- }
- return 0;
-}
-
-
-
-void CcdPhysicsEnvironment::removeConstraint(int constraintId)
-{
-
- int i;
- int numConstraints = m_dynamicsWorld->getNumConstraints();
- for (i=0;i<numConstraints;i++)
- {
- btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
- if (constraint->getUserConstraintId() == constraintId)
- {
- constraint->getRigidBodyA().activate();
- constraint->getRigidBodyB().activate();
- m_dynamicsWorld->removeConstraint(constraint);
- break;
- }
- }
-}
-
-
-struct FilterClosestRayResultCallback : public btCollisionWorld::ClosestRayResultCallback
-{
- PHY_IRayCastFilterCallback& m_phyRayFilter;
- const btCollisionShape* m_hitTriangleShape;
- int m_hitTriangleIndex;
-
-
- FilterClosestRayResultCallback (PHY_IRayCastFilterCallback& phyRayFilter,const btVector3& rayFrom,const btVector3& rayTo)
- : btCollisionWorld::ClosestRayResultCallback(rayFrom,rayTo),
- m_phyRayFilter(phyRayFilter),
- m_hitTriangleShape(NULL),
- m_hitTriangleIndex(0)
- {
- }
-
- virtual ~FilterClosestRayResultCallback()
- {
- }
-
- virtual bool needsCollision(btBroadphaseProxy* proxy0) const
- {
- if (!(proxy0->m_collisionFilterGroup & m_collisionFilterMask))
- return false;
- if (!(m_collisionFilterGroup & proxy0->m_collisionFilterMask))
- return false;
- btCollisionObject* object = (btCollisionObject*)proxy0->m_clientObject;
- CcdPhysicsController* phyCtrl = static_cast<CcdPhysicsController*>(object->getUserPointer());
- if (phyCtrl == m_phyRayFilter.m_ignoreController)
- return false;
- return m_phyRayFilter.needBroadphaseRayCast(phyCtrl);
- }
-
- virtual btScalar addSingleResult(btCollisionWorld::LocalRayResult& rayResult,bool normalInWorldSpace)
- {
- //CcdPhysicsController* curHit = static_cast<CcdPhysicsController*>(rayResult.m_collisionObject->getUserPointer());
- // save shape information as ClosestRayResultCallback::AddSingleResult() does not do it
- if (rayResult.m_localShapeInfo)
- {
- m_hitTriangleShape = rayResult.m_collisionObject->getCollisionShape();
- m_hitTriangleIndex = rayResult.m_localShapeInfo->m_triangleIndex;
- } else
- {
- m_hitTriangleShape = NULL;
- m_hitTriangleIndex = 0;
- }
- return ClosestRayResultCallback::addSingleResult(rayResult,normalInWorldSpace);
- }
-
-};
-
-static bool GetHitTriangle(btCollisionShape* shape, CcdShapeConstructionInfo* shapeInfo, int hitTriangleIndex, btVector3 triangle[])
-{
- // this code is copied from Bullet
- const unsigned char *vertexbase;
- int numverts;
- PHY_ScalarType type;
- int stride;
- const unsigned char *indexbase;
- int indexstride;
- int numfaces;
- PHY_ScalarType indicestype;
- btStridingMeshInterface* meshInterface = NULL;
- btTriangleMeshShape* triangleShape = shapeInfo->GetMeshShape();
-
- if (triangleShape)
- meshInterface = triangleShape->getMeshInterface();
- else
- {
- // other possibility is gImpact
- if (shape->getShapeType() == GIMPACT_SHAPE_PROXYTYPE)
- meshInterface = (static_cast<btGImpactMeshShape*>(shape))->getMeshInterface();
- }
- if (!meshInterface)
- return false;
-
- meshInterface->getLockedReadOnlyVertexIndexBase(
- &vertexbase,
- numverts,
- type,
- stride,
- &indexbase,
- indexstride,
- numfaces,
- indicestype,
- 0);
-
- unsigned int* gfxbase = (unsigned int*)(indexbase+hitTriangleIndex*indexstride);
- const btVector3& meshScaling = shape->getLocalScaling();
- for (int j=2;j>=0;j--)
- {
- int graphicsindex = indicestype==PHY_SHORT?((unsigned short*)gfxbase)[j]:gfxbase[j];
-
- btScalar* graphicsbase = (btScalar*)(vertexbase+graphicsindex*stride);
-
- triangle[j] = btVector3(graphicsbase[0]*meshScaling.getX(),graphicsbase[1]*meshScaling.getY(),graphicsbase[2]*meshScaling.getZ());
- }
- meshInterface->unLockReadOnlyVertexBase(0);
- return true;
-}
-
-PHY_IPhysicsController* CcdPhysicsEnvironment::rayTest(PHY_IRayCastFilterCallback &filterCallback, float fromX,float fromY,float fromZ, float toX,float toY,float toZ)
-{
- btVector3 rayFrom(fromX,fromY,fromZ);
- btVector3 rayTo(toX,toY,toZ);
-
- btVector3 hitPointWorld,normalWorld;
-
- //Either Ray Cast with or without filtering
-
- //btCollisionWorld::ClosestRayResultCallback rayCallback(rayFrom,rayTo);
- FilterClosestRayResultCallback rayCallback(filterCallback,rayFrom,rayTo);
-
-
- PHY_RayCastResult result;
- memset(&result, 0, sizeof(result));
-
- // don't collision with sensor object
- rayCallback.m_collisionFilterMask = CcdConstructionInfo::AllFilter ^ CcdConstructionInfo::SensorFilter;
- //, ,filterCallback.m_faceNormal);
-
- m_dynamicsWorld->rayTest(rayFrom,rayTo,rayCallback);
- if (rayCallback.hasHit())
- {
- CcdPhysicsController* controller = static_cast<CcdPhysicsController*>(rayCallback.m_collisionObject->getUserPointer());
- result.m_controller = controller;
- result.m_hitPoint[0] = rayCallback.m_hitPointWorld.getX();
- result.m_hitPoint[1] = rayCallback.m_hitPointWorld.getY();
- result.m_hitPoint[2] = rayCallback.m_hitPointWorld.getZ();
-
- if (rayCallback.m_hitTriangleShape != NULL)
- {
- // identify the mesh polygon
- CcdShapeConstructionInfo* shapeInfo = controller->m_shapeInfo;
- if (shapeInfo)
- {
- btCollisionShape* shape = controller->GetCollisionObject()->getCollisionShape();
- if (shape->isCompound())
- {
- btCompoundShape* compoundShape = (btCompoundShape*)shape;
- CcdShapeConstructionInfo* compoundShapeInfo = shapeInfo;
- // need to search which sub-shape has been hit
- for (int i=0; i<compoundShape->getNumChildShapes(); i++)
- {
- shapeInfo = compoundShapeInfo->GetChildShape(i);
- shape=compoundShape->getChildShape(i);
- if (shape == rayCallback.m_hitTriangleShape)
- break;
- }
- }
- if (shape == rayCallback.m_hitTriangleShape &&
- rayCallback.m_hitTriangleIndex < shapeInfo->m_polygonIndexArray.size())
- {
- // save original collision shape triangle for soft body
- int hitTriangleIndex = rayCallback.m_hitTriangleIndex;
-
- result.m_meshObject = shapeInfo->GetMesh();
- if (shape->isSoftBody())
- {
- // soft body using different face numbering because of randomization
- // hopefully we have stored the original face number in m_tag
- btSoftBody* softBody = static_cast<btSoftBody*>(rayCallback.m_collisionObject);
- if (softBody->m_faces[hitTriangleIndex].m_tag != 0)
- {
- rayCallback.m_hitTriangleIndex = (int)((uintptr_t)(softBody->m_faces[hitTriangleIndex].m_tag)-1);
- }
- }
- // retrieve the original mesh polygon (in case of quad->tri conversion)
- result.m_polygon = shapeInfo->m_polygonIndexArray.at(rayCallback.m_hitTriangleIndex);
- // hit triangle in world coordinate, for face normal and UV coordinate
- btVector3 triangle[3];
- bool triangleOK = false;
- if (filterCallback.m_faceUV && (3*rayCallback.m_hitTriangleIndex) < shapeInfo->m_triFaceUVcoArray.size())
- {
- // interpolate the UV coordinate of the hit point
- CcdShapeConstructionInfo::UVco* uvCo = &shapeInfo->m_triFaceUVcoArray[3*rayCallback.m_hitTriangleIndex];
- // 1. get the 3 coordinate of the triangle in world space
- btVector3 v1, v2, v3;
- if (shape->isSoftBody())
- {
- // soft body give points directly in world coordinate
- btSoftBody* softBody = static_cast<btSoftBody*>(rayCallback.m_collisionObject);
- v1 = softBody->m_faces[hitTriangleIndex].m_n[0]->m_x;
- v2 = softBody->m_faces[hitTriangleIndex].m_n[1]->m_x;
- v3 = softBody->m_faces[hitTriangleIndex].m_n[2]->m_x;
- } else
- {
- // for rigid body we must apply the world transform
- triangleOK = GetHitTriangle(shape, shapeInfo, hitTriangleIndex, triangle);
- if (!triangleOK)
- // if we cannot get the triangle, no use to continue
- goto SKIP_UV_NORMAL;
- v1 = rayCallback.m_collisionObject->getWorldTransform()(triangle[0]);
- v2 = rayCallback.m_collisionObject->getWorldTransform()(triangle[1]);
- v3 = rayCallback.m_collisionObject->getWorldTransform()(triangle[2]);
- }
- // 2. compute barycentric coordinate of the hit point
- btVector3 v = v2-v1;
- btVector3 w = v3-v1;
- btVector3 u = v.cross(w);
- btScalar A = u.length();
-
- v = v2-rayCallback.m_hitPointWorld;
- w = v3-rayCallback.m_hitPointWorld;
- u = v.cross(w);
- btScalar A1 = u.length();
-
- v = rayCallback.m_hitPointWorld-v1;
- w = v3-v1;
- u = v.cross(w);
- btScalar A2 = u.length();
-
- btVector3 baryCo;
- baryCo.setX(A1/A);
- baryCo.setY(A2/A);
- baryCo.setZ(1.0f-baryCo.getX()-baryCo.getY());
- // 3. compute UV coordinate
- result.m_hitUV[0] = baryCo.getX()*uvCo[0].uv[0] + baryCo.getY()*uvCo[1].uv[0] + baryCo.getZ()*uvCo[2].uv[0];
- result.m_hitUV[1] = baryCo.getX()*uvCo[0].uv[1] + baryCo.getY()*uvCo[1].uv[1] + baryCo.getZ()*uvCo[2].uv[1];
- result.m_hitUVOK = 1;
- }
-
- // Bullet returns the normal from "outside".
- // If the user requests the real normal, compute it now
- if (filterCallback.m_faceNormal)
- {
- if (shape->isSoftBody())
- {
- // we can get the real normal directly from the body
- btSoftBody* softBody = static_cast<btSoftBody*>(rayCallback.m_collisionObject);
- rayCallback.m_hitNormalWorld = softBody->m_faces[hitTriangleIndex].m_normal;
- } else
- {
- if (!triangleOK)
- triangleOK = GetHitTriangle(shape, shapeInfo, hitTriangleIndex, triangle);
- if (triangleOK)
- {
- btVector3 triangleNormal;
- triangleNormal = (triangle[1]-triangle[0]).cross(triangle[2]-triangle[0]);
- rayCallback.m_hitNormalWorld = rayCallback.m_collisionObject->getWorldTransform().getBasis()*triangleNormal;
- }
- }
- }
- SKIP_UV_NORMAL:
- ;
- }
- }
- }
- if (rayCallback.m_hitNormalWorld.length2() > (SIMD_EPSILON*SIMD_EPSILON))
- {
- rayCallback.m_hitNormalWorld.normalize();
- } else
- {
- rayCallback.m_hitNormalWorld.setValue(1,0,0);
- }
- result.m_hitNormal[0] = rayCallback.m_hitNormalWorld.getX();
- result.m_hitNormal[1] = rayCallback.m_hitNormalWorld.getY();
- result.m_hitNormal[2] = rayCallback.m_hitNormalWorld.getZ();
- filterCallback.reportHit(&result);
- }
-
-
- return result.m_controller;
-}
-
-// Handles occlusion culling.
-// The implementation is based on the CDTestFramework
-struct OcclusionBuffer
-{
- struct WriteOCL
- {
- static inline bool Process(btScalar& q,btScalar v) { if(q<v) q=v;return(false); }
- static inline void Occlusion(bool& flag) { flag = true; }
- };
- struct QueryOCL
- {
- static inline bool Process(btScalar& q,btScalar v) { return(q<=v); }
- static inline void Occlusion(bool& flag) { }
- };
- btScalar* m_buffer;
- size_t m_bufferSize;
- bool m_initialized;
- bool m_occlusion;
- int m_sizes[2];
- btScalar m_scales[2];
- btScalar m_offsets[2];
- btScalar m_wtc[16]; // world to clip transform
- btScalar m_mtc[16]; // model to clip transform
- // constructor: size=largest dimension of the buffer.
- // Buffer size depends on aspect ratio
- OcclusionBuffer()
- {
- m_initialized=false;
- m_occlusion = false;
- m_buffer = NULL;
- m_bufferSize = 0;
- }
- // multiplication of column major matrices: m=m1*m2
- template<typename T1, typename T2>
- void CMmat4mul(btScalar* m, const T1* m1, const T2* m2)
- {
- m[ 0] = btScalar(m1[ 0]*m2[ 0]+m1[ 4]*m2[ 1]+m1[ 8]*m2[ 2]+m1[12]*m2[ 3]);
- m[ 1] = btScalar(m1[ 1]*m2[ 0]+m1[ 5]*m2[ 1]+m1[ 9]*m2[ 2]+m1[13]*m2[ 3]);
- m[ 2] = btScalar(m1[ 2]*m2[ 0]+m1[ 6]*m2[ 1]+m1[10]*m2[ 2]+m1[14]*m2[ 3]);
- m[ 3] = btScalar(m1[ 3]*m2[ 0]+m1[ 7]*m2[ 1]+m1[11]*m2[ 2]+m1[15]*m2[ 3]);
-
- m[ 4] = btScalar(m1[ 0]*m2[ 4]+m1[ 4]*m2[ 5]+m1[ 8]*m2[ 6]+m1[12]*m2[ 7]);
- m[ 5] = btScalar(m1[ 1]*m2[ 4]+m1[ 5]*m2[ 5]+m1[ 9]*m2[ 6]+m1[13]*m2[ 7]);
- m[ 6] = btScalar(m1[ 2]*m2[ 4]+m1[ 6]*m2[ 5]+m1[10]*m2[ 6]+m1[14]*m2[ 7]);
- m[ 7] = btScalar(m1[ 3]*m2[ 4]+m1[ 7]*m2[ 5]+m1[11]*m2[ 6]+m1[15]*m2[ 7]);
-
- m[ 8] = btScalar(m1[ 0]*m2[ 8]+m1[ 4]*m2[ 9]+m1[ 8]*m2[10]+m1[12]*m2[11]);
- m[ 9] = btScalar(m1[ 1]*m2[ 8]+m1[ 5]*m2[ 9]+m1[ 9]*m2[10]+m1[13]*m2[11]);
- m[10] = btScalar(m1[ 2]*m2[ 8]+m1[ 6]*m2[ 9]+m1[10]*m2[10]+m1[14]*m2[11]);
- m[11] = btScalar(m1[ 3]*m2[ 8]+m1[ 7]*m2[ 9]+m1[11]*m2[10]+m1[15]*m2[11]);
-
- m[12] = btScalar(m1[ 0]*m2[12]+m1[ 4]*m2[13]+m1[ 8]*m2[14]+m1[12]*m2[15]);
- m[13] = btScalar(m1[ 1]*m2[12]+m1[ 5]*m2[13]+m1[ 9]*m2[14]+m1[13]*m2[15]);
- m[14] = btScalar(m1[ 2]*m2[12]+m1[ 6]*m2[13]+m1[10]*m2[14]+m1[14]*m2[15]);
- m[15] = btScalar(m1[ 3]*m2[12]+m1[ 7]*m2[13]+m1[11]*m2[14]+m1[15]*m2[15]);
- }
- void setup(int size)
- {
- m_initialized=false;
- m_occlusion=false;
- // compute the size of the buffer
- GLint v[4];
- GLdouble m[16],p[16];
- int maxsize;
- double ratio;
- glGetIntegerv(GL_VIEWPORT,v);
- maxsize = (v[2] > v[3]) ? v[2] : v[3];
- assert(maxsize > 0);
- ratio = 1.0/(2*maxsize);
- // ensure even number
- m_sizes[0] = 2*((int)(size*v[2]*ratio+0.5));
- m_sizes[1] = 2*((int)(size*v[3]*ratio+0.5));
- m_scales[0]=btScalar(m_sizes[0]/2);
- m_scales[1]=btScalar(m_sizes[1]/2);
- m_offsets[0]=m_scales[0]+0.5f;
- m_offsets[1]=m_scales[1]+0.5f;
- // prepare matrix
- // at this time of the rendering, the modelview matrix is the
- // world to camera transformation and the projection matrix is
- // camera to clip transformation. combine both so that
- glGetDoublev(GL_MODELVIEW_MATRIX,m);
- glGetDoublev(GL_PROJECTION_MATRIX,p);
- CMmat4mul(m_wtc,p,m);
- }
- void initialize()
- {
- size_t newsize = (m_sizes[0]*m_sizes[1])*sizeof(btScalar);
- if (m_buffer)
- {
- // see if we can reuse
- if (newsize > m_bufferSize)
- {
- free(m_buffer);
- m_buffer = NULL;
- m_bufferSize = 0;
- }
- }
- if (!m_buffer)
- {
- m_buffer = (btScalar*)calloc(1, newsize);
- m_bufferSize = newsize;
- } else
- {
- // buffer exists already, just clears it
- memset(m_buffer, 0, newsize);
- }
- // memory allocate must succeed
- assert(m_buffer != NULL);
- m_initialized = true;
- m_occlusion = false;
- }
- void SetModelMatrix(double *fl)
- {
- CMmat4mul(m_mtc,m_wtc,fl);
- if (!m_initialized)
- initialize();
- }
-
- // transform a segment in world coordinate to clip coordinate
- void transformW(const btVector3& x, btVector4& t)
- {
- t[0] = x[0]*m_wtc[0]+x[1]*m_wtc[4]+x[2]*m_wtc[8]+m_wtc[12];
- t[1] = x[0]*m_wtc[1]+x[1]*m_wtc[5]+x[2]*m_wtc[9]+m_wtc[13];
- t[2] = x[0]*m_wtc[2]+x[1]*m_wtc[6]+x[2]*m_wtc[10]+m_wtc[14];
- t[3] = x[0]*m_wtc[3]+x[1]*m_wtc[7]+x[2]*m_wtc[11]+m_wtc[15];
- }
- void transformM(const float* x, btVector4& t)
- {
- t[0] = x[0]*m_mtc[0]+x[1]*m_mtc[4]+x[2]*m_mtc[8]+m_mtc[12];
- t[1] = x[0]*m_mtc[1]+x[1]*m_mtc[5]+x[2]*m_mtc[9]+m_mtc[13];
- t[2] = x[0]*m_mtc[2]+x[1]*m_mtc[6]+x[2]*m_mtc[10]+m_mtc[14];
- t[3] = x[0]*m_mtc[3]+x[1]*m_mtc[7]+x[2]*m_mtc[11]+m_mtc[15];
- }
- // convert polygon to device coordinates
- static bool project(btVector4* p,int n)
- {
- for(int i=0;i<n;++i)
- {
- p[i][2]=1/p[i][3];
- p[i][0]*=p[i][2];
- p[i][1]*=p[i][2];
- }
- return(true);
- }
- // pi: closed polygon in clip coordinate, NP = number of segments
- // po: same polygon with clipped segments removed
- template <const int NP>
- static int clip(const btVector4* pi,btVector4* po)
- {
- btScalar s[2*NP];
- btVector4 pn[2*NP];
- int i, j, m, n, ni;
- // deal with near clipping
- for(i=0, m=0;i<NP;++i)
- {
- s[i]=pi[i][2]+pi[i][3];
- if(s[i]<0) m+=1<<i;
- }
- if(m==((1<<NP)-1))
- return(0);
- if(m!=0)
- {
- for(i=NP-1,j=0,n=0;j<NP;i=j++)
- {
- const btVector4& a=pi[i];
- const btVector4& b=pi[j];
- const btScalar t=s[i]/(a[3]+a[2]-b[3]-b[2]);
- if((t>0)&&(t<1))
- {
- pn[n][0] = a[0]+(b[0]-a[0])*t;
- pn[n][1] = a[1]+(b[1]-a[1])*t;
- pn[n][2] = a[2]+(b[2]-a[2])*t;
- pn[n][3] = a[3]+(b[3]-a[3])*t;
- ++n;
- }
- if(s[j]>0) pn[n++]=b;
- }
- // ready to test far clipping, start from the modified polygon
- pi = pn;
- ni = n;
- } else
- {
- // no clipping on the near plane, keep same vector
- ni = NP;
- }
- // now deal with far clipping
- for(i=0, m=0;i<ni;++i)
- {
- s[i]=pi[i][2]-pi[i][3];
- if(s[i]>0) m+=1<<i;
- }
- if(m==((1<<ni)-1))
- return(0);
- if(m!=0)
- {
- for(i=ni-1,j=0,n=0;j<ni;i=j++)
- {
- const btVector4& a=pi[i];
- const btVector4& b=pi[j];
- const btScalar t=s[i]/(a[2]-a[3]-b[2]+b[3]);
- if((t>0)&&(t<1))
- {
- po[n][0] = a[0]+(b[0]-a[0])*t;
- po[n][1] = a[1]+(b[1]-a[1])*t;
- po[n][2] = a[2]+(b[2]-a[2])*t;
- po[n][3] = a[3]+(b[3]-a[3])*t;
- ++n;
- }
- if(s[j]<0) po[n++]=b;
- }
- return(n);
- }
- for(int i=0;i<ni;++i) po[i]=pi[i];
- return(ni);
- }
- // write or check a triangle to buffer. a,b,c in device coordinates (-1,+1)
- template <typename POLICY>
- inline bool draw( const btVector4& a,
- const btVector4& b,
- const btVector4& c,
- const float face,
- const btScalar minarea)
- {
- const btScalar a2=cross(b-a,c-a)[2];
- if((face*a2)<0.f || btFabs(a2)<minarea)
- return false;
- // further down we are normally going to write to the Zbuffer, mark it so
- POLICY::Occlusion(m_occlusion);
-
- int x[3], y[3], ib=1, ic=2;
- btScalar z[3];
- x[0]=(int)(a.x()*m_scales[0]+m_offsets[0]);
- y[0]=(int)(a.y()*m_scales[1]+m_offsets[1]);
- z[0]=a.z();
- if (a2 < 0.f)
- {
- // negative aire is possible with double face => must
- // change the order of b and c otherwise the algorithm doesn't work
- ib=2;
- ic=1;
- }
- x[ib]=(int)(b.x()*m_scales[0]+m_offsets[0]);
- x[ic]=(int)(c.x()*m_scales[0]+m_offsets[0]);
- y[ib]=(int)(b.y()*m_scales[1]+m_offsets[1]);
- y[ic]=(int)(c.y()*m_scales[1]+m_offsets[1]);
- z[ib]=b.z();
- z[ic]=c.z();
- const int mix=btMax(0,btMin(x[0],btMin(x[1],x[2])));
- const int mxx=btMin(m_sizes[0],1+btMax(x[0],btMax(x[1],x[2])));
- const int miy=btMax(0,btMin(y[0],btMin(y[1],y[2])));
- const int mxy=btMin(m_sizes[1],1+btMax(y[0],btMax(y[1],y[2])));
- const int width=mxx-mix;
- const int height=mxy-miy;
- if ((width*height) <= 1)
- {
- // degenerated in at most one single pixel
- btScalar* scan=&m_buffer[miy*m_sizes[0]+mix];
- // use for loop to detect the case where width or height == 0
- for(int iy=miy;iy<mxy;++iy)
- {
- for(int ix=mix;ix<mxx;++ix)
- {
- if(POLICY::Process(*scan,z[0]))
- return(true);
- if(POLICY::Process(*scan,z[1]))
- return(true);
- if(POLICY::Process(*scan,z[2]))
- return(true);
- }
- }
- } else if (width == 1)
- {
- // Degenerated in at least 2 vertical lines
- // The algorithm below doesn't work when face has a single pixel width
- // We cannot use general formulas because the plane is degenerated.
- // We have to interpolate along the 3 edges that overlaps and process each pixel.
- // sort the y coord to make formula simpler
- int ytmp;
- btScalar ztmp;
- if (y[0] > y[1]) { ytmp=y[1];y[1]=y[0];y[0]=ytmp;ztmp=z[1];z[1]=z[0];z[0]=ztmp; }
- if (y[0] > y[2]) { ytmp=y[2];y[2]=y[0];y[0]=ytmp;ztmp=z[2];z[2]=z[0];z[0]=ztmp; }
- if (y[1] > y[2]) { ytmp=y[2];y[2]=y[1];y[1]=ytmp;ztmp=z[2];z[2]=z[1];z[1]=ztmp; }
- int dy[]={ y[0]-y[1],
- y[1]-y[2],
- y[2]-y[0]};
- btScalar dzy[3];
- dzy[0] = (dy[0]) ? (z[0]-z[1])/dy[0] : btScalar(0.f);
- dzy[1] = (dy[1]) ? (z[1]-z[2])/dy[1] : btScalar(0.f);
- dzy[2] = (dy[2]) ? (z[2]-z[0])/dy[2] : btScalar(0.f);
- btScalar v[3] = { dzy[0]*(miy-y[0])+z[0],
- dzy[1]*(miy-y[1])+z[1],
- dzy[2]*(miy-y[2])+z[2] };
- dy[0] = y[1]-y[0];
- dy[1] = y[0]-y[1];
- dy[2] = y[2]-y[0];
- btScalar* scan=&m_buffer[miy*m_sizes[0]+mix];
- for(int iy=miy;iy<mxy;++iy)
- {
- if(dy[0] >= 0 && POLICY::Process(*scan,v[0]))
- return(true);
- if(dy[1] >= 0 && POLICY::Process(*scan,v[1]))
- return(true);
- if(dy[2] >= 0 && POLICY::Process(*scan,v[2]))
- return(true);
- scan+=m_sizes[0];
- v[0] += dzy[0]; v[1] += dzy[1]; v[2] += dzy[2];
- dy[0]--; dy[1]++, dy[2]--;
- }
- } else if (height == 1)
- {
- // Degenerated in at least 2 horizontal lines
- // The algorithm below doesn't work when face has a single pixel width
- // We cannot use general formulas because the plane is degenerated.
- // We have to interpolate along the 3 edges that overlaps and process each pixel.
- int xtmp;
- btScalar ztmp;
- if (x[0] > x[1]) { xtmp=x[1];x[1]=x[0];x[0]=xtmp;ztmp=z[1];z[1]=z[0];z[0]=ztmp; }
- if (x[0] > x[2]) { xtmp=x[2];x[2]=x[0];x[0]=xtmp;ztmp=z[2];z[2]=z[0];z[0]=ztmp; }
- if (x[1] > x[2]) { xtmp=x[2];x[2]=x[1];x[1]=xtmp;ztmp=z[2];z[2]=z[1];z[1]=ztmp; }
- int dx[]={ x[0]-x[1],
- x[1]-x[2],
- x[2]-x[0]};
- btScalar dzx[3];
- dzx[0] = (dx[0]) ? (z[0]-z[1])/dx[0] : btScalar(0.f);
- dzx[1] = (dx[1]) ? (z[1]-z[2])/dx[1] : btScalar(0.f);
- dzx[2] = (dx[2]) ? (z[2]-z[0])/dx[2] : btScalar(0.f);
- btScalar v[3] = { dzx[0]*(mix-x[0])+z[0],
- dzx[1]*(mix-x[1])+z[1],
- dzx[2]*(mix-x[2])+z[2] };
- dx[0] = x[1]-x[0];
- dx[1] = x[0]-x[1];
- dx[2] = x[2]-x[0];
- btScalar* scan=&m_buffer[miy*m_sizes[0]+mix];
- for(int ix=mix;ix<mxx;++ix)
- {
- if(dx[0] >= 0 && POLICY::Process(*scan,v[0]))
- return(true);
- if(dx[1] >= 0 && POLICY::Process(*scan,v[1]))
- return(true);
- if(dx[2] >= 0 && POLICY::Process(*scan,v[2]))
- return(true);
- scan++;
- v[0] += dzx[0]; v[1] += dzx[1]; v[2] += dzx[2];
- dx[0]--; dx[1]++, dx[2]--;
- }
- } else
- {
- // general case
- const int dx[]={ y[0]-y[1],
- y[1]-y[2],
- y[2]-y[0]};
- const int dy[]={ x[1]-x[0]-dx[0]*width,
- x[2]-x[1]-dx[1]*width,
- x[0]-x[2]-dx[2]*width};
- const int a=x[2]*y[0]+x[0]*y[1]-x[2]*y[1]-x[0]*y[2]+x[1]*y[2]-x[1]*y[0];
- const btScalar ia=1/(btScalar)a;
- const btScalar dzx=ia*(y[2]*(z[1]-z[0])+y[1]*(z[0]-z[2])+y[0]*(z[2]-z[1]));
- const btScalar dzy=ia*(x[2]*(z[0]-z[1])+x[0]*(z[1]-z[2])+x[1]*(z[2]-z[0]))-(dzx*width);
- int c[]={ miy*x[1]+mix*y[0]-x[1]*y[0]-mix*y[1]+x[0]*y[1]-miy*x[0],
- miy*x[2]+mix*y[1]-x[2]*y[1]-mix*y[2]+x[1]*y[2]-miy*x[1],
- miy*x[0]+mix*y[2]-x[0]*y[2]-mix*y[0]+x[2]*y[0]-miy*x[2]};
- btScalar v=ia*((z[2]*c[0])+(z[0]*c[1])+(z[1]*c[2]));
- btScalar* scan=&m_buffer[miy*m_sizes[0]];
- for(int iy=miy;iy<mxy;++iy)
- {
- for(int ix=mix;ix<mxx;++ix)
- {
- if((c[0]>=0)&&(c[1]>=0)&&(c[2]>=0))
- {
- if(POLICY::Process(scan[ix],v))
- return(true);
- }
- c[0]+=dx[0];c[1]+=dx[1];c[2]+=dx[2];v+=dzx;
- }
- c[0]+=dy[0];c[1]+=dy[1];c[2]+=dy[2];v+=dzy;
- scan+=m_sizes[0];
- }
- }
- return(false);
- }
- // clip than write or check a polygon
- template <const int NP,typename POLICY>
- inline bool clipDraw( const btVector4* p,
- const float face,
- btScalar minarea)
- {
- btVector4 o[NP*2];
- int n=clip<NP>(p,o);
- bool earlyexit=false;
- if (n)
- {
- project(o,n);
- for(int i=2;i<n && !earlyexit;++i)
- {
- earlyexit|=draw<POLICY>(o[0],o[i-1],o[i],face,minarea);
- }
- }
- return(earlyexit);
- }
- // add a triangle (in model coordinate)
- // face = 0.f if face is double side,
- // = 1.f if face is single sided and scale is positive
- // = -1.f if face is single sided and scale is negative
- void appendOccluderM(const float* a,
- const float* b,
- const float* c,
- const float face)
- {
- btVector4 p[3];
- transformM(a,p[0]);
- transformM(b,p[1]);
- transformM(c,p[2]);
- clipDraw<3,WriteOCL>(p,face,btScalar(0.f));
- }
- // add a quad (in model coordinate)
- void appendOccluderM(const float* a,
- const float* b,
- const float* c,
- const float* d,
- const float face)
- {
- btVector4 p[4];
- transformM(a,p[0]);
- transformM(b,p[1]);
- transformM(c,p[2]);
- transformM(d,p[3]);
- clipDraw<4,WriteOCL>(p,face,btScalar(0.f));
- }
- // query occluder for a box (c=center, e=extend) in world coordinate
- inline bool queryOccluderW( const btVector3& c,
- const btVector3& e)
- {
- if (!m_occlusion)
- // no occlusion yet, no need to check
- return true;
- btVector4 x[8];
- transformW(btVector3(c[0]-e[0],c[1]-e[1],c[2]-e[2]),x[0]);
- transformW(btVector3(c[0]+e[0],c[1]-e[1],c[2]-e[2]),x[1]);
- transformW(btVector3(c[0]+e[0],c[1]+e[1],c[2]-e[2]),x[2]);
- transformW(btVector3(c[0]-e[0],c[1]+e[1],c[2]-e[2]),x[3]);
- transformW(btVector3(c[0]-e[0],c[1]-e[1],c[2]+e[2]),x[4]);
- transformW(btVector3(c[0]+e[0],c[1]-e[1],c[2]+e[2]),x[5]);
- transformW(btVector3(c[0]+e[0],c[1]+e[1],c[2]+e[2]),x[6]);
- transformW(btVector3(c[0]-e[0],c[1]+e[1],c[2]+e[2]),x[7]);
- for(int i=0;i<8;++i)
- {
- // the box is clipped, it's probably a large box, don't waste our time to check
- if((x[i][2]+x[i][3])<=0) return(true);
- }
- static const int d[]={ 1,0,3,2,
- 4,5,6,7,
- 4,7,3,0,
- 6,5,1,2,
- 7,6,2,3,
- 5,4,0,1};
- for(unsigned int i=0;i<(sizeof(d)/sizeof(d[0]));)
- {
- const btVector4 p[]={ x[d[i++]],
- x[d[i++]],
- x[d[i++]],
- x[d[i++]]};
- if(clipDraw<4,QueryOCL>(p,1.f,0.f))
- return(true);
- }
- return(false);
- }
-};
-
-
-struct DbvtCullingCallback : btDbvt::ICollide
-{
- PHY_CullingCallback m_clientCallback;
- void* m_userData;
- OcclusionBuffer *m_ocb;
-
- DbvtCullingCallback(PHY_CullingCallback clientCallback, void* userData)
- {
- m_clientCallback = clientCallback;
- m_userData = userData;
- m_ocb = NULL;
- }
- bool Descent(const btDbvtNode* node)
- {
- return(m_ocb->queryOccluderW(node->volume.Center(),node->volume.Extents()));
- }
- void Process(const btDbvtNode* node,btScalar depth)
- {
- Process(node);
- }
- void Process(const btDbvtNode* leaf)
- {
- btBroadphaseProxy* proxy=(btBroadphaseProxy*)leaf->data;
- // the client object is a graphic controller
- CcdGraphicController* ctrl = static_cast<CcdGraphicController*>(proxy->m_clientObject);
- KX_ClientObjectInfo* info = (KX_ClientObjectInfo*)ctrl->getNewClientInfo();
- if (m_ocb)
- {
- // means we are doing occlusion culling. Check if this object is an occluders
- KX_GameObject* gameobj = KX_GameObject::GetClientObject(info);
- if (gameobj && gameobj->GetOccluder())
- {
- double* fl = gameobj->GetOpenGLMatrixPtr()->getPointer();
- // this will create the occlusion buffer if not already done
- // and compute the transformation from model local space to clip space
- m_ocb->SetModelMatrix(fl);
- float face = (gameobj->IsNegativeScaling()) ? -1.0f : 1.0f;
- // walk through the meshes and for each add to buffer
- for (int i=0; i<gameobj->GetMeshCount(); i++)
- {
- RAS_MeshObject* meshobj = gameobj->GetMesh(i);
- const float *v1, *v2, *v3, *v4;
-
- int polycount = meshobj->NumPolygons();
- for (int j=0; j<polycount; j++)
- {
- RAS_Polygon* poly = meshobj->GetPolygon(j);
- switch (poly->VertexCount())
- {
- case 3:
- v1 = poly->GetVertex(0)->getXYZ();
- v2 = poly->GetVertex(1)->getXYZ();
- v3 = poly->GetVertex(2)->getXYZ();
- m_ocb->appendOccluderM(v1,v2,v3,((poly->IsTwoside())?0.f:face));
- break;
- case 4:
- v1 = poly->GetVertex(0)->getXYZ();
- v2 = poly->GetVertex(1)->getXYZ();
- v3 = poly->GetVertex(2)->getXYZ();
- v4 = poly->GetVertex(3)->getXYZ();
- m_ocb->appendOccluderM(v1,v2,v3,v4,((poly->IsTwoside())?0.f:face));
- break;
- }
- }
- }
- }
- }
- if (info)
- (*m_clientCallback)(info, m_userData);
- }
-};
-
-static OcclusionBuffer gOcb;
-bool CcdPhysicsEnvironment::cullingTest(PHY_CullingCallback callback, void* userData, PHY__Vector4 *planes, int nplanes, int occlusionRes)
-{
- if (!m_cullingTree)
- return false;
- DbvtCullingCallback dispatcher(callback, userData);
- btVector3 planes_n[6];
- btScalar planes_o[6];
- if (nplanes > 6)
- nplanes = 6;
- for (int i=0; i<nplanes; i++)
- {
- planes_n[i].setValue(planes[i][0], planes[i][1], planes[i][2]);
- planes_o[i] = planes[i][3];
- }
- // if occlusionRes != 0 => occlusion culling
- if (occlusionRes)
- {
- gOcb.setup(occlusionRes);
- dispatcher.m_ocb = &gOcb;
- // occlusion culling, the direction of the view is taken from the first plan which MUST be the near plane
- btDbvt::collideOCL(m_cullingTree->m_sets[1].m_root,planes_n,planes_o,planes_n[0],nplanes,dispatcher);
- btDbvt::collideOCL(m_cullingTree->m_sets[0].m_root,planes_n,planes_o,planes_n[0],nplanes,dispatcher);
- }else
- {
- btDbvt::collideKDOP(m_cullingTree->m_sets[1].m_root,planes_n,planes_o,nplanes,dispatcher);
- btDbvt::collideKDOP(m_cullingTree->m_sets[0].m_root,planes_n,planes_o,nplanes,dispatcher);
- }
- return true;
-}
-
-int CcdPhysicsEnvironment::getNumContactPoints()
-{
- return 0;
-}
-
-void CcdPhysicsEnvironment::getContactPoint(int i,float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ)
-{
-
-}
-
-
-
-
-btBroadphaseInterface* CcdPhysicsEnvironment::getBroadphase()
-{
- return m_dynamicsWorld->getBroadphase();
-}
-
-btDispatcher* CcdPhysicsEnvironment::getDispatcher()
-{
- return m_dynamicsWorld->getDispatcher();
-}
-
-void CcdPhysicsEnvironment::MergeEnvironment(CcdPhysicsEnvironment *other)
-{
- std::set<CcdPhysicsController*>::iterator it;
-
- while (other->m_controllers.begin() != other->m_controllers.end())
- {
- it= other->m_controllers.begin();
- CcdPhysicsController* ctrl= (*it);
-
- other->removeCcdPhysicsController(ctrl);
- this->addCcdPhysicsController(ctrl);
- }
-}
-
-CcdPhysicsEnvironment::~CcdPhysicsEnvironment()
-{
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
- m_wrapperVehicles.clear();
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
- //m_broadphase->DestroyScene();
- //delete broadphase ? release reference on broadphase ?
-
- //first delete scene, then dispatcher, because pairs have to release manifolds on the dispatcher
- //delete m_dispatcher;
- delete m_dynamicsWorld;
-
-
- if (NULL != m_ownPairCache)
- delete m_ownPairCache;
-
- if (NULL != m_ownDispatcher)
- delete m_ownDispatcher;
-
- if (NULL != m_solver)
- delete m_solver;
-
- if (NULL != m_debugDrawer)
- delete m_debugDrawer;
-
- if (NULL != m_filterCallback)
- delete m_filterCallback;
-
- if (NULL != m_collisionConfiguration)
- delete m_collisionConfiguration;
-
- if (NULL != m_broadphase)
- delete m_broadphase;
-
- if (NULL != m_cullingTree)
- delete m_cullingTree;
-
- if (NULL != m_cullingCache)
- delete m_cullingCache;
-
-}
-
-
-float CcdPhysicsEnvironment::getConstraintParam(int constraintId,int param)
-{
- btTypedConstraint* typedConstraint = getConstraintById(constraintId);
- switch (typedConstraint->getUserConstraintType())
- {
- case PHY_GENERIC_6DOF_CONSTRAINT:
- {
-
- switch (param)
- {
- case 0: case 1: case 2:
- {
- //param = 0..2 are linear constraint values
- btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint;
- genCons->calculateTransforms();
- return genCons->getRelativePivotPosition(param);
- break;
- }
- case 3: case 4: case 5:
- {
- //param = 3..5 are relative constraint (Euler) angles
- btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint;
- genCons->calculateTransforms();
- return genCons->getAngle(param-3);
- break;
- }
- default:
- {
- }
- }
- break;
- };
- default:
- {
- };
- };
- return 0.f;
-}
-
-void CcdPhysicsEnvironment::setConstraintParam(int constraintId,int param,float value0,float value1)
-{
- btTypedConstraint* typedConstraint = getConstraintById(constraintId);
- switch (typedConstraint->getUserConstraintType())
- {
- case PHY_GENERIC_6DOF_CONSTRAINT:
- {
-
- switch (param)
- {
- case 0: case 1: case 2: case 3: case 4: case 5:
- {
- //param = 0..5 are constraint limits, with low/high limit value
- btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint;
- genCons->setLimit(param,value0,value1);
- break;
- }
- case 6: case 7: case 8:
- {
- //param = 6,7,8 are translational motors, with value0=target velocity, value1 = max motor force
- btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint;
- int transMotorIndex = param-6;
- btTranslationalLimitMotor* transMotor = genCons->getTranslationalLimitMotor();
- transMotor->m_targetVelocity[transMotorIndex]= value0;
- transMotor->m_maxMotorForce[transMotorIndex]=value1;
- transMotor->m_enableMotor[transMotorIndex] = (value1>0.f);
- break;
- }
- case 9: case 10: case 11:
- {
- //param = 9,10,11 are rotational motors, with value0=target velocity, value1 = max motor force
- btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint;
- int angMotorIndex = param-9;
- btRotationalLimitMotor* rotMotor = genCons->getRotationalLimitMotor(angMotorIndex);
- rotMotor->m_enableMotor = (value1 > 0.f);
- rotMotor->m_targetVelocity = value0;
- rotMotor->m_maxMotorForce = value1;
- break;
- }
-
- case 12: case 13: case 14: case 15: case 16: case 17:
- {
- //param 13-17 are for motorized springs on each of the degrees of freedom
- btGeneric6DofSpringConstraint* genCons = (btGeneric6DofSpringConstraint*)typedConstraint;
- int springIndex = param-12;
- if (value0!=0.f)
- {
- bool springEnabled = true;
- genCons->setStiffness(springIndex,value0);
- genCons->setDamping(springIndex,value1);
- genCons->enableSpring(springIndex,springEnabled);
- genCons->setEquilibriumPoint(springIndex);
- } else
- {
- bool springEnabled = false;
- genCons->enableSpring(springIndex,springEnabled);
- }
- break;
- }
-
- default:
- {
- }
- }
- break;
- };
- default:
- {
- };
- };
-}
-
-btTypedConstraint* CcdPhysicsEnvironment::getConstraintById(int constraintId)
-{
-
- int numConstraints = m_dynamicsWorld->getNumConstraints();
- int i;
- for (i=0;i<numConstraints;i++)
- {
- btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
- if (constraint->getUserConstraintId()==constraintId)
- {
- return constraint;
- }
- }
- return 0;
-}
-
-
-void CcdPhysicsEnvironment::addSensor(PHY_IPhysicsController* ctrl)
-{
-
- CcdPhysicsController* ctrl1 = (CcdPhysicsController* )ctrl;
- // addSensor() is a "light" function for bullet because it is used
- // dynamically when the sensor is activated. Use enableCcdPhysicsController() instead
- //if (m_controllers.insert(ctrl1).second)
- //{
- // addCcdPhysicsController(ctrl1);
- //}
- enableCcdPhysicsController(ctrl1);
-}
-
-bool CcdPhysicsEnvironment::removeCollisionCallback(PHY_IPhysicsController* ctrl)
-{
- CcdPhysicsController* ccdCtrl = (CcdPhysicsController*)ctrl;
- if (!ccdCtrl->Unregister())
- return false;
- m_triggerControllers.erase(ccdCtrl);
- return true;
-}
-
-
-void CcdPhysicsEnvironment::removeSensor(PHY_IPhysicsController* ctrl)
-{
- disableCcdPhysicsController((CcdPhysicsController*)ctrl);
-}
-
-void CcdPhysicsEnvironment::addTouchCallback(int response_class, PHY_ResponseCallback callback, void *user)
-{
- /* printf("addTouchCallback\n(response class = %i)\n",response_class);
-
- //map PHY_ convention into SM_ convention
- switch (response_class)
- {
- case PHY_FH_RESPONSE:
- printf("PHY_FH_RESPONSE\n");
- break;
- case PHY_SENSOR_RESPONSE:
- printf("PHY_SENSOR_RESPONSE\n");
- break;
- case PHY_CAMERA_RESPONSE:
- printf("PHY_CAMERA_RESPONSE\n");
- break;
- case PHY_OBJECT_RESPONSE:
- printf("PHY_OBJECT_RESPONSE\n");
- break;
- case PHY_STATIC_RESPONSE:
- printf("PHY_STATIC_RESPONSE\n");
- break;
- default:
- assert(0);
- return;
- }
- */
-
- m_triggerCallbacks[response_class] = callback;
- m_triggerCallbacksUserPtrs[response_class] = user;
-
-}
-bool CcdPhysicsEnvironment::requestCollisionCallback(PHY_IPhysicsController* ctrl)
-{
- CcdPhysicsController* ccdCtrl = static_cast<CcdPhysicsController*>(ctrl);
-
- if (!ccdCtrl->Register())
- return false;
- m_triggerControllers.insert(ccdCtrl);
- return true;
-}
-
-void CcdPhysicsEnvironment::CallbackTriggers()
-{
- if (m_triggerCallbacks[PHY_OBJECT_RESPONSE] || (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints)))
- {
- //walk over all overlapping pairs, and if one of the involved bodies is registered for trigger callback, perform callback
- btDispatcher* dispatcher = m_dynamicsWorld->getDispatcher();
- int numManifolds = dispatcher->getNumManifolds();
- for (int i=0;i<numManifolds;i++)
- {
- btPersistentManifold* manifold = dispatcher->getManifoldByIndexInternal(i);
- int numContacts = manifold->getNumContacts();
- if (numContacts)
- {
- btRigidBody* rb0 = static_cast<btRigidBody*>(manifold->getBody0());
- btRigidBody* rb1 = static_cast<btRigidBody*>(manifold->getBody1());
- if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints))
- {
- for (int j=0;j<numContacts;j++)
- {
- btVector3 color(1,0,0);
- const btManifoldPoint& cp = manifold->getContactPoint(j);
- if (m_debugDrawer)
- m_debugDrawer->drawContactPoint(cp.m_positionWorldOnB,cp.m_normalWorldOnB,cp.getDistance(),cp.getLifeTime(),color);
- }
- }
- btRigidBody* obj0 = rb0;
- btRigidBody* obj1 = rb1;
-
- //m_internalOwner is set in 'addPhysicsController'
- CcdPhysicsController* ctrl0 = static_cast<CcdPhysicsController*>(obj0->getUserPointer());
- CcdPhysicsController* ctrl1 = static_cast<CcdPhysicsController*>(obj1->getUserPointer());
-
- std::set<CcdPhysicsController*>::const_iterator i = m_triggerControllers.find(ctrl0);
- if (i == m_triggerControllers.end())
- {
- i = m_triggerControllers.find(ctrl1);
- }
-
- if (!(i == m_triggerControllers.end()))
- {
- m_triggerCallbacks[PHY_OBJECT_RESPONSE](m_triggerCallbacksUserPtrs[PHY_OBJECT_RESPONSE],
- ctrl0,ctrl1,0);
- }
- // Bullet does not refresh the manifold contact point for object without contact response
- // may need to remove this when a newer Bullet version is integrated
- if (!dispatcher->needsResponse(rb0, rb1))
- {
- // Refresh algorithm fails sometimes when there is penetration
- // (usuall the case with ghost and sensor objects)
- // Let's just clear the manifold, in any case, it is recomputed on each frame.
- manifold->clearManifold(); //refreshContactPoints(rb0->getCenterOfMassTransform(),rb1->getCenterOfMassTransform());
- }
- }
- }
-
-
-
- }
-
-
-}
-
-// This call back is called before a pair is added in the cache
-// Handy to remove objects that must be ignored by sensors
-bool CcdOverlapFilterCallBack::needBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const
-{
- btCollisionObject *colObj0, *colObj1;
- CcdPhysicsController *sensorCtrl, *objCtrl;
- bool collides;
- // first check the filters
- collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
- collides = collides && (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
- if (!collides)
- return false;
-
- // additional check for sensor object
- if (proxy0->m_collisionFilterGroup & btBroadphaseProxy::SensorTrigger)
- {
- // this is a sensor object, the other one can't be a sensor object because
- // they exclude each other in the above test
- assert(!(proxy1->m_collisionFilterGroup & btBroadphaseProxy::SensorTrigger));
- colObj0 = (btCollisionObject*)proxy0->m_clientObject;
- colObj1 = (btCollisionObject*)proxy1->m_clientObject;
- }
- else if (proxy1->m_collisionFilterGroup & btBroadphaseProxy::SensorTrigger)
- {
- colObj0 = (btCollisionObject*)proxy1->m_clientObject;
- colObj1 = (btCollisionObject*)proxy0->m_clientObject;
- }
- else
- {
- return true;
- }
- if (!colObj0 || !colObj1)
- return false;
- sensorCtrl = static_cast<CcdPhysicsController*>(colObj0->getUserPointer());
- objCtrl = static_cast<CcdPhysicsController*>(colObj1->getUserPointer());
- if (m_physEnv->m_triggerCallbacks[PHY_BROADPH_RESPONSE])
- {
- return m_physEnv->m_triggerCallbacks[PHY_BROADPH_RESPONSE](m_physEnv->m_triggerCallbacksUserPtrs[PHY_BROADPH_RESPONSE], sensorCtrl, objCtrl, 0);
- }
- return true;
-}
-
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
-
-//complex constraint for vehicles
-PHY_IVehicle* CcdPhysicsEnvironment::getVehicleConstraint(int constraintId)
-{
- int i;
-
- int numVehicles = m_wrapperVehicles.size();
- for (i=0;i<numVehicles;i++)
- {
- WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i];
- if (wrapperVehicle->GetVehicle()->getUserConstraintId() == constraintId)
- return wrapperVehicle;
- }
-
- return 0;
-}
-
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
-
-int currentController = 0;
-int numController = 0;
-
-
-
-
-PHY_IPhysicsController* CcdPhysicsEnvironment::CreateSphereController(float radius,const PHY__Vector3& position)
-{
-
- CcdConstructionInfo cinfo;
- memset(&cinfo, 0, sizeof(cinfo)); /* avoid uninitialized values */
- cinfo.m_collisionShape = new btSphereShape(radius); // memory leak! The shape is not deleted by Bullet and we cannot add it to the KX_Scene.m_shapes list
- cinfo.m_MotionState = 0;
- cinfo.m_physicsEnv = this;
- // declare this object as Dyamic rather then static!!
- // The reason as it is designed to detect all type of object, including static object
- // It would cause static-static message to be printed on the console otherwise
- cinfo.m_collisionFlags |= btCollisionObject::CF_NO_CONTACT_RESPONSE | btCollisionObject::CF_STATIC_OBJECT;
- DefaultMotionState* motionState = new DefaultMotionState();
- cinfo.m_MotionState = motionState;
- // we will add later the possibility to select the filter from option
- cinfo.m_collisionFilterMask = CcdConstructionInfo::AllFilter ^ CcdConstructionInfo::SensorFilter;
- cinfo.m_collisionFilterGroup = CcdConstructionInfo::SensorFilter;
- cinfo.m_bSensor = true;
- motionState->m_worldTransform.setIdentity();
- motionState->m_worldTransform.setOrigin(btVector3(position[0],position[1],position[2]));
-
- CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo);
-
- return sphereController;
-}
-
-int findClosestNode(btSoftBody* sb,const btVector3& worldPoint);
-int findClosestNode(btSoftBody* sb,const btVector3& worldPoint)
-{
- int node = -1;
-
- btSoftBody::tNodeArray& nodes(sb->m_nodes);
- float maxDistSqr = 1e30f;
-
- for (int n=0;n<nodes.size();n++)
- {
- btScalar distSqr = (nodes[n].m_x - worldPoint).length2();
- if (distSqr<maxDistSqr)
- {
- maxDistSqr = distSqr;
- node = n;
- }
- }
- return node;
-}
-
-int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl0,class PHY_IPhysicsController* ctrl1,PHY_ConstraintType type,
- float pivotX,float pivotY,float pivotZ,
- float axisX,float axisY,float axisZ,
- float axis1X,float axis1Y,float axis1Z,
- float axis2X,float axis2Y,float axis2Z,int flags
- )
-{
-
- bool disableCollisionBetweenLinkedBodies = (0!=(flags & CCD_CONSTRAINT_DISABLE_LINKED_COLLISION));
-
-
-
- CcdPhysicsController* c0 = (CcdPhysicsController*)ctrl0;
- CcdPhysicsController* c1 = (CcdPhysicsController*)ctrl1;
-
- btRigidBody* rb0 = c0 ? c0->GetRigidBody() : 0;
- btRigidBody* rb1 = c1 ? c1->GetRigidBody() : 0;
-
-
-
-
- bool rb0static = rb0 ? rb0->isStaticOrKinematicObject() : true;
- bool rb1static = rb1 ? rb1->isStaticOrKinematicObject() : true;
-
- btCollisionObject* colObj0 = c0->GetCollisionObject();
- if (!colObj0)
- {
- return 0;
- }
-
- btVector3 pivotInA(pivotX,pivotY,pivotZ);
-
-
-
- //it might be a soft body, let's try
- btSoftBody* sb0 = c0 ? c0->GetSoftBody() : 0;
- btSoftBody* sb1 = c1 ? c1->GetSoftBody() : 0;
- if (sb0 && sb1)
- {
- //not between two soft bodies?
- return 0;
- }
-
- if (sb0)
- {
- //either cluster or node attach, let's find closest node first
- //the soft body doesn't have a 'real' world transform, so get its initial world transform for now
- btVector3 pivotPointSoftWorld = sb0->m_initialWorldTransform(pivotInA);
- int node=findClosestNode(sb0,pivotPointSoftWorld);
- if (node >=0)
- {
- bool clusterconstaint = false;
-/*
- switch (type)
- {
- case PHY_LINEHINGE_CONSTRAINT:
- {
- if (sb0->clusterCount() && rb1)
- {
- btSoftBody::LJoint::Specs ls;
- ls.erp=0.5f;
- ls.position=sb0->clusterCom(0);
- sb0->appendLinearJoint(ls,rb1);
- clusterconstaint = true;
- break;
- }
- }
- case PHY_GENERIC_6DOF_CONSTRAINT:
- {
- if (sb0->clusterCount() && rb1)
- {
- btSoftBody::AJoint::Specs as;
- as.erp = 1;
- as.cfm = 1;
- as.axis.setValue(axisX,axisY,axisZ);
- sb0->appendAngularJoint(as,rb1);
- clusterconstaint = true;
- break;
- }
-
- break;
- }
- default:
- {
-
- }
- };
- */
-
- if (!clusterconstaint)
- {
- if (rb1)
- {
- sb0->appendAnchor(node,rb1,disableCollisionBetweenLinkedBodies);
- } else
- {
- sb0->setMass(node,0.f);
- }
- }
-
-
- }
- return 0;//can't remove soft body anchors yet
- }
-
- if (sb1)
- {
- btVector3 pivotPointAWorld = colObj0->getWorldTransform()(pivotInA);
- int node=findClosestNode(sb1,pivotPointAWorld);
- if (node >=0)
- {
- bool clusterconstaint = false;
-
- /*
- switch (type)
- {
- case PHY_LINEHINGE_CONSTRAINT:
- {
- if (sb1->clusterCount() && rb0)
- {
- btSoftBody::LJoint::Specs ls;
- ls.erp=0.5f;
- ls.position=sb1->clusterCom(0);
- sb1->appendLinearJoint(ls,rb0);
- clusterconstaint = true;
- break;
- }
- }
- case PHY_GENERIC_6DOF_CONSTRAINT:
- {
- if (sb1->clusterCount() && rb0)
- {
- btSoftBody::AJoint::Specs as;
- as.erp = 1;
- as.cfm = 1;
- as.axis.setValue(axisX,axisY,axisZ);
- sb1->appendAngularJoint(as,rb0);
- clusterconstaint = true;
- break;
- }
-
- break;
- }
- default:
- {
-
-
- }
- };*/
-
-
- if (!clusterconstaint)
- {
- if (rb0)
- {
- sb1->appendAnchor(node,rb0,disableCollisionBetweenLinkedBodies);
- } else
- {
- sb1->setMass(node,0.f);
- }
- }
-
-
- }
- return 0;//can't remove soft body anchors yet
- }
-
- if (rb0static && rb1static)
- {
-
- return 0;
- }
-
-
- if (!rb0)
- return 0;
-
-
- btVector3 pivotInB = rb1 ? rb1->getCenterOfMassTransform().inverse()(rb0->getCenterOfMassTransform()(pivotInA)) :
- rb0->getCenterOfMassTransform() * pivotInA;
- btVector3 axisInA(axisX,axisY,axisZ);
-
-
- bool angularOnly = false;
-
- switch (type)
- {
- case PHY_POINT2POINT_CONSTRAINT:
- {
-
- btPoint2PointConstraint* p2p = 0;
-
- if (rb1)
- {
- p2p = new btPoint2PointConstraint(*rb0,
- *rb1,pivotInA,pivotInB);
- } else
- {
- p2p = new btPoint2PointConstraint(*rb0,
- pivotInA);
- }
-
- m_dynamicsWorld->addConstraint(p2p,disableCollisionBetweenLinkedBodies);
-// m_constraints.push_back(p2p);
-
- p2p->setUserConstraintId(gConstraintUid++);
- p2p->setUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return p2p->getUserConstraintId();
-
- break;
- }
-
- case PHY_GENERIC_6DOF_CONSTRAINT:
- {
- btGeneric6DofConstraint* genericConstraint = 0;
-
- if (rb1)
- {
- btTransform frameInA;
- btTransform frameInB;
-
- btVector3 axis1(axis1X,axis1Y,axis1Z), axis2(axis2X,axis2Y,axis2Z);
- if (axis1.length() == 0.0)
- {
- btPlaneSpace1( axisInA, axis1, axis2 );
- }
-
- frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(),
- axisInA.y(), axis1.y(), axis2.y(),
- axisInA.z(), axis1.z(), axis2.z() );
- frameInA.setOrigin( pivotInA );
-
- btTransform inv = rb1->getCenterOfMassTransform().inverse();
-
- btTransform globalFrameA = rb0->getCenterOfMassTransform() * frameInA;
-
- frameInB = inv * globalFrameA;
- bool useReferenceFrameA = true;
-
- genericConstraint = new btGeneric6DofSpringConstraint(
- *rb0,*rb1,
- frameInA,frameInB,useReferenceFrameA);
-
-
- } else
- {
- static btRigidBody s_fixedObject2( 0,0,0);
- btTransform frameInA;
- btTransform frameInB;
-
- btVector3 axis1, axis2;
- btPlaneSpace1( axisInA, axis1, axis2 );
-
- frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(),
- axisInA.y(), axis1.y(), axis2.y(),
- axisInA.z(), axis1.z(), axis2.z() );
-
- frameInA.setOrigin( pivotInA );
-
- ///frameInB in worldspace
- frameInB = rb0->getCenterOfMassTransform() * frameInA;
-
- bool useReferenceFrameA = true;
- genericConstraint = new btGeneric6DofSpringConstraint(
- *rb0,s_fixedObject2,
- frameInA,frameInB,useReferenceFrameA);
- }
-
- if (genericConstraint)
- {
- //m_constraints.push_back(genericConstraint);
- m_dynamicsWorld->addConstraint(genericConstraint,disableCollisionBetweenLinkedBodies);
- genericConstraint->setUserConstraintId(gConstraintUid++);
- genericConstraint->setUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return genericConstraint->getUserConstraintId();
- }
-
- break;
- }
- case PHY_CONE_TWIST_CONSTRAINT:
- {
- btConeTwistConstraint* coneTwistContraint = 0;
-
-
- if (rb1)
- {
- btTransform frameInA;
- btTransform frameInB;
-
- btVector3 axis1(axis1X,axis1Y,axis1Z), axis2(axis2X,axis2Y,axis2Z);
- if (axis1.length() == 0.0)
- {
- btPlaneSpace1( axisInA, axis1, axis2 );
- }
-
- frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(),
- axisInA.y(), axis1.y(), axis2.y(),
- axisInA.z(), axis1.z(), axis2.z() );
- frameInA.setOrigin( pivotInA );
-
- btTransform inv = rb1->getCenterOfMassTransform().inverse();
-
- btTransform globalFrameA = rb0->getCenterOfMassTransform() * frameInA;
-
- frameInB = inv * globalFrameA;
-
- coneTwistContraint = new btConeTwistConstraint( *rb0,*rb1,
- frameInA,frameInB);
-
-
- } else
- {
- static btRigidBody s_fixedObject2( 0,0,0);
- btTransform frameInA;
- btTransform frameInB;
-
- btVector3 axis1, axis2;
- btPlaneSpace1( axisInA, axis1, axis2 );
-
- frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(),
- axisInA.y(), axis1.y(), axis2.y(),
- axisInA.z(), axis1.z(), axis2.z() );
-
- frameInA.setOrigin( pivotInA );
-
- ///frameInB in worldspace
- frameInB = rb0->getCenterOfMassTransform() * frameInA;
-
- coneTwistContraint = new btConeTwistConstraint(
- *rb0,s_fixedObject2,
- frameInA,frameInB);
- }
-
- if (coneTwistContraint)
- {
- //m_constraints.push_back(genericConstraint);
- m_dynamicsWorld->addConstraint(coneTwistContraint,disableCollisionBetweenLinkedBodies);
- coneTwistContraint->setUserConstraintId(gConstraintUid++);
- coneTwistContraint->setUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return coneTwistContraint->getUserConstraintId();
- }
-
-
-
- break;
- }
- case PHY_ANGULAR_CONSTRAINT:
- angularOnly = true;
-
-
- case PHY_LINEHINGE_CONSTRAINT:
- {
- btHingeConstraint* hinge = 0;
-
- if (rb1)
- {
- btVector3 axisInB = rb1 ?
- (rb1->getCenterOfMassTransform().getBasis().inverse()*(rb0->getCenterOfMassTransform().getBasis() * axisInA)) :
- rb0->getCenterOfMassTransform().getBasis() * axisInA;
-
- hinge = new btHingeConstraint(
- *rb0,
- *rb1,pivotInA,pivotInB,axisInA,axisInB);
-
-
- } else
- {
- hinge = new btHingeConstraint(*rb0,
- pivotInA,axisInA);
-
- }
- hinge->setAngularOnly(angularOnly);
-
- //m_constraints.push_back(hinge);
- m_dynamicsWorld->addConstraint(hinge,disableCollisionBetweenLinkedBodies);
- hinge->setUserConstraintId(gConstraintUid++);
- hinge->setUserConstraintType(type);
- //64 bit systems can't cast pointer to int. could use size_t instead.
- return hinge->getUserConstraintId();
- break;
- }
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
-
- case PHY_VEHICLE_CONSTRAINT:
- {
- btRaycastVehicle::btVehicleTuning* tuning = new btRaycastVehicle::btVehicleTuning();
- btRigidBody* chassis = rb0;
- btDefaultVehicleRaycaster* raycaster = new btDefaultVehicleRaycaster(m_dynamicsWorld);
- btRaycastVehicle* vehicle = new btRaycastVehicle(*tuning,chassis,raycaster);
- WrapperVehicle* wrapperVehicle = new WrapperVehicle(vehicle,ctrl0);
- m_wrapperVehicles.push_back(wrapperVehicle);
- m_dynamicsWorld->addVehicle(vehicle);
- vehicle->setUserConstraintId(gConstraintUid++);
- vehicle->setUserConstraintType(type);
- return vehicle->getUserConstraintId();
-
- break;
- };
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
- default:
- {
- }
- };
-
- //btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB
-
- return 0;
-
-}
-
-
-
-PHY_IPhysicsController* CcdPhysicsEnvironment::CreateConeController(float coneradius,float coneheight)
-{
- CcdConstructionInfo cinfo;
- memset(&cinfo, 0, sizeof(cinfo)); /* avoid uninitialized values */
- // we don't need a CcdShapeConstructionInfo for this shape:
- // it is simple enough for the standard copy constructor (see CcdPhysicsController::GetReplica)
- cinfo.m_collisionShape = new btConeShape(coneradius,coneheight);
- cinfo.m_MotionState = 0;
- cinfo.m_physicsEnv = this;
- cinfo.m_collisionFlags |= btCollisionObject::CF_NO_CONTACT_RESPONSE | btCollisionObject::CF_STATIC_OBJECT;
- DefaultMotionState* motionState = new DefaultMotionState();
- cinfo.m_MotionState = motionState;
-
- // we will add later the possibility to select the filter from option
- cinfo.m_collisionFilterMask = CcdConstructionInfo::AllFilter ^ CcdConstructionInfo::SensorFilter;
- cinfo.m_collisionFilterGroup = CcdConstructionInfo::SensorFilter;
- cinfo.m_bSensor = true;
- motionState->m_worldTransform.setIdentity();
-// motionState->m_worldTransform.setOrigin(btVector3(position[0],position[1],position[2]));
-
- CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo);
-
-
- return sphereController;
-}
-
-float CcdPhysicsEnvironment::getAppliedImpulse(int constraintid)
-{
- int i;
- int numConstraints = m_dynamicsWorld->getNumConstraints();
- for (i=0;i<numConstraints;i++)
- {
- btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
- if (constraint->getUserConstraintId() == constraintid)
- {
- return constraint->getAppliedImpulse();
- }
- }
-
- return 0.f;
-}
diff --git a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h b/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h
deleted file mode 100644
index c6e759743a9..00000000000
--- a/source/gameengine/Physics/Bullet/CcdPhysicsEnvironment.h
+++ /dev/null
@@ -1,285 +0,0 @@
-/*
-Bullet Continuous Collision Detection and Physics Library
-Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
-
-This software is provided 'as-is', without any express or implied warranty.
-In no event will the authors be held liable for any damages arising from the use of this software.
-Permission is granted to anyone to use this software for any purpose,
-including commercial applications, and to alter it and redistribute it freely,
-subject to the following restrictions:
-
-1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
-2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
-3. This notice may not be removed or altered from any source distribution.
-*/
-
-#ifndef CCDPHYSICSENVIRONMENT
-#define CCDPHYSICSENVIRONMENT
-
-#include "PHY_IPhysicsEnvironment.h"
-#include <vector>
-#include <set>
-class CcdPhysicsController;
-class CcdGraphicController;
-#include "LinearMath/btVector3.h"
-#include "LinearMath/btTransform.h"
-
-
-
-
-class btTypedConstraint;
-class btSimulationIslandManager;
-class btCollisionDispatcher;
-class btDispatcher;
-//#include "btBroadphaseInterface.h"
-
-//switch on/off new vehicle support
-#define NEW_BULLET_VEHICLE_SUPPORT 1
-
-#include "BulletDynamics/ConstraintSolver/btContactSolverInfo.h"
-
-class WrapperVehicle;
-class btPersistentManifold;
-class btBroadphaseInterface;
-struct btDbvtBroadphase;
-class btOverlappingPairCache;
-class btIDebugDraw;
-class PHY_IVehicle;
-class CcdOverlapFilterCallBack;
-
-/// CcdPhysicsEnvironment is an experimental mainloop for physics simulation using optional continuous collision detection.
-/// Physics Environment takes care of stepping the simulation and is a container for physics entities.
-/// It stores rigidbodies,constraints, materials etc.
-/// A derived class may be able to 'construct' entities by loading and/or converting
-class CcdPhysicsEnvironment : public PHY_IPhysicsEnvironment
-{
- friend class CcdOverlapFilterCallBack;
- btVector3 m_gravity;
-
-protected:
- btIDebugDraw* m_debugDrawer;
-
- class btDefaultCollisionConfiguration* m_collisionConfiguration;
- class btBroadphaseInterface* m_broadphase; // broadphase for dynamic world
- // for culling only
- btOverlappingPairCache* m_cullingCache;
- struct btDbvtBroadphase* m_cullingTree; // broadphase for culling
-
- //solver iterations
- int m_numIterations;
-
- //timestep subdivisions
- int m_numTimeSubSteps;
-
-
- int m_ccdMode;
- int m_solverType;
- int m_profileTimings;
- bool m_enableSatCollisionDetection;
-
- btContactSolverInfo m_solverInfo;
-
- void processFhSprings(double curTime,float timeStep);
-
- public:
- CcdPhysicsEnvironment(bool useDbvtCulling, btDispatcher* dispatcher=0, btOverlappingPairCache* pairCache=0);
-
- virtual ~CcdPhysicsEnvironment();
-
- /////////////////////////////////////
- //PHY_IPhysicsEnvironment interface
- /////////////////////////////////////
-
- /// Perform an integration step of duration 'timeStep'.
-
- virtual void setDebugDrawer(btIDebugDraw* debugDrawer);
-
- virtual void setNumIterations(int numIter);
- virtual void setNumTimeSubSteps(int numTimeSubSteps)
- {
- m_numTimeSubSteps = numTimeSubSteps;
- }
- virtual void setDeactivationTime(float dTime);
- virtual void setDeactivationLinearTreshold(float linTresh) ;
- virtual void setDeactivationAngularTreshold(float angTresh) ;
- virtual void setContactBreakingTreshold(float contactBreakingTreshold) ;
- virtual void setCcdMode(int ccdMode);
- virtual void setSolverType(int solverType);
- virtual void setSolverSorConstant(float sor);
- virtual void setSolverTau(float tau);
- virtual void setSolverDamping(float damping);
- virtual void setLinearAirDamping(float damping);
- virtual void setUseEpa(bool epa) ;
-
- virtual void beginFrame();
- virtual void endFrame() {};
- /// Perform an integration step of duration 'timeStep'.
- virtual bool proceedDeltaTime(double curTime,float timeStep,float interval);
-
- virtual void debugDrawWorld();
-// virtual bool proceedDeltaTimeOneStep(float timeStep);
-
- virtual void setFixedTimeStep(bool useFixedTimeStep,float fixedTimeStep){};
- //returns 0.f if no fixed timestep is used
-
- virtual float getFixedTimeStep(){ return 0.f;};
-
- virtual void setDebugMode(int debugMode);
-
- virtual void setGravity(float x,float y,float z);
- virtual void getGravity(PHY__Vector3& grav);
-
-
- virtual int createConstraint(class PHY_IPhysicsController* ctrl,class PHY_IPhysicsController* ctrl2,PHY_ConstraintType type,
- float pivotX,float pivotY,float pivotZ,
- float axisX,float axisY,float axisZ,
- float axis1X=0,float axis1Y=0,float axis1Z=0,
- float axis2X=0,float axis2Y=0,float axis2Z=0,int flag=0
- );
-
-
- //Following the COLLADA physics specification for constraints
- virtual int createUniversalD6Constraint(
- class PHY_IPhysicsController* ctrlRef,class PHY_IPhysicsController* ctrlOther,
- btTransform& localAttachmentFrameRef,
- btTransform& localAttachmentOther,
- const btVector3& linearMinLimits,
- const btVector3& linearMaxLimits,
- const btVector3& angularMinLimits,
- const btVector3& angularMaxLimits,int flags
- );
-
-
- virtual void setConstraintParam(int constraintId,int param,float value,float value1);
-
- virtual float getConstraintParam(int constraintId,int param);
-
- virtual void removeConstraint(int constraintid);
-
- virtual float getAppliedImpulse(int constraintid);
-
-
- virtual void CallbackTriggers();
-
-
-#ifdef NEW_BULLET_VEHICLE_SUPPORT
- //complex constraint for vehicles
- virtual PHY_IVehicle* getVehicleConstraint(int constraintId);
-#else
- virtual class PHY_IVehicle* getVehicleConstraint(int constraintId)
- {
- return 0;
- }
-#endif //NEW_BULLET_VEHICLE_SUPPORT
-
- btTypedConstraint* getConstraintById(int constraintId);
-
- virtual PHY_IPhysicsController* rayTest(PHY_IRayCastFilterCallback &filterCallback, float fromX,float fromY,float fromZ, float toX,float toY,float toZ);
- virtual bool cullingTest(PHY_CullingCallback callback, void* userData, PHY__Vector4* planes, int nplanes, int occlusionRes);
-
-
- //Methods for gamelogic collision/physics callbacks
- virtual void addSensor(PHY_IPhysicsController* ctrl);
- virtual void removeSensor(PHY_IPhysicsController* ctrl);
- virtual void addTouchCallback(int response_class, PHY_ResponseCallback callback, void *user);
- virtual bool requestCollisionCallback(PHY_IPhysicsController* ctrl);
- virtual bool removeCollisionCallback(PHY_IPhysicsController* ctrl);
- //These two methods are used *solely* to create controllers for Near/Radar sensor! Don't use for anything else
- virtual PHY_IPhysicsController* CreateSphereController(float radius,const PHY__Vector3& position);
- virtual PHY_IPhysicsController* CreateConeController(float coneradius,float coneheight);
-
-
- virtual int getNumContactPoints();
-
- virtual void getContactPoint(int i,float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ);
-
- //////////////////////
- //CcdPhysicsEnvironment interface
- ////////////////////////
-
- void addCcdPhysicsController(CcdPhysicsController* ctrl);
-
- bool removeCcdPhysicsController(CcdPhysicsController* ctrl);
-
- void updateCcdPhysicsController(CcdPhysicsController* ctrl, btScalar newMass, int newCollisionFlags, short int newCollisionGroup, short int newCollisionMask);
-
- void disableCcdPhysicsController(CcdPhysicsController* ctrl);
-
- void enableCcdPhysicsController(CcdPhysicsController* ctrl);
-
- void refreshCcdPhysicsController(CcdPhysicsController* ctrl);
-
- void addCcdGraphicController(CcdGraphicController* ctrl);
-
- void removeCcdGraphicController(CcdGraphicController* ctrl);
-
- btBroadphaseInterface* getBroadphase();
- btDbvtBroadphase* getCullingTree() { return m_cullingTree; }
-
- btDispatcher* getDispatcher();
-
-
- bool IsSatCollisionDetectionEnabled() const
- {
- return m_enableSatCollisionDetection;
- }
-
- void EnableSatCollisionDetection(bool enableSat)
- {
- m_enableSatCollisionDetection = enableSat;
- }
-
-
- const btPersistentManifold* GetManifold(int index) const;
-
-
- void SyncMotionStates(float timeStep);
-
- class btSoftRigidDynamicsWorld* getDynamicsWorld()
- {
- return m_dynamicsWorld;
- }
-
- class btConstraintSolver* GetConstraintSolver();
-
- void MergeEnvironment(CcdPhysicsEnvironment *other);
-
- protected:
-
-
-
- std::set<CcdPhysicsController*> m_controllers;
- std::set<CcdPhysicsController*> m_triggerControllers;
-
- PHY_ResponseCallback m_triggerCallbacks[PHY_NUM_RESPONSE];
- void* m_triggerCallbacksUserPtrs[PHY_NUM_RESPONSE];
-
- std::vector<WrapperVehicle*> m_wrapperVehicles;
-
- //use explicit btSoftRigidDynamicsWorld/btDiscreteDynamicsWorld* so that we have access to
- //btDiscreteDynamicsWorld::addRigidBody(body,filter,group)
- //so that we can set the body collision filter/group at the time of creation
- //and not afterwards (breaks the collision system for radar/near sensor)
- //Ideally we would like to have access to this function from the btDynamicsWorld interface
- //class btDynamicsWorld* m_dynamicsWorld;
- class btSoftRigidDynamicsWorld* m_dynamicsWorld;
-
- class btConstraintSolver* m_solver;
-
- class btOverlappingPairCache* m_ownPairCache;
-
- class CcdOverlapFilterCallBack* m_filterCallback;
-
- class btDispatcher* m_ownDispatcher;
-
- bool m_scalingPropagated;
-
-
-#ifdef WITH_CXX_GUARDEDALLOC
-public:
- void *operator new(size_t num_bytes) { return MEM_mallocN(num_bytes, "GE:CcdPhysicsEnvironment"); }
- void operator delete( void *mem ) { MEM_freeN(mem); }
-#endif
-};
-
-#endif //CCDPHYSICSENVIRONMENT
diff --git a/source/gameengine/Physics/Bullet/Makefile b/source/gameengine/Physics/Bullet/Makefile
deleted file mode 100644
index 0514565534d..00000000000
--- a/source/gameengine/Physics/Bullet/Makefile
+++ /dev/null
@@ -1,55 +0,0 @@
-#
-# $Id$
-#
-# ***** BEGIN GPL LICENSE BLOCK *****
-#
-# This program is free software; you can redistribute it and/or
-# modify it under the terms of the GNU General Public License
-# as published by the Free Software Foundation; either version 2
-# of the License, or (at your option) any later version.
-#
-# This program is distributed in the hope that it will be useful,
-# but WITHOUT ANY WARRANTY; without even the implied warranty of
-# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
-# GNU General Public License for more details.
-#
-# You should have received a copy of the GNU General Public License
-# along with this program; if not, write to the Free Software Foundation,
-# Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
-#
-# The Original Code is Copyright (C) 2001-2002 by NaN Holding BV.
-# All rights reserved.
-#
-# The Original Code is: all of this file.
-#
-# Contributor(s): none yet.
-#
-# ***** END GPL LICENSE BLOCK *****
-#
-#
-
-LIBNAME = blbullet
-DIR = $(OCGDIR)/gameengine/blphys/$(LIBNAME)
-
-include nan_compile.mk
-
-CCFLAGS += $(LEVEL_1_CPP_WARNINGS)
-
-CPPFLAGS += -I$(NAN_BULLET2)/include
-CPPFLAGS += -I$(NAN_GUARDEDALLOC)/include
-CPPFLAGS += -I$(NAN_STRING)/include
-CPPFLAGS += -I$(NAN_MOTO)/include
-CPPFLAGS += -I$(NAN_GLEW)/include
-CPPFLAGS += -I$(NAN_PYTHON)/include/python$(NAN_PYTHON_VERSION)
-CPPFLAGS += -I../../../kernel/gen_system
-CPPFLAGS += -I../../Physics/common
-CPPFLAGS += -I../../Physics/Dummy
-CPPFLAGS += -I../../Rasterizer
-CPPFLAGS += -I../../Ketsji
-CPPFLAGS += -I../../Expressions
-CPPFLAGS += -I../../GameLogic
-CPPFLAGS += -I../../SceneGraph
-CPPFLAGS += -I../../../../source/blender/makesdna
-CPPFLAGS += -I../../../../source/blender/blenkernel
-CPPFLAGS += -I../../../../source/blender/blenlib
-
diff --git a/source/gameengine/Physics/Bullet/SConscript b/source/gameengine/Physics/Bullet/SConscript
deleted file mode 100644
index 2554ada2e8c..00000000000
--- a/source/gameengine/Physics/Bullet/SConscript
+++ /dev/null
@@ -1,31 +0,0 @@
-#!/usr/bin/python
-Import ('env')
-
-sources = 'CcdPhysicsEnvironment.cpp CcdPhysicsController.cpp CcdGraphicController.cpp'
-
-incs = '. ../common'
-incs += ' #source/kernel/gen_system'
-incs += ' #intern/string'
-incs += ' #intern/moto/include'
-incs += ' #extern/glew/include'
-incs += ' #source/gameengine/Rasterizer'
-incs += ' #source/gameengine/Ketsji'
-incs += ' #source/gameengine/Expressions'
-incs += ' #source/gameengine/GameLogic'
-incs += ' #source/gameengine/SceneGraph'
-incs += ' #source/blender/makesdna'
-incs += ' #source/blender/bmesh'
-incs += ' #source/blender/blenkernel'
-incs += ' #source/blender/blenlib'
-incs += ' #intern/guardedalloc'
-
-incs += ' ' + env['BF_BULLET_INC']
-
-defs = []
-
-if env['WITH_BF_PYTHON']:
- incs += ' ' + env['BF_PYTHON_INC']
-else:
- defs.append('DISABLE_PYTHON')
-
-env.BlenderLib ( 'bf_bullet', Split(sources), Split(incs), defs, libtype=['core','player'], priority=[350,50], cxx_compileflags=env['BGE_CXXFLAGS'])