Add support for childshape index for btCompoundShape during ContactAddedCallback,

see example in Bullet/Demos/ConvexDecompositionDemo
Removed some warnings
This commit is contained in:
erwin.coumans
2009-08-11 00:30:41 +00:00
parent f352cca5cf
commit d67aa861f2
40 changed files with 235 additions and 113 deletions

View File

@@ -111,7 +111,7 @@ btDemoEntry g_demoEntries[] =
{"Basic Demo", BasicDemo::Create},
{"Convex Decomposition",ConvexDecompositionDemo::Create},
{"Concave Moving", GimpactConcaveDemo::Create},
// {"Dynamic Control Demo",MotorDemo::Create},
{"Dynamic Control Demo",MotorDemo::Create},
//{"ConcaveDemo",ConcaveDemo::Create},
{"Concave Convexcast Demo",ConcaveConvexcastDemo::Create},
// {"SoftBody Cloth",SoftDemo0::Create},

View File

@@ -62,9 +62,39 @@ void ConvexDecompositionDemo::initPhysics()
///MyContactCallback is just an example to show how to get access to the child shape that collided
bool MyContactCallback (
btManifoldPoint& cp,
const btCollisionObject* colObj0,
int partId0,
int index0,
const btCollisionObject* colObj1,
int partId1,
int index1)
{
if (colObj0->getRootCollisionShape()->getShapeType()==COMPOUND_SHAPE_PROXYTYPE)
{
btCompoundShape* compound = (btCompoundShape*)colObj0->getRootCollisionShape();
btCollisionShape* childShape;
childShape = compound->getChildShape(index0);
}
if (colObj1->getRootCollisionShape()->getShapeType()==COMPOUND_SHAPE_PROXYTYPE)
{
btCompoundShape* compound = (btCompoundShape*)colObj1->getRootCollisionShape();
btCollisionShape* childShape;
childShape = compound->getChildShape(index1);
}
return true;
}
void ConvexDecompositionDemo::initPhysics(const char* filename)
{
gContactAddedCallback = &MyContactCallback;
setTexturing(true);
setShadows(true);
@@ -396,7 +426,7 @@ void ConvexDecompositionDemo::initPhysics(const char* filename)
//now create some bodies
{
btCompoundShape* compound = new btCompoundShape();
btCompoundShape* compound = new btCompoundShape(false);
m_collisionShapes.push_back (compound);
btTransform trans;
@@ -411,13 +441,18 @@ void ConvexDecompositionDemo::initPhysics(const char* filename)
}
btScalar mass=10.f;
trans.setOrigin(-convexDecompositionObjectOffset);
localCreateRigidBody( mass, trans,compound);
btRigidBody* body = localCreateRigidBody( mass, trans,compound);
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
convexDecompositionObjectOffset.setZ(6);
trans.setOrigin(-convexDecompositionObjectOffset);
localCreateRigidBody( mass, trans,compound);
body = localCreateRigidBody( mass, trans,compound);
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
convexDecompositionObjectOffset.setZ(-6);
trans.setOrigin(-convexDecompositionObjectOffset);
localCreateRigidBody( mass, trans,compound);
body = localCreateRigidBody( mass, trans,compound);
body->setCollisionFlags(body->getCollisionFlags() | btCollisionObject::CF_CUSTOM_MATERIAL_CALLBACK);
}

View File

@@ -338,7 +338,8 @@ void MotorDemo::clientMoveAndDisplay()
if (m_dynamicsWorld)
{
m_dynamicsWorld->stepSimulation(ms / 1000000.f);
///run the simulation at 120 hertz internally (maximum of 10 substeps)
m_dynamicsWorld->stepSimulation(ms / 1000000.f,10,1./120.f);
m_dynamicsWorld->debugDrawWorld();
}

View File

