Fixes / improvements in soft body:

avoid blow-up due to improper mass calculation for fixed nodes (happened when using clusters)
allow to create collision clusters for each tetrahedron or triangle, when using btSoftBody::generateClusters(0)
tweak soft body demos a bit, only draw debug wireframe if necessary
This commit is contained in:
erwin.coumans
2009-08-28 21:23:54 +00:00
parent f492899499
commit 2ef7c1a457
7 changed files with 218 additions and 68 deletions

View File

@@ -135,7 +135,7 @@ void NextScene()
gDebugConstraints=1;
}
if(testSelection>23)
if(testSelection>28)
testSelection=0;
if (glui)
glui->sync_live();

View File

@@ -163,6 +163,7 @@ void SoftDemo::clientMoveAndDisplay()
int numSimSteps;
numSimSteps = m_dynamicsWorld->stepSimulation(dt);
//numSimSteps = m_dynamicsWorld->stepSimulation(dt,10,1./240.f);
#ifdef VERBOSE_TIMESTEPPING_CONSOLEOUTPUT
if (!numSimSteps)
@@ -307,8 +308,9 @@ static void Ctor_RbUpStack(SoftDemo* pdemo,int count)
btCollisionShape* shape[]={cylinderCompound,
new btSphereShape(1.5),
new btBoxShape(btVector3(1,1,1))
new btBoxShape(btVector3(1,1,1)),
new btSphereShape(1.5)
};
static const int nshapes=sizeof(shape)/sizeof(shape[0]);
for(int i=0;i<count;++i)
@@ -317,6 +319,7 @@ static void Ctor_RbUpStack(SoftDemo* pdemo,int count)
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0,2+6*i,0));
pdemo->localCreateRigidBody(mass,startTransform,shape[i%nshapes]);
//pdemo->localCreateRigidBody(mass,startTransform,shape[0]);
}
}
@@ -1016,8 +1019,9 @@ static void Init_ClusterCollide1(SoftDemo* pdemo)
btVector3(+s,0,-s),
btVector3(-s,0,+s),
btVector3(+s,0,+s),
31,31,
1+2+4+8,true);
17,17,//9,9,//31,31,
1+2+4+8,
true);
btSoftBody::Material* pm=psb->appendMaterial();
pm->m_kLST = 0.4;
pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
@@ -1025,10 +1029,17 @@ static void Init_ClusterCollide1(SoftDemo* pdemo)
psb->m_cfg.kSRHR_CL = 1;
psb->m_cfg.kSR_SPLT_CL = 0;
psb->m_cfg.collisions = btSoftBody::fCollision::CL_SS+
btSoftBody::fCollision::CL_RS;
psb->generateBendingConstraints(2,pm);
psb->getCollisionShape()->setMargin(0.05);
psb->setTotalMass(50);
psb->generateClusters(64);
///pass zero in generateClusters to create cluster for each tetrahedron or triangle
psb->generateClusters(0);
//psb->generateClusters(64);
pdemo->getSoftDynamicsWorld()->addSoftBody(psb);
Ctor_RbUpStack(pdemo,10);
@@ -1122,7 +1133,7 @@ static void Init_ClusterCombine(SoftDemo* pdemo)
//
static void Init_ClusterCar(SoftDemo* pdemo)
{
pdemo->setAzi(270);
pdemo->setAzi(180);
const btVector3 origin(100,80,0);
const btQuaternion orientation(-SIMD_PI/2,0,0);
const btScalar widthf=8;
@@ -1275,7 +1286,19 @@ static void Init_TetraBunny(SoftDemo* pdemo)
psb->rotate(btQuaternion(SIMD_PI/2,0,0));
psb->setVolumeMass(150);
psb->m_cfg.piterations=2;
//psb->m_cfg.piterations=1;
pdemo->m_cutting=true;
//psb->getCollisionShape()->setMargin(0.01);
psb->m_cfg.collisions = btSoftBody::fCollision::CL_SS+ btSoftBody::fCollision::CL_RS
//+ btSoftBody::fCollision::CL_SELF
;
///pass zero in generateClusters to create cluster for each tetrahedron or triangle
psb->generateClusters(0);
//psb->m_materials[0]->m_kLST=.2;
psb->m_cfg.kDF = 10. ;
}
//
@@ -1293,24 +1316,37 @@ static void Init_TetraCube(SoftDemo* pdemo)
psb->translate(btVector3(0,5,0));
psb->setVolumeMass(300);
///fix one vertex
psb->setMass(0,0);
//psb->setMass(0,0);
//psb->setMass(10,0);
//psb->setMass(20,0);
psb->m_cfg.piterations=1;
//psb->m_materials[0]->m_kLST=0.05;
//psb->generateClusters(128);
psb->generateClusters(16);
//psb->getCollisionShape()->setMargin(0.5);
psb->getCollisionShape()->setMargin(0.01);
psb->m_cfg.collisions = btSoftBody::fCollision::CL_SS+ btSoftBody::fCollision::CL_RS
//+ btSoftBody::fCollision::CL_SELF
;
psb->m_materials[0]->m_kLST=0.8;
pdemo->m_cutting=true;
}
unsigned current_demo=21;
unsigned current_demo=28;//19;
void SoftDemo::clientResetScene()
{
m_azi = 0;
m_cameraDistance = 30.f;
m_cameraTargetPosition.setValue(0,0,0);
DemoApplication::clientResetScene();
/* Clean up */
for(int i=m_dynamicsWorld->getNumCollisionObjects()-1;i>0;i--)
for(int i=m_dynamicsWorld->getNumCollisionObjects()-1;i>=0;i--)
{
btCollisionObject* obj=m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body=btRigidBody::upcast(obj);
@@ -1376,6 +1412,30 @@ void SoftDemo::clientResetScene()
};
current_demo=current_demo%(sizeof(demofncs)/sizeof(demofncs[0]));
//create ground object
btTransform tr;
tr.setIdentity();
tr.setOrigin(btVector3(0,-12,0));
btCollisionObject* newOb = new btCollisionObject();
newOb->setWorldTransform(tr);
newOb->setInterpolationWorldTransform( tr);
if (current_demo>19)
{
newOb->setCollisionShape(m_collisionShapes[0]);
} else
{
newOb->setCollisionShape(m_collisionShapes[1]);
}
m_dynamicsWorld->addCollisionObject(newOb);
motorcontrol.goal = 0;
motorcontrol.maxtorque = 0;
m_softBodyWorldInfo.air_density = (btScalar)1.2;
m_softBodyWorldInfo.water_density = 0;
m_softBodyWorldInfo.water_offset = 0;
@@ -1660,15 +1720,14 @@ void SoftDemo::initPhysics()
{
///create concave ground mesh
m_azi = 0;
//reset and disable motorcontrol at the start
motorcontrol.goal = 0;
motorcontrol.maxtorque = 0;
m_azi = 0;
btCollisionShape* groundShape = 0;
bool useConcaveMesh = false;//not ready yet true;
if (useConcaveMesh)
{
int i;
int j;
@@ -1720,14 +1779,14 @@ void SoftDemo::initPhysics()
bool useQuantizedAabbCompression = true;
groundShape = new btBvhTriangleMeshShape(indexVertexArrays,useQuantizedAabbCompression);
} else
{
groundShape = new btBoxShape (btVector3(200,CUBE_HALF_EXTENTS,200));
groundShape->setMargin(0.5);
}
m_collisionShapes.push_back(groundShape);
btCollisionShape* groundBox = new btBoxShape (btVector3(100,CUBE_HALF_EXTENTS,100));
m_collisionShapes.push_back(groundBox);
btCompoundShape* cylinderCompound = new btCompoundShape;
btCollisionShape* cylinderShape = new btCylinderShape (btVector3(CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS));
btTransform localTransform;
@@ -1782,21 +1841,6 @@ void SoftDemo::initPhysics()
btTransform tr;
tr.setIdentity();
tr.setOrigin(btVector3(0,-12,0));
#define USE_COLLISION_OBJECT 1
#ifdef USE_COLLISION_OBJECT
btCollisionObject* newOb = new btCollisionObject();
newOb->setWorldTransform(tr);
newOb->setInterpolationWorldTransform( tr);
newOb->setCollisionShape(m_collisionShapes[0]);
m_dynamicsWorld->addCollisionObject(newOb);
#else
this->localCreateRigidBody(0,tr,m_collisionShapes[0]);
#endif //USE_COLLISION_OBJECT
// clientResetScene();

View File

@@ -1053,10 +1053,50 @@ int btSoftBody::generateClusters(int k,int maxiterations)
releaseCluster(i--);
}
}
} else
{
//create a cluster for each tetrahedron (if tetrahedra exist) or each face
if (m_tetras.size())
{
m_clusters.resize(m_tetras.size());
for(i=0;i<m_clusters.size();++i)
{
m_clusters[i] = new(btAlignedAlloc(sizeof(Cluster),16)) Cluster();
m_clusters[i]->m_collide= true;
}
for (i=0;i<m_tetras.size();i++)
{
for (int j=0;j<4;j++)
{
m_clusters[i]->m_nodes.push_back(m_tetras[i].m_n[j]);
}
}
} else
{
m_clusters.resize(m_faces.size());
for(i=0;i<m_clusters.size();++i)
{
m_clusters[i] = new(btAlignedAlloc(sizeof(Cluster),16)) Cluster();
m_clusters[i]->m_collide= true;
}
for(i=0;i<m_faces.size();++i)
{
for(int j=0;j<3;++j)
{
m_clusters[i]->m_nodes.push_back(m_faces[i].m_n[j]);
}
}
}
}
if (m_clusters.size())
{
initializeClusters();
updateClusters();
//for self-collision
m_clusterConnectivity.resize(m_clusters.size()*m_clusters.size());
{
@@ -1084,11 +1124,10 @@ int btSoftBody::generateClusters(int k,int maxiterations)
}
}
}
}
return(m_clusters.size());
}
return(0);
}
//
void btSoftBody::refine(ImplicitFn* ifn,btScalar accurary,bool cut)
@@ -2077,7 +2116,8 @@ void btSoftBody::initializeClusters()
c.m_masses.resize(c.m_nodes.size());
for(int j=0;j<c.m_nodes.size();++j)
{
c.m_masses[j] = c.m_nodes[j]->m_im>0?1/c.m_nodes[j]->m_im:0;
c.m_masses[j] = c.m_nodes[j]->m_im>0?1/c.m_nodes[j]->m_im: BT_LARGE_FLOAT;
//c.m_masses[j] = c.m_nodes[j]->m_im>0?1/c.m_nodes[j]->m_im: 0.f;
c.m_imass += c.m_masses[j];
}
c.m_imass = 1/c.m_imass;
@@ -2107,7 +2147,9 @@ void btSoftBody::initializeClusters()
ii[1][0]=ii[0][1];
ii[2][0]=ii[0][2];
ii[2][1]=ii[1][2];
ii = ii.inverse();
/* Frame */
c.m_framexform.setIdentity();
c.m_framexform.setOrigin(c.m_com);
@@ -2481,9 +2523,30 @@ void btSoftBody::CJoint::Solve(btScalar dt,btScalar sor)
impulse.m_velocity += iv+fv*m_friction;
}
impulse.m_velocity=m_massmatrix*impulse.m_velocity*sor;
if (m_bodies[0].m_soft==m_bodies[1].m_soft)
{
if ((impulse.m_velocity.getX() ==impulse.m_velocity.getX())&&(impulse.m_velocity.getY() ==impulse.m_velocity.getY())&&
(impulse.m_velocity.getZ() ==impulse.m_velocity.getZ()))
{
if (impulse.m_asVelocity)
{
if (impulse.m_velocity.length() <m_bodies[0].m_soft->m_maxSelfCollisionImpulse)
{
} else
{
m_bodies[0].applyImpulse(-impulse*m_bodies[0].m_soft->m_selfCollisionImpulseFactor,m_rpos[0]);
m_bodies[1].applyImpulse( impulse*m_bodies[0].m_soft->m_selfCollisionImpulseFactor,m_rpos[1]);
}
}
}
} else
{
m_bodies[0].applyImpulse(-impulse,m_rpos[0]);
m_bodies[1].applyImpulse( impulse,m_rpos[1]);
}
}
//
void btSoftBody::CJoint::Terminate(btScalar dt)
@@ -2684,7 +2747,8 @@ void btSoftBody::PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti)
c.m_weights);
const btVector3 vr=(n.m_x-n.m_q)-(p-q);
btVector3 corr(0,0,0);
if(btDot(vr,nr)<0)
btScalar dot = btDot(vr,nr);
if(dot<0)
{
const btScalar j=c.m_margin-(btDot(nr,n.m_x)-btDot(nr,p));
corr+=c.m_normal*j;
@@ -2735,10 +2799,14 @@ btSoftBody::psolver_t btSoftBody::getSolver(ePSolver::_ solver)
{
switch(solver)
{
case ePSolver::Anchors: return(&btSoftBody::PSolve_Anchors);
case ePSolver::Linear: return(&btSoftBody::PSolve_Links);
case ePSolver::RContacts: return(&btSoftBody::PSolve_RContacts);
case ePSolver::SContacts: return(&btSoftBody::PSolve_SContacts);
case ePSolver::Anchors:
return(&btSoftBody::PSolve_Anchors);
case ePSolver::Linear:
return(&btSoftBody::PSolve_Links);
case ePSolver::RContacts:
return(&btSoftBody::PSolve_RContacts);
case ePSolver::SContacts:
return(&btSoftBody::PSolve_SContacts);
}
return(0);
}
@@ -2800,10 +2868,16 @@ void btSoftBody::defaultCollisionHandler(btSoftBody* psb)
switch(cf&fCollision::SVSmask)
{
case fCollision::CL_SS:
{
//support self-collision if CL_SELF flag set
if (this!=psb || psb->m_cfg.collisions&fCollision::CL_SELF)
{
btSoftColliders::CollideCL_SS docollide;
docollide.Process(this,psb);
}
}
break;
case fCollision::VF_SS:
{
@@ -2829,5 +2903,9 @@ void btSoftBody::defaultCollisionHandler(btSoftBody* psb)
}
}
break;
default:
{
}
}
}

