disable help text by default in AllBulletDemos (text slows down many graphics cards)

improve CollisionDemo.cpp, show multi-contact generation using perturbation
improve ColladaConverter: add hinge/point 2 point constraint conversion support, add btScaledTriangleMeshShape support
Fix Dynamica MayaPlygin: remove 'active' flag, it has to be replaced by mass=0 for active, mass<>0 for passive
Added missing projectfiles
Fixed single-shot contact generation. it is disabled by default to improve performance
Bugfixes for character controller, thanks to John McCutchan for reporting
Constraint solver: better default settings
btDefaultAllocator: aligned allocator uses non-aligned allocator (instead of directly malloc/free)
disable memalign by default, use Bullet's aligned allocator
This commit is contained in:
erwin.coumans
2009-02-06 03:20:43 +00:00
parent 328116d015
commit 2162f6663d
34 changed files with 4029 additions and 239 deletions

View File

@@ -51,7 +51,7 @@ subject to the following restrictions:
btConvexConvexAlgorithm::CreateFunc::CreateFunc(btSimplexSolverInterface* simplexSolver, btConvexPenetrationDepthSolver* pdSolver)
{
m_numPerturbationIterations = 3;
m_numPerturbationIterations = 0;
m_minimumPointsPerturbationThreshold = 3;
m_simplexSolver = simplexSolver;
m_pdSolver = pdSolver;
@@ -102,25 +102,53 @@ struct btPerturbedContactResult : public btManifoldResult
btManifoldResult* m_originalManifoldResult;
btTransform m_transformA;
btTransform m_transformB;
btTransform m_unPerturbedTransform;
bool m_perturbA;
btIDebugDraw* m_debugDrawer;
btPerturbedContactResult(btManifoldResult* originalResult,const btTransform& transformA,const btTransform& transformB)
btPerturbedContactResult(btManifoldResult* originalResult,const btTransform& transformA,const btTransform& transformB,const btTransform& unPerturbedTransform,bool perturbA,btIDebugDraw* debugDrawer)
:m_originalManifoldResult(originalResult),
m_transformA(transformA),
m_transformB(transformB)
m_transformB(transformB),
m_perturbA(perturbA),
m_unPerturbedTransform(unPerturbedTransform),
m_debugDrawer(debugDrawer)
{
}
virtual ~ btPerturbedContactResult()
{
}
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar orgDepth)
{
const btVector3& worldPointB = pointInWorld;
btVector3 worldPointA = worldPointB+normalOnBInWorld*depth;
btVector3 localA = m_transformA.invXform(worldPointA);
btVector3 localB = m_transformB.invXform(pointInWorld);
m_originalManifoldResult->addLocalContactPointInternal( normalOnBInWorld,localA,localB);
btVector3 endPt,startPt;
btScalar newDepth;
btVector3 newNormal;
if (m_perturbA)
{
btVector3 endPtOrg = pointInWorld + normalOnBInWorld*orgDepth;
endPt = (m_unPerturbedTransform*m_transformA.inverse())(endPtOrg);
newDepth = (endPt - pointInWorld).dot(normalOnBInWorld);
startPt = endPt+normalOnBInWorld*newDepth;
} else
{
endPt = pointInWorld + normalOnBInWorld*orgDepth;
startPt = (m_unPerturbedTransform*m_transformB.inverse())(pointInWorld);
newDepth = (endPt - startPt).dot(normalOnBInWorld);
}
//#define DEBUG_CONTACTS 1
#ifdef DEBUG_CONTACTS
m_debugDrawer->drawLine(startPt,endPt,btVector3(1,0,0));
m_debugDrawer->drawSphere(startPt,0.05,btVector3(0,1,0));
m_debugDrawer->drawSphere(endPt,0.05,btVector3(0,0,1));
#endif //DEBUG_CONTACTS
m_originalManifoldResult->addContactPoint(normalOnBInWorld,startPt,newDepth);
}
};
@@ -188,8 +216,7 @@ void btConvexConvexAlgorithm ::processCollision (btCollisionObject* body0,btColl
//now perform 'm_numPerturbationIterations' collision queries with the perturbated collision objects
//perform perturbation when more then 'm_minimumPointsPerturbationThreshold' points
//perturbation is work-in-progress, disable until fully finished and tested
if (0)//resultOut->getPersistentManifold()->getNumContacts() < m_minimumPointsPerturbationThreshold)
if (resultOut->getPersistentManifold()->getNumContacts() < m_minimumPointsPerturbationThreshold)
{
int i;
@@ -211,21 +238,42 @@ void btConvexConvexAlgorithm ::processCollision (btCollisionObject* body0,btColl
if ( perturbeAngle > angleLimit )
perturbeAngle = angleLimit;
btTransform unPerturbedTransform;
if (perturbeA)
{
unPerturbedTransform = input.m_transformA;
} else
{
unPerturbedTransform = input.m_transformB;
}
for ( i=0;i<m_numPerturbationIterations;i++)
{
btQuaternion perturbeRot(v0,perturbeAngle);
btScalar iterationAngle = i*(SIMD_2_PI/btScalar(m_numPerturbationIterations));
btQuaternion rotq(sepNormalWorldSpace,iterationAngle);
if (perturbeA)
{
input.m_transformA.setBasis( btMatrix3x3(rotq.inverse()*perturbeRot*rotq)*body0->getWorldTransform().getBasis());
input.m_transformA.setBasis( btMatrix3x3(rotq.inverse()*perturbeRot*rotq)*body0->getWorldTransform().getBasis());
input.m_transformB = body1->getWorldTransform();
#ifdef DEBUG_CONTACTS
dispatchInfo.m_debugDraw->drawTransform(input.m_transformA,10.0);
#endif //DEBUG_CONTACTS
} else
{
input.m_transformA = body0->getWorldTransform();
input.m_transformB.setBasis( btMatrix3x3(rotq.inverse()*perturbeRot*rotq)*body1->getWorldTransform().getBasis());
#ifdef DEBUG_CONTACTS
dispatchInfo.m_debugDraw->drawTransform(input.m_transformB,10.0);
#endif
}
btPerturbedContactResult perturbedResultOut(resultOut,input.m_transformA,input.m_transformB);
btPerturbedContactResult perturbedResultOut(resultOut,input.m_transformA,input.m_transformB,unPerturbedTransform,perturbeA,dispatchInfo.m_debugDraw);
gjkPairDetector.getClosestPoints(input,perturbedResultOut,dispatchInfo.m_debugDraw);
btScalar curSepDist = gjkPairDetector.getCachedSeparatingDistance()+dispatchInfo.m_convexConservativeDistanceThreshold;
}
}

View File

@@ -52,14 +52,6 @@ btManifoldResult::btManifoldResult(btCollisionObject* body0,btCollisionObject* b
m_rootTransB = body1->getWorldTransform();
}
void btManifoldResult::addLocalContactPointInternal(const btVector3& normalOnBInWorld,const btVector3& localPointA,const btVector3& localPointB)
{
btVector3 worldPointA = m_rootTransA( localPointA );
btVector3 worldPointB = m_rootTransB( localPointB );
btScalar depth = (worldPointA - worldPointB).dot(normalOnBInWorld);
addContactPoint(normalOnBInWorld,worldPointB,depth);
}
void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)
{
@@ -100,7 +92,7 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
newPt.m_partId1 = m_partId1;
newPt.m_index0 = m_index0;
newPt.m_index1 = m_index1;
//printf("depth=%f\n",depth);
///@todo, check this for any side effects
if (insertIndex >= 0)
{

View File

@@ -82,8 +82,6 @@ public:
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth);
virtual void addLocalContactPointInternal(const btVector3& normalOnBInWorld,const btVector3& localPointA,const btVector3& localPointB);
SIMD_FORCE_INLINE void refreshContactPoints()
{
btAssert(m_manifoldPtr);

View File

@@ -135,6 +135,9 @@ bool btContinuousConvexCollision::calcTimeOfImpact(
//btScalar clippedDist = GEN_min(angularConservativeRadius,dist);
//btScalar clippedDist = dist;
//don't report time of impact for motion away from the contact normal (or causes minor penetration)
if ((projectedLinearVelocity+ maxAngularProjectedVelocity)<=SIMD_EPSILON)
return false;
dLambda = dist / (projectedLinearVelocity+ maxAngularProjectedVelocity);
@@ -196,11 +199,10 @@ bool btContinuousConvexCollision::calcTimeOfImpact(
}
}
//don't report time of impact for motion away from the contact normal (or causes minor penetration)
if ((projectedLinearVelocity+ maxAngularProjectedVelocity)<=result.m_allowedPenetration)//SIMD_EPSILON)
return false;
result.m_fraction = lambda;
result.m_normal = n;
result.m_hitPoint = c;

View File

@@ -183,6 +183,9 @@ int btPersistentManifold::addManifoldPoint(const btManifoldPoint& newPoint)
}
if (insertIndex<0)
insertIndex=0;
btAssert(m_pointCache[insertIndex].m_userPersistentData==0);
m_pointCache[insertIndex] = newPoint;
return insertIndex;

View File

@@ -22,9 +22,9 @@ enum btSolverMode
SOLVER_FRICTION_SEPARATE = 2,
SOLVER_USE_WARMSTARTING = 4,
SOLVER_USE_FRICTION_WARMSTARTING = 8,
SOLVER_USE_1_FRICTION_DIRECTION = 16,
SOLVER_USE_2_FRICTION_DIRECTIONS = 16,
SOLVER_ENABLE_FRICTION_DIRECTION_CACHING = 32,
SOLVER_ENABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION = 64,
SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION = 64,
SOLVER_CACHE_FRIENDLY = 128,
SOLVER_SIMD = 256, //enabled for Windows, the solver innerloop is branchless SIMD, 40% faster than FPU/scalar version
SOLVER_CUDA = 512 //will be open sourced during Game Developers Conference 2009. Much faster.
@@ -77,7 +77,7 @@ struct btContactSolverInfo : public btContactSolverInfoData
m_splitImpulsePenetrationThreshold = -0.02f;
m_linearSlop = btScalar(0.0);
m_warmstartingFactor=btScalar(0.85);
m_solverMode = SOLVER_USE_WARMSTARTING | SOLVER_SIMD;//SOLVER_RANDMIZE_ORDER
m_solverMode = SOLVER_USE_WARMSTARTING | SOLVER_SIMD ;//SOLVER_RANDMIZE_ORDER
m_restingContactRestitutionThreshold = 2;//resting contact lifetime threshold to disable restitution
}
};