@@ -283,7 +283,10 @@ static float gDepth;
struct MyResult : public btDiscreteCollisionDetectorInterface::Result
{
virtual void setShapeIdentifiers(int partId0, int index0, int partId1, int index1)
virtual void setShapeIdentifiersA(int partId0, int index0)
{
}
virtual void setShapeIdentifiersB(int partId1, int index1)
{
}

View File

@@ -349,6 +349,9 @@ void RagdollDemo::initPhysics()
m_solver = new btSequentialImpulseConstraintSolver;
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
//m_dynamicsWorld->getDispatchInfo().m_useConvexConservativeDistanceUtil = true;
//m_dynamicsWorld->getDispatchInfo().m_convexConservativeDistanceThreshold = 0.01f;
// Setup a big ground box

View File

@@ -267,7 +267,7 @@ int dBoxBox2 (const btVector3& p1, const dMatrix3 R1,
int maxc, dContactGeom * /*contact*/, int /*skip*/,btDiscreteCollisionDetectorInterface::Result& output)
{
const btScalar fudge_factor = btScalar(1.05);
btVector3 p,pp,normalC;
btVector3 p,pp,normalC(0.f,0.f,0.f);
const btScalar *normalR = 0;
btScalar A[3],B[3],R11,R12,R13,R21,R22,R23,R31,R32,R33,
Q11,Q12,Q13,Q21,Q22,Q23,Q31,Q32,Q33,s,s2,l;

View File

@@ -142,6 +142,15 @@ public:
if (!m_childCollisionAlgorithms[index])
m_childCollisionAlgorithms[index] = m_dispatcher->findAlgorithm(m_compoundColObj,m_otherObj,m_sharedManifold);
///detect swapping case
if (m_resultOut->getBody0Internal() == m_compoundColObj)
{
m_resultOut->setShapeIdentifiersA(-1,index);
} else
{
m_resultOut->setShapeIdentifiersB(-1,index);
}
m_childCollisionAlgorithms[index]->processCollision(m_compoundColObj,m_otherObj,m_dispatchInfo,m_resultOut);
if (m_dispatchInfo.m_debugDraw && (m_dispatchInfo.m_debugDraw->getDebugMode() & btIDebugDraw::DBG_DrawAabb))
{

View File

@@ -124,8 +124,8 @@ void btConvexTriangleCallback::processTriangle(btVector3* triangle,int partId, i
///this should use the btDispatcher, so the actual registered algorithm is used
// btConvexConvexAlgorithm cvxcvxalgo(m_manifoldPtr,ci,m_convexBody,m_triBody);
m_resultOut->setShapeIdentifiers(-1,-1,partId,triangleIndex);
// cvxcvxalgo.setShapeIdentifiers(-1,-1,partId,triangleIndex);
m_resultOut->setShapeIdentifiersB(partId,triangleIndex);
// cvxcvxalgo.processCollision(m_convexBody,m_triBody,*m_dispatchInfoPtr,m_resultOut);
colAlgo->processCollision(m_convexBody,m_triBody,*m_dispatchInfoPtr,m_resultOut);
colAlgo->~btCollisionAlgorithm();

View File

@@ -47,6 +47,12 @@ btManifoldResult::btManifoldResult(btCollisionObject* body0,btCollisionObject* b
:m_manifoldPtr(0),
m_body0(body0),
m_body1(body1)
#ifdef DEBUG_PART_INDEX
,m_partId0(-1),
m_partId1(-1),
m_index0(-1),
m_index1(-1)
#endif //DEBUG_PART_INDEX
{
m_rootTransA = body0->getWorldTransform();
m_rootTransB = body1->getWorldTransform();
@@ -88,10 +94,19 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
newPt.m_combinedRestitution = calculateCombinedRestitution(m_body0,m_body1);
//BP mod, store contact triangles.
if (isSwapped)
{
newPt.m_partId0 = m_partId1;
newPt.m_partId1 = m_partId0;
newPt.m_index0 = m_index1;
newPt.m_index1 = m_index0;
} else
{
newPt.m_partId0 = m_partId0;
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)
@@ -112,7 +127,7 @@ void btManifoldResult::addContactPoint(const btVector3& normalOnBInWorld,const b
//experimental feature info, for per-triangle material etc.
btCollisionObject* obj0 = isSwapped? m_body1 : m_body0;
btCollisionObject* obj1 = isSwapped? m_body0 : m_body1;
(*gContactAddedCallback)(m_manifoldPtr->getContactPoint(insertIndex),obj0,m_partId0,m_index0,obj1,m_partId1,m_index1);
(*gContactAddedCallback)(m_manifoldPtr->getContactPoint(insertIndex),obj0,newPt.m_partId0,newPt.m_index0,obj1,newPt.m_partId1,newPt.m_index1);
}
}

View File

@@ -28,6 +28,7 @@ class btManifoldPoint;
typedef bool (*ContactAddedCallback)(btManifoldPoint& cp, const btCollisionObject* colObj0,int partId0,int index0,const btCollisionObject* colObj1,int partId1,int index1);
extern ContactAddedCallback gContactAddedCallback;
//#define DEBUG_PART_INDEX 1
///btManifoldResult is a helper class to manage contact results.
@@ -50,6 +51,13 @@ class btManifoldResult : public btDiscreteCollisionDetectorInterface::Result
public:
btManifoldResult()
#ifdef DEBUG_PART_INDEX
:
m_partId0(-1),
m_partId1(-1),
m_index0(-1),
m_index1(-1)
#endif //DEBUG_PART_INDEX
{
}
@@ -71,11 +79,15 @@ public:
return m_manifoldPtr;
}
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1)
virtual void setShapeIdentifiersA(int partId0,int index0)
{
m_partId0=partId0;
m_partId1=partId1;
m_index0=index0;
}
virtual void setShapeIdentifiersB( int partId1,int index1)
{
m_partId1=partId1;
m_index1=index1;
}
@@ -99,6 +111,15 @@ public:
}
}
const btCollisionObject* getBody0Internal() const
{
return m_body0;
}
const btCollisionObject* getBody1Internal() const
{
return m_body1;
}
};

View File