View File

@@ -110,9 +110,10 @@ public:
SDF_RS = 0x0001, ///SDF based rigid vs soft
CL_RS = 0x0002, ///Cluster vs convex rigid vs soft
SVSmask = 0x00f0, ///Rigid versus soft mask
SVSmask = 0x0030, ///Rigid versus soft mask
VF_SS = 0x0010, ///Vertex vs face soft vs soft handling
CL_SS = 0x0020, ///Cluster vs cluster soft vs soft handling
CL_SELF = 0x0040, ///Cluster soft body self collision
/* presets */
Default = SDF_RS,
END
@@ -307,9 +308,14 @@ public:
btScalar m_ldamping; /* Linear damping */
btScalar m_adamping; /* Angular damping */
btScalar m_matching;
btScalar m_maxSelfCollisionImpulse;
btScalar m_selfCollisionImpulseFactor;
bool m_collide;
int m_clusterIndex;
Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0) {}
Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0)
,m_maxSelfCollisionImpulse(100.f),
m_selfCollisionImpulseFactor(0.01f)
{}
};
/* Impulse */
struct Impulse
@@ -406,8 +412,16 @@ public:
}
void applyImpulse(const Impulse& impulse,const btVector3& rpos) const
{
if(impulse.m_asVelocity) applyVImpulse(impulse.m_velocity,rpos);
if(impulse.m_asDrift) applyDImpulse(impulse.m_drift,rpos);
if(impulse.m_asVelocity)
{
// printf("impulse.m_velocity = %f,%f,%f\n",impulse.m_velocity.getX(),impulse.m_velocity.getY(),impulse.m_velocity.getZ());
applyVImpulse(impulse.m_velocity,rpos);
}
if(impulse.m_asDrift)
{
// printf("impulse.m_drift = %f,%f,%f\n",impulse.m_drift.getX(),impulse.m_drift.getY(),impulse.m_drift.getZ());
applyDImpulse(impulse.m_drift,rpos);
}
}
void applyVAImpulse(const btVector3& impulse) const
{
@@ -780,6 +794,8 @@ public:
void releaseCluster(int index);
void releaseClusters();
/* Generate clusters (K-mean) */
///generateClusters with k=0 will create a convex cluster for each tetrahedron or triangle
///otherwise an approximation will be used (better performance)
int generateClusters(int k,int maxiterations=8192);
/* Refine */
void refine(ImplicitFn* ifn,btScalar accurary,bool cut);

View File

@@ -95,7 +95,7 @@ void btSoftBodyTriangleCallback::processTriangle(btVector3* triangle,int partId,
ci.m_dispatcher1 = m_dispatcher;
///debug drawing of the overlapping triangles
if (m_dispatchInfoPtr && m_dispatchInfoPtr->m_debugDraw && m_dispatchInfoPtr->m_debugDraw->getDebugMode() > 0)
if (m_dispatchInfoPtr && m_dispatchInfoPtr->m_debugDraw && m_dispatchInfoPtr->m_debugDraw->getDebugMode() &btIDebugDraw::DBG_DrawWireframe)
{
btVector3 color(255,255,0);
btTransform& tr = ob->getWorldTransform();

View File

@@ -923,7 +923,7 @@ for(int i=0;i<pos.size();++i)
{
int index=0;
//int bound=0;
float x,y,z,a;
float x,y,z;
sscanf(node,"%d %f %f %f",&index,&x,&y,&z);
// sn>>index;
@@ -977,7 +977,7 @@ if(ele&&ele[0])
for(int i=0;i<ntetra;++i)
{
int index=0;
int ni[4],a;
int ni[4];
//se>>index;
//se>>ni[0];se>>ni[1];se>>ni[2];se>>ni[3];

View File

@@ -19,6 +19,7 @@ subject to the following restrictions:
#include "btSoftBody.h"
#include "LinearMath/btQuickprof.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
@@ -654,14 +655,14 @@ struct btSoftColliders
{
btScalar erp;
btScalar idt;
btScalar margin;
btScalar m_margin;
btScalar friction;
btScalar threshold;
ClusterBase()
{
erp =(btScalar)1;
idt =0;
margin =0;
m_margin =0;
friction =0;
threshold =(btScalar)0;
}
@@ -669,16 +670,21 @@ struct btSoftColliders
btSoftBody::Body ba,btSoftBody::Body bb,
btSoftBody::CJoint& joint)
{
if(res.distance<margin)
if(res.distance<m_margin)
{
btVector3 norm = res.normal;
norm.normalize();//is it necessary?
const btVector3 ra=res.witnesses[0]-ba.xform().getOrigin();
const btVector3 rb=res.witnesses[1]-bb.xform().getOrigin();
const btVector3 va=ba.velocity(ra);
const btVector3 vb=bb.velocity(rb);
const btVector3 vrel=va-vb;
const btScalar rvac=btDot(vrel,res.normal);
const btScalar depth=res.distance-margin;
const btVector3 iv=res.normal*rvac;
const btScalar rvac=btDot(vrel,norm);
btScalar depth=res.distance-m_margin;
// printf("depth=%f\n",depth);
const btVector3 iv=norm*rvac;
const btVector3 fv=vrel-iv;
joint.m_bodies[0] = ba;
joint.m_bodies[1] = bb;
@@ -691,12 +697,16 @@ struct btSoftColliders
joint.m_life = 0;
joint.m_maxlife = 0;
joint.m_split = 1;
joint.m_drift = depth*res.normal;
joint.m_normal = res.normal;
joint.m_drift = depth*norm;
joint.m_normal = norm;
// printf("normal=%f,%f,%f\n",res.normal.getX(),res.normal.getY(),res.normal.getZ());
joint.m_delete = false;
joint.m_friction = fv.length2()<(-rvac*friction)?1:friction;
joint.m_massmatrix = ImpulseMatrix( ba.invMass(),ba.invWorldInertia(),joint.m_rpos[0],
bb.invMass(),bb.invWorldInertia(),joint.m_rpos[1]);
return(true);
}
return(false);
@@ -714,6 +724,7 @@ struct btSoftColliders
{
btSoftBody::Cluster* cluster=(btSoftBody::Cluster*)leaf->data;
btSoftClusterCollisionShape cshape(cluster);
const btConvexShape* rshape=(const btConvexShape*)m_colObj->getCollisionShape();
btGjkEpaSolver2::sResults res;
if(btGjkEpaSolver2::SignedDistance( &cshape,btTransform::getIdentity(),
@@ -743,7 +754,7 @@ struct btSoftColliders
psb = ps;
m_colObj = colOb;
idt = ps->m_sst.isdt;
margin = m_colObj->getCollisionShape()->getMargin();
m_margin = m_colObj->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin();
///Bullet rigid body uses multiply instead of minimum to determine combined friction. Some customization would be useful.
friction = btMin(psb->m_cfg.kDF,m_colObj->getFriction());
btVector3 mins;
@@ -752,7 +763,7 @@ struct btSoftColliders
ATTRIBUTE_ALIGNED16(btDbvtVolume) volume;
colOb->getCollisionShape()->getAabb(colOb->getInterpolationWorldTransform(),mins,maxs);
volume=btDbvtVolume::FromMM(mins,maxs);
volume.Expand(btVector3(1,1,1)*margin);
volume.Expand(btVector3(1,1,1)*m_margin);
ps->m_cdbvt.collideTV(ps->m_cdbvt.m_root,volume,*this);
}
};
@@ -803,7 +814,8 @@ struct btSoftColliders
void Process(btSoftBody* psa,btSoftBody* psb)
{
idt = psa->m_sst.isdt;
margin = (psa->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin())/2;
//m_margin = (psa->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin())/2;
m_margin = (psa->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin());
friction = btMin(psa->m_cfg.kDF,psb->m_cfg.kDF);
bodies[0] = psa;
bodies[1] = psb;