View File

@@ -92,6 +92,16 @@ public:
return m_rbB;
}
btRigidBody& getRigidBodyA()
{
return m_rbA;
}
btRigidBody& getRigidBodyB()
{
return m_rbB;
}
void setAngularOnly(bool angularOnly)
{
m_angularOnly = angularOnly;

View File

@@ -543,6 +543,9 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
solverBodyIdB = getOrInitSolverBody(*colObj1);
}
if (solverBodyIdA == 0 && solverBodyIdB == 0)
continue;
btVector3 rel_pos1;
btVector3 rel_pos2;
btScalar relaxation;
@@ -703,11 +706,11 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
{
cp.m_lateralFrictionDir1 = vel - cp.m_normalWorldOnB * rel_vel;
btScalar lat_rel_vel = cp.m_lateralFrictionDir1.length2();
if ((infoGlobal.m_solverMode & SOLVER_ENABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION) && lat_rel_vel > SIMD_EPSILON)
if (!(infoGlobal.m_solverMode & SOLVER_DISABLE_VELOCITY_DEPENDENT_FRICTION_DIRECTION) && lat_rel_vel > SIMD_EPSILON)
{
cp.m_lateralFrictionDir1 /= btSqrt(lat_rel_vel);
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
if(!(infoGlobal.m_solverMode & SOLVER_USE_1_FRICTION_DIRECTION))
if((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
{
cp.m_lateralFrictionDir2 = cp.m_lateralFrictionDir1.cross(cp.m_normalWorldOnB);
cp.m_lateralFrictionDir2.normalize();//??
@@ -719,7 +722,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
//re-calculate friction direction every frame, todo: check if this is really needed
btPlaneSpace1(cp.m_normalWorldOnB,cp.m_lateralFrictionDir1,cp.m_lateralFrictionDir2);
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
if (!(infoGlobal.m_solverMode & SOLVER_USE_1_FRICTION_DIRECTION))
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
{
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
}
@@ -729,7 +732,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
} else
{
addFrictionConstraint(cp.m_lateralFrictionDir1,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
if (!(infoGlobal.m_solverMode & SOLVER_USE_1_FRICTION_DIRECTION))
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
addFrictionConstraint(cp.m_lateralFrictionDir2,solverBodyIdA,solverBodyIdB,frictionIndex,cp,rel_pos1,rel_pos2,colObj0,colObj1, relaxation);
}
@@ -750,7 +753,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
}
}
if (!(infoGlobal.m_solverMode & SOLVER_USE_1_FRICTION_DIRECTION))
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
{
btSolverConstraint& frictionConstraint2 = m_tmpSolverContactFrictionConstraintPool[solverConstraint.m_frictionIndex+1];
if (infoGlobal.m_solverMode & SOLVER_USE_WARMSTARTING)
@@ -769,7 +772,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
{
btSolverConstraint& frictionConstraint1 = m_tmpSolverContactFrictionConstraintPool[solverConstraint.m_frictionIndex];
frictionConstraint1.m_appliedImpulse = 0.f;
if (!(infoGlobal.m_solverMode & SOLVER_USE_1_FRICTION_DIRECTION))
if ((infoGlobal.m_solverMode & SOLVER_USE_2_FRICTION_DIRECTIONS))
{
btSolverConstraint& frictionConstraint2 = m_tmpSolverContactFrictionConstraintPool[solverConstraint.m_frictionIndex+1];
frictionConstraint2.m_appliedImpulse = 0.f;

View File

@@ -19,6 +19,21 @@ int gNumAlignedAllocs = 0;
int gNumAlignedFree = 0;
int gTotalBytesAlignedAllocs = 0;//detect memory leaks
static void *btAllocDefault(size_t size)
{
return malloc(size);
}
static void btFreeDefault(void *ptr)
{
free(ptr);
}
static btAllocFunc *sAllocFunc = btAllocDefault;
static btFreeFunc *sFreeFunc = btFreeDefault;
#if defined (BT_HAS_ALIGNED_ALLOCATOR)
#include <malloc.h>
static void *btAlignedAllocDefault(size_t size, int alignment)
@@ -49,7 +64,7 @@ static inline void *btAlignedAllocDefault(size_t size, int alignment)
char *real;
unsigned long offset;
real = (char *)malloc(size + sizeof(void *) + (alignment-1));
real = (char *)sAllocFunc(size + sizeof(void *) + (alignment-1));
if (real) {
offset = (alignment - (unsigned long)(real + sizeof(void *))) & (alignment-1);
ret = (void *)((real + sizeof(void *)) + offset);
@@ -66,25 +81,14 @@ static inline void btAlignedFreeDefault(void *ptr)
if (ptr) {
real = *((void **)(ptr)-1);
free(real);
sFreeFunc(real);
}
}
#endif
static void *btAllocDefault(size_t size)
{
return malloc(size);
}
static void btFreeDefault(void *ptr)
{
free(ptr);
}
static btAlignedAllocFunc *sAlignedAllocFunc = btAlignedAllocDefault;
static btAlignedFreeFunc *sAlignedFreeFunc = btAlignedFreeDefault;
static btAllocFunc *sAllocFunc = btAllocDefault;
static btFreeFunc *sFreeFunc = btFreeDefault;
void btAlignedAllocSetCustomAligned(btAlignedAllocFunc *allocFunc, btAlignedFreeFunc *freeFunc)
{

View File

@@ -49,8 +49,11 @@ typedef void (btAlignedFreeFunc)(void *memblock);
typedef void *(btAllocFunc)(size_t size);
typedef void (btFreeFunc)(void *memblock);
void btAlignedAllocSetCustomAligned(btAlignedAllocFunc *allocFunc, btAlignedFreeFunc *freeFunc);
///The developer can let all Bullet memory allocations go through a custom memory allocator, using btAlignedAllocSetCustom
void btAlignedAllocSetCustom(btAllocFunc *allocFunc, btFreeFunc *freeFunc);
///If the developer has already an custom aligned allocator, then btAlignedAllocSetCustomAligned can be used. The default aligned allocator pre-allocates extra memory using the non-aligned allocator, and instruments it.
void btAlignedAllocSetCustomAligned(btAlignedAllocFunc *allocFunc, btAlignedFreeFunc *freeFunc);
///The btAlignedAllocator is a portable class for aligned memory allocations.
///Default implementations for unaligned and aligned allocations can be overridden by a custom allocator using btAlignedAllocSetCustom and btAlignedAllocSetCustomAligned.

View File

@@ -45,7 +45,7 @@ inline int btGetVersion()
#define ATTRIBUTE_ALIGNED16(a) a
#define ATTRIBUTE_ALIGNED128(a) a
#else
#define BT_HAS_ALIGNED_ALLOCATOR
//#define BT_HAS_ALIGNED_ALLOCATOR
#pragma warning(disable : 4324) // disable padding warning
// #pragma warning(disable:4530) // Disable the exception disable but used in MSCV Stl warning.
// #pragma warning(disable:4996) //Turn off warnings about deprecated C routines