@@ -340,7 +340,7 @@ btScalar btConvexShape::getMarginNonVirtual () const
btAssert (0);
return btScalar(0.0f);
}
#ifndef __SPU__
void btConvexShape::getAabbNonVirtual (const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const
{
switch (m_shapeType)
@@ -425,3 +425,5 @@ void btConvexShape::getAabbNonVirtual (const btTransform& t, btVector3& aabbMin,
// should never reach here
btAssert (0);
}
#endif //__SPU__

View File

@@ -24,9 +24,10 @@ btPolyhedralConvexShape::btPolyhedralConvexShape() :btConvexInternalShape()
btVector3 btPolyhedralConvexShape::localGetSupportingVertexWithoutMargin(const btVector3& vec0)const
{
int i;
btVector3 supVec(0,0,0);
#ifndef __SPU__
int i;
btScalar maxDot(btScalar(-BT_LARGE_FLOAT));
btVector3 vec = vec0;
@@ -54,8 +55,9 @@ btVector3 btPolyhedralConvexShape::localGetSupportingVertexWithoutMargin(const b
}
}
return supVec;
#endif //__SPU__
return supVec;
}

View File

@@ -45,12 +45,13 @@ ATTRIBUTE_ALIGNED16( struct) btIndexedMesh
btIndexedMesh()
{
:m_indexType(PHY_INTEGER),
#ifdef BT_USE_DOUBLE_PRECISION
m_vertexType = PHY_DOUBLE;
m_vertexType(PHY_DOUBLE)
#else // BT_USE_DOUBLE_PRECISION
m_vertexType = PHY_FLOAT;
m_vertexType(PHY_FLOAT)
#endif // BT_USE_DOUBLE_PRECISION
{
}
}
;

View File

@@ -231,6 +231,8 @@ class btPrimitiveManagerBase
{
public:
virtual ~btPrimitiveManagerBase() {}
//! determines if this manager consist on only triangles, which special case will be optimized
virtual bool is_trimesh() const = 0;
virtual int get_primitive_count() const = 0;

View File

@@ -102,6 +102,7 @@ public:
{
return m_parent->m_gim_shape->getChildShape(index);
}
virtual ~ChildShapeRetriever() {}
};
class TriangleShapeRetriever:public ChildShapeRetriever
@@ -113,6 +114,7 @@ public:
m_parent->m_gim_shape->getBulletTriangle(index,m_parent->m_trishape);
return &m_parent->m_trishape;
}
virtual ~TriangleShapeRetriever() {}
};
class TetraShapeRetriever:public ChildShapeRetriever
@@ -213,7 +215,8 @@ void btGImpactCollisionAlgorithm::addContactPoint(btCollisionObject * body0,
const btVector3 & normal,
btScalar distance)
{
m_resultOut->setShapeIdentifiers(m_part0,m_triface0,m_part1,m_triface1);
m_resultOut->setShapeIdentifiersA(m_part0,m_triface0);
m_resultOut->setShapeIdentifiersB(m_part1,m_triface1);
checkManifold(body0,body1);
m_resultOut->addContactPoint(normal,point,distance);
}
@@ -236,7 +239,8 @@ void btGImpactCollisionAlgorithm::shape_vs_shape_collision(
btCollisionAlgorithm* algor = newAlgorithm(body0,body1);
// post : checkManifold is called
m_resultOut->setShapeIdentifiers(m_part0,m_triface0,m_part1,m_triface1);
m_resultOut->setShapeIdentifiersA(m_part0,m_triface0);
m_resultOut->setShapeIdentifiersB(m_part1,m_triface1);
algor->processCollision(body0,body1,*m_dispatchInfo,m_resultOut);
@@ -262,7 +266,8 @@ void btGImpactCollisionAlgorithm::convex_vs_convex_collision(
body1->internalSetTemporaryCollisionShape(shape1);
m_resultOut->setShapeIdentifiers(m_part0,m_triface0,m_part1,m_triface1);
m_resultOut->setShapeIdentifiersA(m_part0,m_triface0);
m_resultOut->setShapeIdentifiersB(m_part1,m_triface1);
checkConvexAlgorithm(body0,body1);
m_convex_algorithm->processCollision(body0,body1,*m_dispatchInfo,m_resultOut);

View File

@@ -302,6 +302,7 @@ public:
class CompoundPrimitiveManager:public btPrimitiveManagerBase
{
public:
virtual ~CompoundPrimitiveManager() {}
btGImpactCompoundShape * m_compoundShape;
@@ -582,6 +583,7 @@ public:
}
virtual ~TrimeshPrimitiveManager() {}
void lock()
{

View File

@@ -33,8 +33,9 @@ struct btDiscreteCollisionDetectorInterface
virtual ~Result(){}
///setShapeIdentifiers provides experimental support for per-triangle material / custom material combiner
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1)=0;
///setShapeIdentifiersA/B provides experimental support for per-triangle material / custom material combiner
virtual void setShapeIdentifiersA(int partId0,int index0)=0;
virtual void setShapeIdentifiersB(int partId1,int index1)=0;
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)=0;
};

View File

