Calculation of bounding box: margins should be added before basis transform.
Disable btSphereBoxCollisionAlgorithm, it is broken. More fixes for btSimpleBroadphase Moved quickstep to Extras/quickstep folder, so developers don't get confused which constraint solver is default.
This commit is contained in:
@@ -92,6 +92,7 @@ void BasicDemo::initPhysics()
|
|||||||
///Don't make the world AABB size too large, it will harm simulation quality and performance
|
///Don't make the world AABB size too large, it will harm simulation quality and performance
|
||||||
btVector3 worldAabbMin(-10000,-10000,-10000);
|
btVector3 worldAabbMin(-10000,-10000,-10000);
|
||||||
btVector3 worldAabbMax(10000,10000,10000);
|
btVector3 worldAabbMax(10000,10000,10000);
|
||||||
|
//m_overlappingPairCache = new btSimpleBroadphase();//new btAxisSweep3(worldAabbMin,worldAabbMax,MAX_PROXIES);
|
||||||
m_overlappingPairCache = new btAxisSweep3(worldAabbMin,worldAabbMax,MAX_PROXIES);
|
m_overlappingPairCache = new btAxisSweep3(worldAabbMin,worldAabbMax,MAX_PROXIES);
|
||||||
|
|
||||||
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
|
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
|
||||||
@@ -104,8 +105,8 @@ void BasicDemo::initPhysics()
|
|||||||
m_dynamicsWorld->setGravity(btVector3(0,-10,0));
|
m_dynamicsWorld->setGravity(btVector3(0,-10,0));
|
||||||
|
|
||||||
///create a few basic rigid bodies
|
///create a few basic rigid bodies
|
||||||
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));
|
// btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));
|
||||||
// btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
|
btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
|
||||||
|
|
||||||
m_collisionShapes.push_back(groundShape);
|
m_collisionShapes.push_back(groundShape);
|
||||||
|
|
||||||
@@ -161,13 +162,15 @@ void BasicDemo::initPhysics()
|
|||||||
|
|
||||||
for (int k=0;k<ARRAY_SIZE_Y;k++)
|
for (int k=0;k<ARRAY_SIZE_Y;k++)
|
||||||
{
|
{
|
||||||
for (int i=0;i<ARRAY_SIZE_X;i++)
|
int i=0;
|
||||||
|
// for (int i=0;i<ARRAY_SIZE_X;i++)
|
||||||
{
|
{
|
||||||
for(int j = 0;j<ARRAY_SIZE_Z;j++)
|
int j=0;
|
||||||
|
// for(int j = 0;j<ARRAY_SIZE_Z;j++)
|
||||||
{
|
{
|
||||||
startTransform.setOrigin(btVector3(
|
startTransform.setOrigin(btVector3(
|
||||||
2.0*i + start_x,
|
2.0*i + start_x,
|
||||||
2.0*k + start_y,
|
10+2.0*k + start_y,
|
||||||
2.0*j + start_z));
|
2.0*j + start_z));
|
||||||
|
|
||||||
|
|
||||||
@@ -175,8 +178,10 @@ void BasicDemo::initPhysics()
|
|||||||
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
|
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
|
||||||
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
|
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,colShape,localInertia);
|
||||||
btRigidBody* body = new btRigidBody(rbInfo);
|
btRigidBody* body = new btRigidBody(rbInfo);
|
||||||
|
body->setActivationState(ISLAND_SLEEPING);
|
||||||
|
|
||||||
m_dynamicsWorld->addRigidBody(body);
|
m_dynamicsWorld->addRigidBody(body);
|
||||||
|
body->setActivationState(ISLAND_SLEEPING);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -272,8 +272,9 @@ void BenchmarkDemo::initPhysics()
|
|||||||
///Don't make the world AABB size too large, it will harm simulation quality and performance
|
///Don't make the world AABB size too large, it will harm simulation quality and performance
|
||||||
btVector3 worldAabbMin(-10000,-10000,-10000);
|
btVector3 worldAabbMin(-10000,-10000,-10000);
|
||||||
btVector3 worldAabbMax(10000,10000,10000);
|
btVector3 worldAabbMax(10000,10000,10000);
|
||||||
m_overlappingPairCache = new btAxisSweep3(worldAabbMin,worldAabbMax,3500);
|
//m_overlappingPairCache = new btAxisSweep3(worldAabbMin,worldAabbMax,3500);
|
||||||
//m_overlappingPairCache = new btDbvtBroadphase();
|
|
||||||
|
m_overlappingPairCache = new btDbvtBroadphase();
|
||||||
|
|
||||||
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
|
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
|
||||||
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
|
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
|
||||||
|
|||||||
@@ -186,7 +186,7 @@ void ConcaveDemo::initPhysics()
|
|||||||
bool useQuantizedAabbCompression = true;
|
bool useQuantizedAabbCompression = true;
|
||||||
|
|
||||||
//comment out the next line to read the BVH from disk (first run the demo once to create the BVH)
|
//comment out the next line to read the BVH from disk (first run the demo once to create the BVH)
|
||||||
#define SERIALIZE_TO_DISK 1
|
//#define SERIALIZE_TO_DISK 1
|
||||||
#ifdef SERIALIZE_TO_DISK
|
#ifdef SERIALIZE_TO_DISK
|
||||||
btVector3 aabbMin(-1000,-1000,-1000),aabbMax(1000,1000,1000);
|
btVector3 aabbMin(-1000,-1000,-1000),aabbMax(1000,1000,1000);
|
||||||
|
|
||||||
|
|||||||
@@ -1229,7 +1229,8 @@ void DemoApplication::clientResetScene()
|
|||||||
myMotionState->m_graphicsWorldTrans = myMotionState->m_startWorldTrans;
|
myMotionState->m_graphicsWorldTrans = myMotionState->m_startWorldTrans;
|
||||||
colObj->setWorldTransform( myMotionState->m_graphicsWorldTrans );
|
colObj->setWorldTransform( myMotionState->m_graphicsWorldTrans );
|
||||||
colObj->setInterpolationWorldTransform( myMotionState->m_startWorldTrans );
|
colObj->setInterpolationWorldTransform( myMotionState->m_startWorldTrans );
|
||||||
colObj->activate();
|
//colObj->activate();
|
||||||
|
colObj->setActivationState(WANTS_DEACTIVATION);
|
||||||
}
|
}
|
||||||
//removed cached contact points
|
//removed cached contact points
|
||||||
m_dynamicsWorld->getBroadphase()->getOverlappingPairCache()->cleanProxyFromPairs(colObj->getBroadphaseHandle(),getDynamicsWorld()->getDispatcher());
|
m_dynamicsWorld->getBroadphase()->getOverlappingPairCache()->cleanProxyFromPairs(colObj->getBroadphaseHandle(),getDynamicsWorld()->getDispatcher());
|
||||||
|
|||||||
@@ -85,15 +85,15 @@ public:
|
|||||||
normal.normalize();
|
normal.normalize();
|
||||||
|
|
||||||
glBegin(GL_TRIANGLES);
|
glBegin(GL_TRIANGLES);
|
||||||
glColor3f(0, 1, 0);
|
glColor3f(1, 1, 1);
|
||||||
glNormal3d(normal.getX(),normal.getY(),normal.getZ());
|
glNormal3d(normal.getX(),normal.getY(),normal.getZ());
|
||||||
glVertex3d(triangle[0].getX(), triangle[0].getY(), triangle[0].getZ());
|
glVertex3d(triangle[0].getX(), triangle[0].getY(), triangle[0].getZ());
|
||||||
|
|
||||||
glColor3f(0, 1, 0);
|
//glColor3f(0, 1, 0);
|
||||||
glNormal3d(normal.getX(),normal.getY(),normal.getZ());
|
glNormal3d(normal.getX(),normal.getY(),normal.getZ());
|
||||||
glVertex3d(triangle[1].getX(), triangle[1].getY(), triangle[1].getZ());
|
glVertex3d(triangle[1].getX(), triangle[1].getY(), triangle[1].getZ());
|
||||||
|
|
||||||
glColor3f(0, 1, 0);
|
//glColor3f(0, 1, 0);
|
||||||
glNormal3d(normal.getX(),normal.getY(),normal.getZ());
|
glNormal3d(normal.getX(),normal.getY(),normal.getZ());
|
||||||
glVertex3d(triangle[2].getX(), triangle[2].getY(), triangle[2].getZ());
|
glVertex3d(triangle[2].getX(), triangle[2].getY(), triangle[2].getZ());
|
||||||
glEnd();
|
glEnd();
|
||||||
@@ -237,11 +237,11 @@ public:
|
|||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
glBegin(GL_TRIANGLES);
|
glBegin(GL_TRIANGLES);
|
||||||
glColor3f(1, 0, 0);
|
glColor3f(1, 1, 1);
|
||||||
glVertex3d(triangle[0].getX(), triangle[0].getY(), triangle[0].getZ());
|
glVertex3d(triangle[0].getX(), triangle[0].getY(), triangle[0].getZ());
|
||||||
glColor3f(0, 1, 0);
|
//glColor3f(0, 1, 0);
|
||||||
glVertex3d(triangle[1].getX(), triangle[1].getY(), triangle[1].getZ());
|
glVertex3d(triangle[1].getX(), triangle[1].getY(), triangle[1].getZ());
|
||||||
glColor3f(0, 0, 1);
|
//glColor3f(0, 0, 1);
|
||||||
glVertex3d(triangle[2].getX(), triangle[2].getY(), triangle[2].getZ());
|
glVertex3d(triangle[2].getX(), triangle[2].getY(), triangle[2].getZ());
|
||||||
glEnd();
|
glEnd();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -55,7 +55,7 @@ btSimpleBroadphase::btSimpleBroadphase(int maxProxies, btOverlappingPairCache* o
|
|||||||
m_maxHandles = maxProxies;
|
m_maxHandles = maxProxies;
|
||||||
m_numHandles = 0;
|
m_numHandles = 0;
|
||||||
m_firstFreeHandle = 0;
|
m_firstFreeHandle = 0;
|
||||||
m_firstAllocatedHandle = -1;
|
|
||||||
|
|
||||||
{
|
{
|
||||||
for (int i = m_firstFreeHandle; i < maxProxies; i++)
|
for (int i = m_firstFreeHandle; i < maxProxies; i++)
|
||||||
|
|||||||
@@ -61,11 +61,10 @@ protected:
|
|||||||
|
|
||||||
void* m_pHandlesRawPtr;
|
void* m_pHandlesRawPtr;
|
||||||
int m_firstFreeHandle; // free handles list
|
int m_firstFreeHandle; // free handles list
|
||||||
int m_firstAllocatedHandle;
|
|
||||||
|
|
||||||
int allocHandle()
|
int allocHandle()
|
||||||
{
|
{
|
||||||
btAssert(m_firstFreeHandle);
|
btAssert(m_numHandles < m_maxHandles);
|
||||||
int freeHandle = m_firstFreeHandle;
|
int freeHandle = m_firstFreeHandle;
|
||||||
m_firstFreeHandle = m_pHandles[freeHandle].GetNextFree();
|
m_firstFreeHandle = m_pHandles[freeHandle].GetNextFree();
|
||||||
m_numHandles++;
|
m_numHandles++;
|
||||||
|
|||||||
@@ -127,6 +127,11 @@ void btCollisionWorld::updateAabbs()
|
|||||||
{
|
{
|
||||||
btPoint3 minAabb,maxAabb;
|
btPoint3 minAabb,maxAabb;
|
||||||
colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
|
colObj->getCollisionShape()->getAabb(colObj->getWorldTransform(), minAabb,maxAabb);
|
||||||
|
//need to increase the aabb for contact thresholds
|
||||||
|
btVector3 contactThreshold(gContactBreakingThreshold,gContactBreakingThreshold,gContactBreakingThreshold);
|
||||||
|
minAabb -= contactThreshold;
|
||||||
|
maxAabb += contactThreshold;
|
||||||
|
|
||||||
btBroadphaseInterface* bp = (btBroadphaseInterface*)m_broadphasePairCache;
|
btBroadphaseInterface* bp = (btBroadphaseInterface*)m_broadphasePairCache;
|
||||||
|
|
||||||
//moving objects should be moderately sized, probably something wrong if not
|
//moving objects should be moderately sized, probably something wrong if not
|
||||||
|
|||||||
@@ -22,7 +22,9 @@ subject to the following restrictions:
|
|||||||
#include "BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h"
|
#include "BulletCollision/CollisionDispatch/btConvexPlaneCollisionAlgorithm.h"
|
||||||
#include "BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h"
|
#include "BulletCollision/CollisionDispatch/btBoxBoxCollisionAlgorithm.h"
|
||||||
#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
|
#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
|
||||||
|
#ifdef USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
#include "BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h"
|
#include "BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h"
|
||||||
|
#endif //USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
#include "BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h"
|
#include "BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.h"
|
||||||
#include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h"
|
#include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h"
|
||||||
#include "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h"
|
#include "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h"
|
||||||
@@ -70,11 +72,14 @@ btDefaultCollisionConfiguration::btDefaultCollisionConfiguration(const btDefault
|
|||||||
|
|
||||||
mem = btAlignedAlloc(sizeof(btSphereSphereCollisionAlgorithm::CreateFunc),16);
|
mem = btAlignedAlloc(sizeof(btSphereSphereCollisionAlgorithm::CreateFunc),16);
|
||||||
m_sphereSphereCF = new(mem) btSphereSphereCollisionAlgorithm::CreateFunc;
|
m_sphereSphereCF = new(mem) btSphereSphereCollisionAlgorithm::CreateFunc;
|
||||||
|
#ifdef USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
mem = btAlignedAlloc(sizeof(btSphereBoxCollisionAlgorithm::CreateFunc),16);
|
mem = btAlignedAlloc(sizeof(btSphereBoxCollisionAlgorithm::CreateFunc),16);
|
||||||
m_sphereBoxCF = new(mem) btSphereBoxCollisionAlgorithm::CreateFunc;
|
m_sphereBoxCF = new(mem) btSphereBoxCollisionAlgorithm::CreateFunc;
|
||||||
mem = btAlignedAlloc(sizeof(btSphereBoxCollisionAlgorithm::CreateFunc),16);
|
mem = btAlignedAlloc(sizeof(btSphereBoxCollisionAlgorithm::CreateFunc),16);
|
||||||
m_boxSphereCF = new (mem)btSphereBoxCollisionAlgorithm::CreateFunc;
|
m_boxSphereCF = new (mem)btSphereBoxCollisionAlgorithm::CreateFunc;
|
||||||
m_boxSphereCF->m_swapped = true;
|
m_boxSphereCF->m_swapped = true;
|
||||||
|
#endif //USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
|
|
||||||
mem = btAlignedAlloc(sizeof(btSphereTriangleCollisionAlgorithm::CreateFunc),16);
|
mem = btAlignedAlloc(sizeof(btSphereTriangleCollisionAlgorithm::CreateFunc),16);
|
||||||
m_sphereTriangleCF = new (mem)btSphereTriangleCollisionAlgorithm::CreateFunc;
|
m_sphereTriangleCF = new (mem)btSphereTriangleCollisionAlgorithm::CreateFunc;
|
||||||
mem = btAlignedAlloc(sizeof(btSphereTriangleCollisionAlgorithm::CreateFunc),16);
|
mem = btAlignedAlloc(sizeof(btSphereTriangleCollisionAlgorithm::CreateFunc),16);
|
||||||
@@ -176,10 +181,13 @@ btDefaultCollisionConfiguration::~btDefaultCollisionConfiguration()
|
|||||||
m_sphereSphereCF->~btCollisionAlgorithmCreateFunc();
|
m_sphereSphereCF->~btCollisionAlgorithmCreateFunc();
|
||||||
btAlignedFree( m_sphereSphereCF);
|
btAlignedFree( m_sphereSphereCF);
|
||||||
|
|
||||||
|
#ifdef USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
m_sphereBoxCF->~btCollisionAlgorithmCreateFunc();
|
m_sphereBoxCF->~btCollisionAlgorithmCreateFunc();
|
||||||
btAlignedFree( m_sphereBoxCF);
|
btAlignedFree( m_sphereBoxCF);
|
||||||
m_boxSphereCF->~btCollisionAlgorithmCreateFunc();
|
m_boxSphereCF->~btCollisionAlgorithmCreateFunc();
|
||||||
btAlignedFree( m_boxSphereCF);
|
btAlignedFree( m_boxSphereCF);
|
||||||
|
#endif //USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
|
|
||||||
m_sphereTriangleCF->~btCollisionAlgorithmCreateFunc();
|
m_sphereTriangleCF->~btCollisionAlgorithmCreateFunc();
|
||||||
btAlignedFree( m_sphereTriangleCF);
|
btAlignedFree( m_sphereTriangleCF);
|
||||||
m_triangleSphereCF->~btCollisionAlgorithmCreateFunc();
|
m_triangleSphereCF->~btCollisionAlgorithmCreateFunc();
|
||||||
@@ -212,7 +220,7 @@ btCollisionAlgorithmCreateFunc* btDefaultCollisionConfiguration::getCollisionAlg
|
|||||||
{
|
{
|
||||||
return m_sphereSphereCF;
|
return m_sphereSphereCF;
|
||||||
}
|
}
|
||||||
|
#ifdef USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE) && (proxyType1==BOX_SHAPE_PROXYTYPE))
|
if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE) && (proxyType1==BOX_SHAPE_PROXYTYPE))
|
||||||
{
|
{
|
||||||
return m_sphereBoxCF;
|
return m_sphereBoxCF;
|
||||||
@@ -222,6 +230,8 @@ btCollisionAlgorithmCreateFunc* btDefaultCollisionConfiguration::getCollisionAlg
|
|||||||
{
|
{
|
||||||
return m_boxSphereCF;
|
return m_boxSphereCF;
|
||||||
}
|
}
|
||||||
|
#endif //USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
|
|
||||||
|
|
||||||
if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE ) && (proxyType1==TRIANGLE_SHAPE_PROXYTYPE))
|
if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE ) && (proxyType1==TRIANGLE_SHAPE_PROXYTYPE))
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -71,8 +71,11 @@ class btDefaultCollisionConfiguration : public btCollisionConfiguration
|
|||||||
btCollisionAlgorithmCreateFunc* m_swappedCompoundCreateFunc;
|
btCollisionAlgorithmCreateFunc* m_swappedCompoundCreateFunc;
|
||||||
btCollisionAlgorithmCreateFunc* m_emptyCreateFunc;
|
btCollisionAlgorithmCreateFunc* m_emptyCreateFunc;
|
||||||
btCollisionAlgorithmCreateFunc* m_sphereSphereCF;
|
btCollisionAlgorithmCreateFunc* m_sphereSphereCF;
|
||||||
|
#ifdef USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
btCollisionAlgorithmCreateFunc* m_sphereBoxCF;
|
btCollisionAlgorithmCreateFunc* m_sphereBoxCF;
|
||||||
btCollisionAlgorithmCreateFunc* m_boxSphereCF;
|
btCollisionAlgorithmCreateFunc* m_boxSphereCF;
|
||||||
|
#endif //USE_BUGGY_SPHERE_BOX_ALGORITHM
|
||||||
|
|
||||||
btCollisionAlgorithmCreateFunc* m_boxBoxCF;
|
btCollisionAlgorithmCreateFunc* m_boxBoxCF;
|
||||||
btCollisionAlgorithmCreateFunc* m_sphereTriangleCF;
|
btCollisionAlgorithmCreateFunc* m_sphereTriangleCF;
|
||||||
btCollisionAlgorithmCreateFunc* m_triangleSphereCF;
|
btCollisionAlgorithmCreateFunc* m_triangleSphereCF;
|
||||||
|
|||||||
@@ -21,14 +21,15 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
void btBoxShape::getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const
|
void btBoxShape::getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const
|
||||||
{
|
{
|
||||||
const btVector3& halfExtents = getHalfExtentsWithoutMargin();
|
btVector3 halfExtents = getHalfExtentsWithoutMargin();
|
||||||
|
halfExtents += btVector3(getMargin(),getMargin(),getMargin());
|
||||||
|
|
||||||
|
|
||||||
btMatrix3x3 abs_b = t.getBasis().absolute();
|
btMatrix3x3 abs_b = t.getBasis().absolute();
|
||||||
btPoint3 center = t.getOrigin();
|
btPoint3 center = t.getOrigin();
|
||||||
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),
|
btVector3 extent = btVector3(abs_b[0].dot(halfExtents),
|
||||||
abs_b[1].dot(halfExtents),
|
abs_b[1].dot(halfExtents),
|
||||||
abs_b[2].dot(halfExtents));
|
abs_b[2].dot(halfExtents));
|
||||||
extent += btVector3(getMargin(),getMargin(),getMargin());
|
|
||||||
|
|
||||||
aabbMin = center - extent;
|
aabbMin = center - extent;
|
||||||
aabbMax = center + extent;
|
aabbMax = center + extent;
|
||||||
|
|||||||
@@ -112,6 +112,7 @@ void btCompoundShape::recalculateLocalAabb()
|
|||||||
void btCompoundShape::getAabb(const btTransform& trans,btVector3& aabbMin,btVector3& aabbMax) const
|
void btCompoundShape::getAabb(const btTransform& trans,btVector3& aabbMin,btVector3& aabbMax) const
|
||||||
{
|
{
|
||||||
btVector3 localHalfExtents = btScalar(0.5)*(m_localAabbMax-m_localAabbMin);
|
btVector3 localHalfExtents = btScalar(0.5)*(m_localAabbMax-m_localAabbMin);
|
||||||
|
localHalfExtents += btVector3(getMargin(),getMargin(),getMargin());
|
||||||
btVector3 localCenter = btScalar(0.5)*(m_localAabbMax+m_localAabbMin);
|
btVector3 localCenter = btScalar(0.5)*(m_localAabbMax+m_localAabbMin);
|
||||||
|
|
||||||
btMatrix3x3 abs_b = trans.getBasis().absolute();
|
btMatrix3x3 abs_b = trans.getBasis().absolute();
|
||||||
@@ -121,10 +122,7 @@ void btCompoundShape::getAabb(const btTransform& trans,btVector3& aabbMin,btVect
|
|||||||
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
|
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
|
||||||
abs_b[1].dot(localHalfExtents),
|
abs_b[1].dot(localHalfExtents),
|
||||||
abs_b[2].dot(localHalfExtents));
|
abs_b[2].dot(localHalfExtents));
|
||||||
extent += btVector3(getMargin(),getMargin(),getMargin());
|
|
||||||
|
|
||||||
aabbMin = center - extent;
|
|
||||||
aabbMax = center + extent;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void btCompoundShape::calculateLocalInertia(btScalar mass,btVector3& inertia) const
|
void btCompoundShape::calculateLocalInertia(btScalar mass,btVector3& inertia) const
|
||||||
|
|||||||
@@ -53,6 +53,7 @@ public:
|
|||||||
|
|
||||||
|
|
||||||
btVector3 localHalfExtents = btScalar(0.5)*(m_localAabbMax-m_localAabbMin);
|
btVector3 localHalfExtents = btScalar(0.5)*(m_localAabbMax-m_localAabbMin);
|
||||||
|
localHalfExtents+= btVector3(margin,margin,margin);
|
||||||
btVector3 localCenter = btScalar(0.5)*(m_localAabbMax+m_localAabbMin);
|
btVector3 localCenter = btScalar(0.5)*(m_localAabbMax+m_localAabbMin);
|
||||||
|
|
||||||
btMatrix3x3 abs_b = trans.getBasis().absolute();
|
btMatrix3x3 abs_b = trans.getBasis().absolute();
|
||||||
@@ -62,10 +63,6 @@ public:
|
|||||||
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
|
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
|
||||||
abs_b[1].dot(localHalfExtents),
|
abs_b[1].dot(localHalfExtents),
|
||||||
abs_b[2].dot(localHalfExtents));
|
abs_b[2].dot(localHalfExtents));
|
||||||
extent += btVector3(margin,margin,margin);
|
|
||||||
|
|
||||||
aabbMin = center - extent;
|
|
||||||
aabbMax = center + extent;
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -47,6 +47,7 @@ void btTriangleMeshShape::getAabb(const btTransform& trans,btVector3& aabbMin,bt
|
|||||||
{
|
{
|
||||||
|
|
||||||
btVector3 localHalfExtents = btScalar(0.5)*(m_localAabbMax-m_localAabbMin);
|
btVector3 localHalfExtents = btScalar(0.5)*(m_localAabbMax-m_localAabbMin);
|
||||||
|
localHalfExtents += btVector3(getMargin(),getMargin(),getMargin());
|
||||||
btVector3 localCenter = btScalar(0.5)*(m_localAabbMax+m_localAabbMin);
|
btVector3 localCenter = btScalar(0.5)*(m_localAabbMax+m_localAabbMin);
|
||||||
|
|
||||||
btMatrix3x3 abs_b = trans.getBasis().absolute();
|
btMatrix3x3 abs_b = trans.getBasis().absolute();
|
||||||
@@ -56,12 +57,7 @@ void btTriangleMeshShape::getAabb(const btTransform& trans,btVector3& aabbMin,bt
|
|||||||
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
|
btVector3 extent = btVector3(abs_b[0].dot(localHalfExtents),
|
||||||
abs_b[1].dot(localHalfExtents),
|
abs_b[1].dot(localHalfExtents),
|
||||||
abs_b[2].dot(localHalfExtents));
|
abs_b[2].dot(localHalfExtents));
|
||||||
extent += btVector3(getMargin(),getMargin(),getMargin());
|
|
||||||
|
|
||||||
aabbMin = center - extent;
|
|
||||||
aabbMax = center + extent;
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void btTriangleMeshShape::recalcLocalAabb()
|
void btTriangleMeshShape::recalcLocalAabb()
|
||||||
|
|||||||
@@ -22,19 +22,6 @@ ADD_LIBRARY(LibBulletDynamics
|
|||||||
ConstraintSolver/btSolve2LinearConstraint.h
|
ConstraintSolver/btSolve2LinearConstraint.h
|
||||||
ConstraintSolver/btTypedConstraint.cpp
|
ConstraintSolver/btTypedConstraint.cpp
|
||||||
ConstraintSolver/btTypedConstraint.h
|
ConstraintSolver/btTypedConstraint.h
|
||||||
ConstraintSolver/btOdeContactJoint.cpp
|
|
||||||
ConstraintSolver/btOdeContactJoint.h
|
|
||||||
ConstraintSolver/btOdeJoint.cpp
|
|
||||||
ConstraintSolver/btOdeJoint.h
|
|
||||||
ConstraintSolver/btOdeSolverBody.h
|
|
||||||
ConstraintSolver/btOdeQuickstepConstraintSolver.cpp
|
|
||||||
ConstraintSolver/btOdeQuickstepConstraintSolver.h
|
|
||||||
ConstraintSolver/btOdeTypedJoint.cpp
|
|
||||||
ConstraintSolver/btOdeTypedJoint.h
|
|
||||||
ConstraintSolver/btSorLcp.cpp
|
|
||||||
ConstraintSolver/btSorLcp.h
|
|
||||||
ConstraintSolver/btOdeQuickstepConstraintSolver.h
|
|
||||||
ConstraintSolver/btOdeMacros.h
|
|
||||||
Dynamics/Bullet-C-API.cpp
|
Dynamics/Bullet-C-API.cpp
|
||||||
Dynamics/btDiscreteDynamicsWorld.cpp
|
Dynamics/btDiscreteDynamicsWorld.cpp
|
||||||
Dynamics/btDiscreteDynamicsWorld.h
|
Dynamics/btDiscreteDynamicsWorld.h
|
||||||
|
|||||||
@@ -43,7 +43,9 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
///Narrowphase Collision Detector
|
///Narrowphase Collision Detector
|
||||||
#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
|
#include "BulletCollision/CollisionDispatch/btSphereSphereCollisionAlgorithm.h"
|
||||||
#include "BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h"
|
|
||||||
|
//btSphereBoxCollisionAlgorithm is broken, use gjk for now
|
||||||
|
//#include "BulletCollision/CollisionDispatch/btSphereBoxCollisionAlgorithm.h"
|
||||||
#include "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h"
|
#include "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h"
|
||||||
|
|
||||||
///Dispatching and generation of collision pairs (broadphase)
|
///Dispatching and generation of collision pairs (broadphase)
|
||||||
|
|||||||
@@ -32,9 +32,7 @@ subject to the following restrictions:
|
|||||||
#include "BulletDynamics/ConstraintSolver/btSliderConstraint.h"
|
#include "BulletDynamics/ConstraintSolver/btSliderConstraint.h"
|
||||||
|
|
||||||
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
|
||||||
///Optional ODE quickstep constraint solver, redistributed under ZLib license
|
|
||||||
#include "BulletDynamics/ConstraintSolver/btOdeQuickstepConstraintSolver.h"
|
|
||||||
#include "BulletDynamics/ConstraintSolver/btOdeTypedJoint.h"
|
|
||||||
|
|
||||||
///Vehicle simulation, with wheel contact simulated by raycasts
|
///Vehicle simulation, with wheel contact simulated by raycasts
|
||||||
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
|
#include "BulletDynamics/Vehicle/btRaycastVehicle.h"
|
||||||
|
|||||||
Reference in New Issue
Block a user