@@ -297,6 +297,9 @@ namespace gjkepa2_impl
{
case eStatus::Valid: m_distance=m_ray.length();break;
case eStatus::Inside: m_distance=0;break;
default:
{
}
}
return(m_status);
}
@@ -415,8 +418,8 @@ namespace gjkepa2_impl
if(l>GJK_SIMPLEX3_EPS)
{
btScalar mindist=-1;
btScalar subw[2];
U subm;
btScalar subw[2]={0.f,0.f};
U subm(0);
for(U i=0;i<3;++i)
{
if(btDot(*vt[i],btCross(dl[i],n))>0)
@@ -462,8 +465,8 @@ namespace gjkepa2_impl
if(ng&&(btFabs(vl)>GJK_SIMPLEX4_EPS))
{
btScalar mindist=-1;
btScalar subw[3];
U subm;
btScalar subw[3]={0.f,0.f,0.f};
U subm(0);
for(U i=0;i<3;++i)
{
const U j=imd3[i];
@@ -892,6 +895,9 @@ bool btGjkEpaSolver2::Penetration( const btConvexShape* shape0,
case GJK::eStatus::Failed:
results.status=sResults::GJK_Failed;
break;
default:
{
}
}
return(false);
}

View File

@@ -55,7 +55,7 @@ static bool Penetration(const btConvexShape* shape0,const btTransform& wtrs0,
const btVector3& guess,
sResults& results,
bool usemargins=true);
#ifndef __SPU__
static btScalar SignedDistance( const btVector3& position,
btScalar margin,
const btConvexShape* shape,
@@ -66,6 +66,8 @@ static bool SignedDistance( const btConvexShape* shape0,const btTransform& wtrs
const btConvexShape* shape1,const btTransform& wtrs1,
const btVector3& guess,
sResults& results);
#endif //__SPU__
};
#endif

View File

@@ -32,7 +32,7 @@ bool btGjkEpaPenetrationDepthSolver::calcPenDepth( btSimplexSolverInterface& sim
(void)v;
(void)simplexSolver;
const btScalar radialmargin(btScalar(0.));
// const btScalar radialmargin(btScalar(0.));
btVector3 guessVector(transformA.getOrigin()-transformB.getOrigin());
btGjkEpaSolver2::sResults results;

View File

@@ -91,10 +91,13 @@ bool btMinkowskiPenetrationDepthSolver::calcPenDepth(btSimplexSolverInterface& s
btScalar m_depth;
bool m_hasResult;
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1)
virtual void setShapeIdentifiersA(int partId0,int index0)
{
(void)partId0;
(void)index0;
}
virtual void setShapeIdentifiersB(int partId1,int index1)
{
(void)partId1;
(void)index1;
}

View File

@@ -35,13 +35,16 @@ struct btPointCollector : public btDiscreteCollisionDetectorInterface::Result
{
}
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1)
virtual void setShapeIdentifiersA(int partId0,int index0)
{
(void)partId0;
(void)index0;
}
virtual void setShapeIdentifiersB(int partId1,int index1)
{
(void)partId1;
(void)index1;
//??
}
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)

View File

@@ -580,7 +580,6 @@ void btGeneric6DofConstraint::getInfo2NonVirtual (btConstraintInfo2* info, const
int btGeneric6DofConstraint::setLinearLimits(btConstraintInfo2* info,const btTransform& transA,const btTransform& transB,const btVector3& linVelA,const btVector3& linVelB,const btVector3& angVelA,const btVector3& angVelB)
{
btGeneric6DofConstraint * d6constraint = this;
int row = 0;
//solve linear limits
btRotationalLimitMotor limot;

View File

@@ -97,7 +97,7 @@ void btSequentialImpulseConstraintSolver::resolveSingleConstraintRowGenericSIMD(
const btScalar deltaVel1Dotn = c.m_contactNormal.dot(body1.m_deltaLinearVelocity) + c.m_relpos1CrossNormal.dot(body1.m_deltaAngularVelocity);
const btScalar deltaVel2Dotn = -c.m_contactNormal.dot(body2.m_deltaLinearVelocity) + c.m_relpos2CrossNormal.dot(body2.m_deltaAngularVelocity);
const btScalar delta_rel_vel = deltaVel1Dotn-deltaVel2Dotn;
// const btScalar delta_rel_vel = deltaVel1Dotn-deltaVel2Dotn;
deltaImpulse -= deltaVel1Dotn*c.m_jacDiagABInv;
deltaImpulse -= deltaVel2Dotn*c.m_jacDiagABInv;
@@ -403,7 +403,7 @@ btSolverConstraint& btSequentialImpulseConstraintSolver::addFrictionConstraint(c
rel_vel = vel1Dotn+vel2Dotn;
btScalar positionalError = 0.f;
// btScalar positionalError = 0.f;
btSimdScalar velocityError = - rel_vel;
btSimdScalar velocityImpulse = velocityError * btSimdScalar(solverConstraint.m_jacDiagABInv);
@@ -871,7 +871,7 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
{
int i;
btPersistentManifold* manifold = 0;
btCollisionObject* colObj0=0,*colObj1=0;
// btCollisionObject* colObj0=0,*colObj1=0;
for (i=0;i<numManifolds;i++)

View File

@@ -68,9 +68,8 @@ void btSliderConstraint::initParams()
btSliderConstraint::btSliderConstraint()
:btTypedConstraint(SLIDER_CONSTRAINT_TYPE),
m_useLinearReferenceFrameA(true),
m_useSolveConstraintObsolete(false)
// m_useSolveConstraintObsolete(true)
m_useSolveConstraintObsolete(false),
m_useLinearReferenceFrameA(true)
{
initParams();
}
@@ -78,12 +77,11 @@ btSliderConstraint::btSliderConstraint()
btSliderConstraint::btSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const btTransform& frameInA, const btTransform& frameInB, bool useLinearReferenceFrameA)
: btTypedConstraint(SLIDER_CONSTRAINT_TYPE, rbA, rbB)
, m_frameInA(frameInA)
, m_frameInB(frameInB),
m_useLinearReferenceFrameA(useLinearReferenceFrameA),
m_useSolveConstraintObsolete(false)
// m_useSolveConstraintObsolete(true)
: btTypedConstraint(SLIDER_CONSTRAINT_TYPE, rbA, rbB),
m_useSolveConstraintObsolete(false),
m_frameInA(frameInA),
m_frameInB(frameInB),
m_useLinearReferenceFrameA(useLinearReferenceFrameA)
{
initParams();
}
@@ -91,12 +89,10 @@ btSliderConstraint::btSliderConstraint(btRigidBody& rbA, btRigidBody& rbB, const
static btRigidBody s_fixed(0, 0, 0);
btSliderConstraint::btSliderConstraint(btRigidBody& rbB, const btTransform& frameInB, bool useLinearReferenceFrameB)
: btTypedConstraint(SLIDER_CONSTRAINT_TYPE, s_fixed, rbB)
,
: btTypedConstraint(SLIDER_CONSTRAINT_TYPE, s_fixed, rbB),
m_useSolveConstraintObsolete(false),
m_frameInB(frameInB),
m_useLinearReferenceFrameA(useLinearReferenceFrameB),
m_useSolveConstraintObsolete(false)
// m_useSolveConstraintObsolete(true)
m_useLinearReferenceFrameA(useLinearReferenceFrameB)
{
///not providing rigidbody B means implicitly using worldspace for body B
// m_frameInA.getOrigin() = m_rbA.getCenterOfMassTransform()(m_frameInA.getOrigin());
@@ -217,9 +213,6 @@ void btSliderConstraint::getInfo1NonVirtual(btConstraintInfo1* info)
void btSliderConstraint::getInfo2(btConstraintInfo2* info)
{
const btTransform& trA = getCalculatedTransformA();
const btTransform& trB = getCalculatedTransformB();
getInfo2NonVirtual(info,m_rbA.getCenterOfMassTransform(),m_rbB.getCenterOfMassTransform(), m_rbA.getLinearVelocity(),m_rbB.getLinearVelocity(), m_rbA.getInvMass(),m_rbB.getInvMass());
}

View File

@@ -64,8 +64,8 @@ btDiscreteDynamicsWorld::btDiscreteDynamicsWorld(btDispatcher* dispatcher,btBroa
m_constraintSolver(constraintSolver),
m_gravity(0,-10,0),
m_localTime(btScalar(1.)/btScalar(60.)),
m_profileTimings(0),
m_synchronizeAllMotionStates(false)
m_synchronizeAllMotionStates(false),
m_profileTimings(0)
{
if (!m_constraintSolver)
{

View File

@@ -66,7 +66,7 @@ int stallingUnalignedDmaSmallGet(void *ls, uint64_t ea, uint32_t size)
ATTRIBUTE_ALIGNED16(char tmpBuffer[32]);
char* mainMem = (char*)ea;
char* localStore = (char*)ls;
uint32_t i;
@@ -126,8 +126,10 @@ int stallingUnalignedDmaSmallGet(void *ls, uint64_t ea, uint32_t size)
#endif//FORCE_cellDmaUnalignedGet
#else
char* mainMem = (char*)ea;
//copy into final destination
#ifdef USE_MEMCPY
memcpy(tmpTarget,mainMem,size);
#else
for ( i=0;i<size;i++)

View File

@@ -77,7 +77,6 @@ struct bvhMeshShape_LocalStoreMemory
};
btVector3 localGetSupportingVertexWithoutMargin(int shapeType, void* shape, const btVector3& localDir,struct SpuConvexPolyhedronVertexData* convexVertexData);//, int *featureIndex)
void computeAabb (btVector3& aabbMin, btVector3& aabbMax, btConvexInternalShape* convexShape, ppu_address_t convexShapePtr, int shapeType, const btTransform& xform);
void dmaBvhShapeData (bvhMeshShape_LocalStoreMemory* bvhMeshShape, btBvhTriangleMeshShape* triMeshShape);
void dmaBvhIndexedMesh (btIndexedMesh* IndexMesh, IndexedMeshArray& indexArray, int index, uint32_t dmaTag);

View File

@@ -65,7 +65,12 @@ inline btScalar calculateCombinedRestitution(btScalar restitution0,btScalar rest
m_isSwapped = isSwapped;
}
void SpuContactResult::setShapeIdentifiers(int partId0,int index0, int partId1,int index1)
void SpuContactResult::setShapeIdentifiersA(int partId0,int index0)
{
}
void SpuContactResult::setShapeIdentifiersB(int partId1,int index1)
{
}
@@ -84,7 +89,7 @@ bool ManifoldResultAddContactPoint(const btVector3& normalOnBInWorld,
bool isSwapped)
{
float contactTreshold = manifoldPtr->getContactBreakingThreshold();
// float contactTreshold = manifoldPtr->getContactBreakingThreshold();
//spu_printf("SPU: add contactpoint, depth:%f, contactTreshold %f, manifoldPtr %llx\n",depth,contactTreshold,manifoldPtr);
@@ -174,7 +179,7 @@ void SpuContactResult::writeDoubleBufferedManifold(btPersistentManifold* lsManif
#endif
}
void SpuContactResult::addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,float depth)
void SpuContactResult::addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)
{
//spu_printf("*** SpuContactResult::addContactPoint: depth = %f\n",depth);

View File

@@ -87,14 +87,15 @@ class SpuContactResult : public btDiscreteCollisionDetectorInterface::Result
return m_spuManifold;
}
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1);
virtual void setShapeIdentifiersA(int partId0,int index0);
virtual void setShapeIdentifiersB(int partId1,int index1);
void setContactInfo(btPersistentManifold* spuManifold, ppu_address_t manifoldAddress,const btTransform& worldTrans0,const btTransform& worldTrans1, btScalar restitution0,btScalar restitution1, btScalar friction0,btScalar friction01, bool isSwapped);
void writeDoubleBufferedManifold(btPersistentManifold* lsManifold, btPersistentManifold* mmManifold);
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,float depth);
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth);
void flush();
};

View File

@@ -363,7 +363,7 @@ public:
triangleConcaveInput.m_spuCollisionShapes[1] = &tmpTriangleShape;
triangleConcaveInput.m_shapeType1 = TRIANGLE_SHAPE_PROXYTYPE;
m_spuContacts.setShapeIdentifiers(-1,-1,subPart,triangleIndex);
m_spuContacts.setShapeIdentifiersB(subPart,triangleIndex);
// m_spuContacts.flush();
@@ -1100,9 +1100,13 @@ void processCollisionTask(void* userPtr, void* lsMemPtr)
{
SpuContactResult& m_spuContacts;
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1)
virtual void setShapeIdentifiersA(int partId0,int index0)
{
m_spuContacts.setShapeIdentifiers(partId0,index0,partId1,index1);
m_spuContacts.setShapeIdentifiersA(partId0,index0);
}
virtual void setShapeIdentifiersB(int partId1,int index1)
{
m_spuContacts.setShapeIdentifiersB(partId1,index1);
}
virtual void addContactPoint(const btVector3& normalOnBInWorld,const btVector3& pointInWorld,btScalar depth)
{

View File

@@ -93,10 +93,14 @@ bool SpuMinkowskiPenetrationDepthSolver::calcPenDepth( btVoronoiSimplexSolver& s
btScalar m_depth;
bool m_hasResult;
virtual void setShapeIdentifiers(int partId0,int index0, int partId1,int index1)
virtual void setShapeIdentifiersA(int partId0,int index0)
{
(void)partId0;
(void)index0;
}
virtual void setShapeIdentifiersB(int partId1,int index1)
{
(void)partId1;
(void)index1;
}
@@ -111,7 +115,7 @@ bool SpuMinkowskiPenetrationDepthSolver::calcPenDepth( btVoronoiSimplexSolver& s
//just take fixed number of orientation, and sample the penetration depth in that direction
btScalar minProj = btScalar(BT_LARGE_FLOAT);
btVector3 minNorm;
btVector3 minNorm(0.f,0.f,0.f);
btVector3 minVertex;
btVector3 minA,minB;
btVector3 seperatingAxisInA,seperatingAxisInB;
@@ -240,8 +244,8 @@ bool SpuMinkowskiPenetrationDepthSolver::calcPenDepth( btVoronoiSimplexSolver& s
seperatingAxisInA = (-norm)* transA.getBasis();
seperatingAxisInB = norm* transB.getBasis();
pInA = localGetSupportingVertexWithoutMargin(shapeTypeA, convexA, seperatingAxisInA,convexVertexDataA);//, NULL);
qInB = localGetSupportingVertexWithoutMargin(shapeTypeB, convexB, seperatingAxisInB,convexVertexDataB);//, NULL);
pInA = convexA->localGetSupportVertexWithoutMarginNonVirtual( seperatingAxisInA);//, NULL);
qInB = convexB->localGetSupportVertexWithoutMarginNonVirtual(seperatingAxisInB);//, NULL);
// pInA = convexA->localGetSupportingVertexWithoutMargin(seperatingAxisInA);
// qInB = convexB->localGetSupportingVertexWithoutMargin(seperatingAxisInB);

View File

@@ -6,6 +6,7 @@
#include "../SpuNarrowPhaseCollisionTask/SpuCollisionShapes.h"
#include "SpuSubSimplexConvexCast.h"
#include "LinearMath/btAabbUtil2.h"
#include "BulletCollision/CollisionShapes/btTriangleShape.h"
/* Future optimization strategies:
@@ -79,7 +80,7 @@ void GatherCollisionObjectAndShapeData (RaycastGatheredObjectData* gatheredObjec
gatheredObjectData->m_collisionMargin = lsMemPtr->getCollisionObjectWrapper()->getCollisionMargin ();
gatheredObjectData->m_shapeType = lsMemPtr->getCollisionObjectWrapper()->getShapeType ();
gatheredObjectData->m_collisionShape = (ppu_address_t)lsMemPtr->getColObj()->getCollisionShape();
gatheredObjectData->m_spuCollisionShape = (void*)&lsMemPtr->gCollisionShape.collisionShape;
gatheredObjectData->m_spuCollisionShape = (btConvexShape*)&lsMemPtr->gCollisionShape.collisionShape;
/* DMA shape data */
dmaCollisionShape (gatheredObjectData->m_spuCollisionShape, gatheredObjectData->m_collisionShape, 1, gatheredObjectData->m_shapeType);
@@ -254,7 +255,8 @@ public:
RaycastGatheredObjectData triangleGatheredObjectData (*m_gatheredObjectData);
triangleGatheredObjectData.m_shapeType = TRIANGLE_SHAPE_PROXYTYPE;
triangleGatheredObjectData.m_spuCollisionShape = &spuTriangleVertices[0];
btTriangleShape triangle(spuTriangleVertices[0],spuTriangleVertices[1],spuTriangleVertices[2]);
triangleGatheredObjectData.m_spuCollisionShape = &triangle;
//printf("%f %f %f\n", spuTriangleVertices[0][0],spuTriangleVertices[0][1],spuTriangleVertices[0][2]);
//printf("%f %f %f\n", spuTriangleVertices[1][0],spuTriangleVertices[1][1],spuTriangleVertices[1][2]);
@@ -361,7 +363,8 @@ public:
RaycastGatheredObjectData triangleGatheredObjectData (*m_gatheredObjectData);
triangleGatheredObjectData.m_shapeType = TRIANGLE_SHAPE_PROXYTYPE;
triangleGatheredObjectData.m_spuCollisionShape = &spuTriangleVertices[0];
btTriangleShape triangle(spuTriangleVertices[0],spuTriangleVertices[1],spuTriangleVertices[2]);
triangleGatheredObjectData.m_spuCollisionShape = &triangle;
//printf("%f %f %f\n", spuTriangleVertices[0][0],spuTriangleVertices[0][1],spuTriangleVertices[0][2]);
//printf("%f %f %f\n", spuTriangleVertices[1][0],spuTriangleVertices[1][1],spuTriangleVertices[1][2]);
@@ -395,7 +398,7 @@ void spuWalkStacklessQuantizedTreeAgainstRays(RaycastTask_LocalStoreMemory* lsMe
{
int curIndex = startNodeIndex;
int walkIterations = 0;
int subTreeSize = endNodeIndex - startNodeIndex;
//int subTreeSize = endNodeIndex - startNodeIndex;
int escapeIndex;
@@ -503,8 +506,8 @@ void spuWalkStacklessQuantizedTreeAgainstRays(RaycastTask_LocalStoreMemory* lsMe
void performRaycastAgainstConcave (RaycastGatheredObjectData* gatheredObjectData, const SpuRaycastTaskWorkUnit* workUnits, SpuRaycastTaskWorkUnitOut* workUnitsOut, int numWorkUnits, RaycastTask_LocalStoreMemory* lsMemPtr)
{
//order: first collision shape is convex, second concave. m_isSwapped is true, if the original order was opposite
register int dmaSize;
register ppu_address_t dmaPpuAddress2;
// register int dmaSize;
// register ppu_address_t dmaPpuAddress2;
btBvhTriangleMeshShape* trimeshShape = (btBvhTriangleMeshShape*)gatheredObjectData->m_spuCollisionShape;
@@ -632,7 +635,7 @@ void performRaycastAgainstCompound (RaycastGatheredObjectData* gatheredObjectDat
void
performRaycastAgainstConvex (RaycastGatheredObjectData* gatheredObjectData, const SpuRaycastTaskWorkUnit& workUnit, SpuRaycastTaskWorkUnitOut* workUnitOut, RaycastTask_LocalStoreMemory* lsMemPtr)
{
SpuVoronoiSimplexSolver simplexSolver;
btVoronoiSimplexSolver simplexSolver;
btTransform rayFromTrans, rayToTrans;
rayFromTrans.setIdentity ();
@@ -660,7 +663,7 @@ performRaycastAgainstConvex (RaycastGatheredObjectData* gatheredObjectData, cons
}
/* performRaycast */
SpuSubsimplexRayCast caster (gatheredObjectData->m_spuCollisionShape, &lsMemPtr->convexVertexData, gatheredObjectData->m_shapeType, gatheredObjectData->m_collisionMargin, &simplexSolver);
SpuSubsimplexRayCast caster ((btConvexShape*)gatheredObjectData->m_spuCollisionShape, &lsMemPtr->convexVertexData, gatheredObjectData->m_shapeType, gatheredObjectData->m_collisionMargin, &simplexSolver);
bool r = caster.calcTimeOfImpact (rayFromTrans, rayToTrans, gatheredObjectData->m_worldTransform, gatheredObjectData->m_worldTransform,result);
if (r)
@@ -682,7 +685,7 @@ void processRaycastTask(void* userPtr, void* lsMemory)
//spu_printf("in processRaycastTask %d\n", taskDesc.numSpuCollisionObjectWrappers);
/* for each object */
RaycastGatheredObjectData gatheredObjectData;
for (int objectId = 0; objectId < taskDesc.numSpuCollisionObjectWrappers; objectId++)
for (unsigned int objectId = 0; objectId < taskDesc.numSpuCollisionObjectWrappers; objectId++)
{
//spu_printf("%d / %d\n", objectId, taskDesc.numSpuCollisionObjectWrappers);
@@ -692,14 +695,15 @@ void processRaycastTask(void* userPtr, void* lsMemory)
if (btBroadphaseProxy::isConcave (gatheredObjectData.m_shapeType))
{
SpuRaycastTaskWorkUnitOut tWorkUnitsOut[SPU_RAYCAST_WORK_UNITS_PER_TASK];
for (int rayId = 0; rayId < taskDesc.numWorkUnits; rayId++)
unsigned int rayId ;
for (rayId = 0; rayId < taskDesc.numWorkUnits; rayId++)
{
tWorkUnitsOut[rayId].hitFraction = 1.0;
}
performRaycastAgainstConcave (&gatheredObjectData, &taskDesc.workUnits[0], &tWorkUnitsOut[0], taskDesc.numWorkUnits, localMemory);
for (int rayId = 0; rayId < taskDesc.numWorkUnits; rayId++)
for (rayId = 0; rayId < taskDesc.numWorkUnits; rayId++)
{
const SpuRaycastTaskWorkUnit& workUnit = taskDesc.workUnits[rayId];
if (tWorkUnitsOut[rayId].hitFraction == 1.0)

View File

@@ -9,7 +9,7 @@
ATTRIBUTE_ALIGNED16(struct) RaycastGatheredObjectData
{
ppu_address_t m_collisionShape;
void* m_spuCollisionShape;
btCollisionShape* m_spuCollisionShape;
btVector3 m_primitiveDimensions;
int m_shapeType;
float m_collisionMargin;

View File

@@ -21,8 +21,8 @@ subject to the following restrictions:
#include "BulletCollision/NarrowPhaseCollision/btSimplexSolverInterface.h"
SpuSubsimplexRayCast::SpuSubsimplexRayCast (void* shapeB, SpuConvexPolyhedronVertexData* convexDataB, int shapeTypeB, float marginB,
SpuVoronoiSimplexSolver* simplexSolver)
SpuSubsimplexRayCast::SpuSubsimplexRayCast (btConvexShape* shapeB, SpuConvexPolyhedronVertexData* convexDataB, int shapeTypeB, float marginB,
btVoronoiSimplexSolver* simplexSolver)
:m_simplexSolver(simplexSolver), m_shapeB(shapeB), m_convexDataB(convexDataB), m_shapeTypeB(shapeTypeB), m_marginB(marginB)
{
}
@@ -42,8 +42,7 @@ SpuSubsimplexRayCast::SpuSubsimplexRayCast (void* shapeB, SpuConvexPolyhedronVer
void supportPoints (const btTransform& xformRay,
const btTransform& xformB,
const int shapeType,
const void* shape,
SpuConvexPolyhedronVertexData* convexVertexData,
const btConvexShape* shape,
const btScalar marginB,
const btVector3& seperatingAxis,
btVector3& w,
@@ -54,7 +53,7 @@ void supportPoints (const btTransform& xformRay,
saUnit.normalize();
btVector3 SupportPellet = xformRay(0.0001 * -saUnit);
btVector3 rotatedSeperatingAxis = seperatingAxis * xformB.getBasis();
btVector3 SupportShape = xformB(localGetSupportingVertexWithoutMargin(shapeType, (void*)shape, rotatedSeperatingAxis, convexVertexData));
btVector3 SupportShape = shape->localGetSupportVertexWithoutMarginNonVirtual(rotatedSeperatingAxis);
SupportShape += saUnit * marginB;
w = SupportPellet - SupportShape;
supVertexRay = SupportPellet;
@@ -82,7 +81,7 @@ bool SpuSubsimplexRayCast::calcTimeOfImpact(const btTransform& fromRay,
btVector3 supVertexRay;
btVector3 supVertexB;
btVector3 v;
supportPoints (fromRay, fromB, m_shapeTypeB, m_shapeB, m_convexDataB, m_marginB, r, v, supVertexRay, supVertexB);
supportPoints (fromRay, fromB, m_shapeTypeB, m_shapeB, m_marginB, r, v, supVertexRay, supVertexB);
btVector3 n;
n.setValue(btScalar(0.), btScalar(0.), btScalar(0.));
@@ -104,7 +103,7 @@ bool SpuSubsimplexRayCast::calcTimeOfImpact(const btTransform& fromRay,
while ( (dist2 > epsilon) && maxIter--)
{
supportPoints (interpolatedTransRay, interpolatedTransB, m_shapeTypeB, m_shapeB, m_convexDataB, m_marginB, v, w, supVertexRay, supVertexB);
supportPoints (interpolatedTransRay, interpolatedTransB, m_shapeTypeB, m_shapeB, m_marginB, v, w, supVertexRay, supVertexB);
btScalar VdotW = v.dot(w);

View File

@@ -17,7 +17,7 @@ subject to the following restrictions:
#ifndef SPU_SUBSIMPLEX_RAY_CAST_H
#define SPU_SUBSIMPLEX_RAY_CAST_H
#include "../SpuNarrowPhaseCollisionTask/SpuVoronoiSimplexSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
#include "../SpuNarrowPhaseCollisionTask/SpuCollisionShapes.h"
#include "SpuRaycastTask.h"
@@ -35,15 +35,15 @@ struct SpuCastResult
/// Objects should not start in overlap, otherwise results are not defined.
class SpuSubsimplexRayCast
{
SpuVoronoiSimplexSolver* m_simplexSolver;
void* m_shapeB;
btVoronoiSimplexSolver* m_simplexSolver;
btConvexShape* m_shapeB;
SpuConvexPolyhedronVertexData* m_convexDataB;
int m_shapeTypeB;
float m_marginB;
public:
SpuSubsimplexRayCast (void* shapeB, SpuConvexPolyhedronVertexData* convexDataB, int shapeTypeB, float marginB,
SpuVoronoiSimplexSolver* simplexSolver);
SpuSubsimplexRayCast (btConvexShape* shapeB, SpuConvexPolyhedronVertexData* convexDataB, int shapeTypeB, float marginB,
btVoronoiSimplexSolver* simplexSolver);
//virtual ~btSubsimplexConvexCast();

View File

@@ -714,7 +714,7 @@ static float computeJacobianInverse (const btRigidBody* rb0, const btRigidBody*
return 1.0f/jacobian;
}
/*
static float computeAngularJacobianInverse (const btRigidBody* rb0, const btRigidBody* rb1,
const btVector3& normal)
{
@@ -724,7 +724,7 @@ static float computeAngularJacobianInverse (const btRigidBody* rb0, const btRigi
return 1.0f/jacobian;
}
/*static void setupLinearConstraintWorld (btSolverConstraint& constraint, const btRigidBody* rb0, const btRigidBody* rb1,
static void setupLinearConstraintWorld (btSolverConstraint& constraint, const btRigidBody* rb0, const btRigidBody* rb1,
const btVector3& anchorAinW, const btVector3& anchorBinW, const btContactSolverInfoData& solverInfo)
{
btVector3 relPos1 = anchorAinW - rb0->getCenterOfMassPosition();

View File

@@ -168,8 +168,7 @@ void btSoftBodyTriangleCallback::processTriangle(btVector3* triangle,int partId,
///this should use the btDispatcher, so the actual registered algorithm is used
// btConvexConvexAlgorithm cvxcvxalgo(m_manifoldPtr,ci,m_convexBody,m_triBody);
//m_resultOut->setShapeIdentifiers(-1,-1,partId,triangleIndex);
// cvxcvxalgo.setShapeIdentifiers(-1,-1,partId,triangleIndex);
//m_resultOut->setShapeIdentifiersB(partId,triangleIndex);
// cvxcvxalgo.processCollision(m_convexBody,m_triBody,*m_dispatchInfoPtr,m_resultOut);
colAlgo->processCollision(m_softBody,m_triBody,*m_dispatchInfoPtr,m_resultOut);
colAlgo->~btCollisionAlgorithm();

View File

@@ -876,7 +876,7 @@ bool HullLibrary::CleanupVertices(unsigned int svcount,
vcount = 0;
btScalar recip[3];
btScalar recip[3]={0.f,0.f,0.f};
if ( scale )
{

View File

@@ -31,14 +31,11 @@ ATTRIBUTE_ALIGNED16(class) btVector3
public:
#if defined (__SPU__) && defined (__CELLOS_LV2__)
union {
vec_float4 mVec128;
btScalar m_floats[4];
};
public:
vec_float4 get128() const
SIMD_FORCE_INLINE const vec_float4& get128() const
{
return mVec128;
return *((const vec_float4*)&m_floats[0]);
}
public:
#else //__CELLOS_LV2__ __SPU__