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

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <blender@erwincoumans.com>2011-03-12 23:34:17 +0300
committerErwin Coumans <blender@erwincoumans.com>2011-03-12 23:34:17 +0300
commit5e374328a87c1b418f8454d5ef38470484804961 (patch)
tree1d6de85165175c5192f74dbd423e1d5cb48f8ff6 /extern/bullet2/src/BulletSoftBody
parent8c526e79e31d40d56a6fecce9343c74bd9fe62d8 (diff)
update Bullet physics sdk to latest trunk/version 2.78
add PhysicsConstraints.exportBulletFile(char* fileName) python command I'll be checking the bf-committers mailing list, in case this commit broke stuff scons needs to be updated, I'll do that in a second.
Diffstat (limited to 'extern/bullet2/src/BulletSoftBody')
-rw-r--r--extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.cpp151
-rw-r--r--extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.h63
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBody.cpp1027
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBody.h166
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp9
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodyData.h217
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.cpp355
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.h26
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodyInternals.h88
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h165
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftBodySolvers.h154
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp4
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp168
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.h20
-rw-r--r--extern/bullet2/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp3
15 files changed, 2249 insertions, 367 deletions
diff --git a/extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.cpp b/extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.cpp
new file mode 100644
index 00000000000..c876ebf1fd6
--- /dev/null
+++ b/extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.cpp
@@ -0,0 +1,151 @@
+/*
+Bullet Continuous Collision Detection and Physics Library
+Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
+
+This software is provided 'as-is', without any express or implied warranty.
+In no event will the authors be held liable for any damages arising from the use of this software.
+Permission is granted to anyone to use this software for any purpose,
+including commercial applications, and to alter it and redistribute it freely,
+subject to the following restrictions:
+
+1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
+2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
+3. This notice may not be removed or altered from any source distribution.
+*/
+
+#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
+#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
+#include "BulletCollision/CollisionShapes/btCollisionShape.h"
+
+#include "btDefaultSoftBodySolver.h"
+#include "BulletCollision/CollisionShapes/btCapsuleShape.h"
+#include "BulletSoftBody/btSoftBody.h"
+
+
+btDefaultSoftBodySolver::btDefaultSoftBodySolver()
+{
+ // Initial we will clearly need to update solver constants
+ // For now this is global for the cloths linked with this solver - we should probably make this body specific
+ // for performance in future once we understand more clearly when constants need to be updated
+ m_updateSolverConstants = true;
+}
+
+btDefaultSoftBodySolver::~btDefaultSoftBodySolver()
+{
+}
+
+// In this case the data is already in the soft bodies so there is no need for us to do anything
+void btDefaultSoftBodySolver::copyBackToSoftBodies()
+{
+
+}
+
+void btDefaultSoftBodySolver::optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate)
+{
+ m_softBodySet.copyFromArray( softBodies );
+}
+
+void btDefaultSoftBodySolver::updateSoftBodies( )
+{
+ for ( int i=0; i < m_softBodySet.size(); i++)
+ {
+ btSoftBody* psb=(btSoftBody*)m_softBodySet[i];
+ if (psb->isActive())
+ {
+ psb->integrateMotion();
+ }
+ }
+} // updateSoftBodies
+
+bool btDefaultSoftBodySolver::checkInitialized()
+{
+ return true;
+}
+
+void btDefaultSoftBodySolver::solveConstraints( float solverdt )
+{
+ // Solve constraints for non-solver softbodies
+ for(int i=0; i < m_softBodySet.size(); ++i)
+ {
+ btSoftBody* psb = static_cast<btSoftBody*>(m_softBodySet[i]);
+ if (psb->isActive())
+ {
+ psb->solveConstraints();
+ }
+ }
+} // btDefaultSoftBodySolver::solveConstraints
+
+
+void btDefaultSoftBodySolver::copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer )
+{
+ // Currently only support CPU output buffers
+ // TODO: check for DX11 buffers. Take all offsets into the same DX11 buffer
+ // and use them together on a single kernel call if possible by setting up a
+ // per-cloth target buffer array for the copy kernel.
+
+ if( vertexBuffer->getBufferType() == btVertexBufferDescriptor::CPU_BUFFER )
+ {
+ const btAlignedObjectArray<btSoftBody::Node> &clothVertices( softBody->m_nodes );
+ int numVertices = clothVertices.size();
+
+ const btCPUVertexBufferDescriptor *cpuVertexBuffer = static_cast< btCPUVertexBufferDescriptor* >(vertexBuffer);
+ float *basePointer = cpuVertexBuffer->getBasePointer();
+
+ if( vertexBuffer->hasVertexPositions() )
+ {
+ const int vertexOffset = cpuVertexBuffer->getVertexOffset();
+ const int vertexStride = cpuVertexBuffer->getVertexStride();
+ float *vertexPointer = basePointer + vertexOffset;
+
+ for( int vertexIndex = 0; vertexIndex < numVertices; ++vertexIndex )
+ {
+ btVector3 position = clothVertices[vertexIndex].m_x;
+ *(vertexPointer + 0) = position.getX();
+ *(vertexPointer + 1) = position.getY();
+ *(vertexPointer + 2) = position.getZ();
+ vertexPointer += vertexStride;
+ }
+ }
+ if( vertexBuffer->hasNormals() )
+ {
+ const int normalOffset = cpuVertexBuffer->getNormalOffset();
+ const int normalStride = cpuVertexBuffer->getNormalStride();
+ float *normalPointer = basePointer + normalOffset;
+
+ for( int vertexIndex = 0; vertexIndex < numVertices; ++vertexIndex )
+ {
+ btVector3 normal = clothVertices[vertexIndex].m_n;
+ *(normalPointer + 0) = normal.getX();
+ *(normalPointer + 1) = normal.getY();
+ *(normalPointer + 2) = normal.getZ();
+ normalPointer += normalStride;
+ }
+ }
+ }
+} // btDefaultSoftBodySolver::copySoftBodyToVertexBuffer
+
+void btDefaultSoftBodySolver::processCollision( btSoftBody* softBody, btSoftBody* otherSoftBody)
+{
+ softBody->defaultCollisionHandler( otherSoftBody);
+}
+
+// For the default solver just leave the soft body to do its collision processing
+void btDefaultSoftBodySolver::processCollision( btSoftBody *softBody, btCollisionObject* collisionObject )
+{
+ softBody->defaultCollisionHandler( collisionObject );
+} // btDefaultSoftBodySolver::processCollision
+
+
+void btDefaultSoftBodySolver::predictMotion( float timeStep )
+{
+ for ( int i=0; i < m_softBodySet.size(); ++i)
+ {
+ btSoftBody* psb = m_softBodySet[i];
+
+ if (psb->isActive())
+ {
+ psb->predictMotion(timeStep);
+ }
+ }
+}
+
diff --git a/extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.h b/extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.h
new file mode 100644
index 00000000000..8e7db3daf98
--- /dev/null
+++ b/extern/bullet2/src/BulletSoftBody/btDefaultSoftBodySolver.h
@@ -0,0 +1,63 @@
+/*
+Bullet Continuous Collision Detection and Physics Library
+Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
+
+This software is provided 'as-is', without any express or implied warranty.
+In no event will the authors be held liable for any damages arising from the use of this software.
+Permission is granted to anyone to use this software for any purpose,
+including commercial applications, and to alter it and redistribute it freely,
+subject to the following restrictions:
+
+1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
+2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
+3. This notice may not be removed or altered from any source distribution.
+*/
+
+#ifndef BT_SOFT_BODY_DEFAULT_SOLVER_H
+#define BT_SOFT_BODY_DEFAULT_SOLVER_H
+
+
+#include "BulletSoftBody/btSoftBodySolvers.h"
+#include "btSoftBodySolverVertexBuffer.h"
+
+
+class btDefaultSoftBodySolver : public btSoftBodySolver
+{
+protected:
+ /** Variable to define whether we need to update solver constants on the next iteration */
+ bool m_updateSolverConstants;
+
+ btAlignedObjectArray< btSoftBody * > m_softBodySet;
+
+
+public:
+ btDefaultSoftBodySolver();
+
+ virtual ~btDefaultSoftBodySolver();
+
+ virtual SolverTypes getSolverType() const
+ {
+ return DEFAULT_SOLVER;
+ }
+
+ virtual bool checkInitialized();
+
+ virtual void updateSoftBodies( );
+
+ virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies,bool forceUpdate=false );
+
+ virtual void copyBackToSoftBodies();
+
+ virtual void solveConstraints( float solverdt );
+
+ virtual void predictMotion( float solverdt );
+
+ virtual void copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer );
+
+ virtual void processCollision( btSoftBody *, btCollisionObject* );
+
+ virtual void processCollision( btSoftBody*, btSoftBody* );
+
+};
+
+#endif // #ifndef BT_ACCELERATED_SOFT_BODY_CPU_SOLVER_H
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBody.cpp b/extern/bullet2/src/BulletSoftBody/btSoftBody.cpp
index ee810c54082..a90acb99f04 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftBody.cpp
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBody.cpp
@@ -15,12 +15,51 @@ subject to the following restrictions:
///btSoftBody implementation by Nathanael Presson
#include "btSoftBodyInternals.h"
+#include "BulletSoftBody/btSoftBodySolvers.h"
+#include "btSoftBodyData.h"
+#include "LinearMath/btSerializer.h"
//
btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo,int node_count, const btVector3* x, const btScalar* m)
-:m_worldInfo(worldInfo)
+:m_worldInfo(worldInfo),m_softBodySolver(0)
{
/* Init */
+ initDefaults();
+
+ /* Default material */
+ Material* pm=appendMaterial();
+ pm->m_kLST = 1;
+ pm->m_kAST = 1;
+ pm->m_kVST = 1;
+ pm->m_flags = fMaterial::Default;
+
+ /* Nodes */
+ const btScalar margin=getCollisionShape()->getMargin();
+ m_nodes.resize(node_count);
+ for(int i=0,ni=node_count;i<ni;++i)
+ {
+ Node& n=m_nodes[i];
+ ZeroInitialize(n);
+ n.m_x = x?*x++:btVector3(0,0,0);
+ n.m_q = n.m_x;
+ n.m_im = m?*m++:1;
+ n.m_im = n.m_im>0?1/n.m_im:0;
+ n.m_leaf = m_ndbvt.insert(btDbvtVolume::FromCR(n.m_x,margin),&n);
+ n.m_material= pm;
+ }
+ updateBounds();
+
+}
+
+btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo)
+:m_worldInfo(worldInfo)
+{
+ initDefaults();
+}
+
+
+void btSoftBody::initDefaults()
+{
m_internalType = CO_SOFT_BODY;
m_cfg.aeromodel = eAeroModel::V_Point;
m_cfg.kVCF = 1;
@@ -61,33 +100,16 @@ btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo,int node_count, const btV
m_bounds[1] = btVector3(0,0,0);
m_worldTransform.setIdentity();
setSolver(eSolverPresets::Positions);
- /* Default material */
- Material* pm=appendMaterial();
- pm->m_kLST = 1;
- pm->m_kAST = 1;
- pm->m_kVST = 1;
- pm->m_flags = fMaterial::Default;
+
/* Collision shape */
///for now, create a collision shape internally
m_collisionShape = new btSoftBodyCollisionShape(this);
m_collisionShape->setMargin(0.25);
- /* Nodes */
- const btScalar margin=getCollisionShape()->getMargin();
- m_nodes.resize(node_count);
- for(int i=0,ni=node_count;i<ni;++i)
- {
- Node& n=m_nodes[i];
- ZeroInitialize(n);
- n.m_x = x?*x++:btVector3(0,0,0);
- n.m_q = n.m_x;
- n.m_im = m?*m++:1;
- n.m_im = n.m_im>0?1/n.m_im:0;
- n.m_leaf = m_ndbvt.insert(btDbvtVolume::FromCR(n.m_x,margin),&n);
- n.m_material= pm;
- }
- updateBounds();
-
+
m_initialWorldTransform.setIdentity();
+
+ m_windVelocity = btVector3(0,0,0);
+
}
//
@@ -306,8 +328,44 @@ void btSoftBody::appendFace(int node0,int node1,int node2,Material* mat)
}
//
+void btSoftBody::appendTetra(int model,Material* mat)
+{
+Tetra t;
+if(model>=0)
+ t=m_tetras[model];
+ else
+ { ZeroInitialize(t);t.m_material=mat?mat:m_materials[0]; }
+m_tetras.push_back(t);
+}
+
+//
+void btSoftBody::appendTetra(int node0,
+ int node1,
+ int node2,
+ int node3,
+ Material* mat)
+{
+ appendTetra(-1,mat);
+ Tetra& t=m_tetras[m_tetras.size()-1];
+ t.m_n[0] = &m_nodes[node0];
+ t.m_n[1] = &m_nodes[node1];
+ t.m_n[2] = &m_nodes[node2];
+ t.m_n[3] = &m_nodes[node3];
+ t.m_rv = VolumeOf(t.m_n[0]->m_x,t.m_n[1]->m_x,t.m_n[2]->m_x,t.m_n[3]->m_x);
+ m_bUpdateRtCst=true;
+}
+
+//
+
void btSoftBody::appendAnchor(int node,btRigidBody* body, bool disableCollisionBetweenLinkedBodies)
{
+ btVector3 local = body->getWorldTransform().inverse()*m_nodes[node].m_x;
+ appendAnchor(node,body,local,disableCollisionBetweenLinkedBodies);
+}
+
+//
+void btSoftBody::appendAnchor(int node,btRigidBody* body, const btVector3& localPivot,bool disableCollisionBetweenLinkedBodies)
+{
if (disableCollisionBetweenLinkedBodies)
{
if (m_collisionDisabledObjects.findLinearSearch(body)==m_collisionDisabledObjects.size())
@@ -319,7 +377,7 @@ void btSoftBody::appendAnchor(int node,btRigidBody* body, bool disableCollisio
Anchor a;
a.m_node = &m_nodes[node];
a.m_body = body;
- a.m_local = body->getInterpolationWorldTransform().inverse()*a.m_node->m_x;
+ a.m_local = localPivot;
a.m_node->m_battach = 1;
m_anchors.push_back(a);
}
@@ -491,6 +549,51 @@ void btSoftBody::setTotalDensity(btScalar density)
}
//
+void btSoftBody::setVolumeMass(btScalar mass)
+{
+btAlignedObjectArray<btScalar> ranks;
+ranks.resize(m_nodes.size(),0);
+int i;
+
+for(i=0;i<m_nodes.size();++i)
+ {
+ m_nodes[i].m_im=0;
+ }
+for(i=0;i<m_tetras.size();++i)
+ {
+ const Tetra& t=m_tetras[i];
+ for(int j=0;j<4;++j)
+ {
+ t.m_n[j]->m_im+=btFabs(t.m_rv);
+ ranks[int(t.m_n[j]-&m_nodes[0])]+=1;
+ }
+ }
+for( i=0;i<m_nodes.size();++i)
+ {
+ if(m_nodes[i].m_im>0)
+ {
+ m_nodes[i].m_im=ranks[i]/m_nodes[i].m_im;
+ }
+ }
+setTotalMass(mass,false);
+}
+
+//
+void btSoftBody::setVolumeDensity(btScalar density)
+{
+btScalar volume=0;
+for(int i=0;i<m_tetras.size();++i)
+ {
+ const Tetra& t=m_tetras[i];
+ for(int j=0;j<4;++j)
+ {
+ volume+=btFabs(t.m_rv);
+ }
+ }
+setVolumeMass(volume*density/6);
+}
+
+//
void btSoftBody::transform(const btTransform& trs)
{
const btScalar margin=getCollisionShape()->getMargin();
@@ -533,6 +636,7 @@ void btSoftBody::rotate( const btQuaternion& rot)
//
void btSoftBody::scale(const btVector3& scl)
{
+
const btScalar margin=getCollisionShape()->getMargin();
ATTRIBUTE_ALIGNED16(btDbvtVolume) vol;
@@ -611,7 +715,7 @@ btScalar btSoftBody::getVolume() const
for(i=0,ni=m_faces.size();i<ni;++i)
{
const Face& f=m_faces[i];
- vol+=dot(f.m_n[0]->m_x-org,cross(f.m_n[1]->m_x-org,f.m_n[2]->m_x-org));
+ vol+=btDot(f.m_n[0]->m_x-org,btCross(f.m_n[1]->m_x-org,f.m_n[2]->m_x-org));
}
vol/=(btScalar)6;
}
@@ -644,14 +748,14 @@ btVector3 btSoftBody::clusterCom(int cluster) const
//
btVector3 btSoftBody::clusterVelocity(const Cluster* cluster,const btVector3& rpos)
{
- return(cluster->m_lv+cross(cluster->m_av,rpos));
+ return(cluster->m_lv+btCross(cluster->m_av,rpos));
}
//
void btSoftBody::clusterVImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse)
{
const btVector3 li=cluster->m_imass*impulse;
- const btVector3 ai=cluster->m_invwi*cross(rpos,impulse);
+ const btVector3 ai=cluster->m_invwi*btCross(rpos,impulse);
cluster->m_vimpulses[0]+=li;cluster->m_lv+=li;
cluster->m_vimpulses[1]+=ai;cluster->m_av+=ai;
cluster->m_nvimpulses++;
@@ -661,7 +765,7 @@ void btSoftBody::clusterVImpulse(Cluster* cluster,const btVector3& rpos,const
void btSoftBody::clusterDImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse)
{
const btVector3 li=cluster->m_imass*impulse;
- const btVector3 ai=cluster->m_invwi*cross(rpos,impulse);
+ const btVector3 ai=cluster->m_invwi*btCross(rpos,impulse);
cluster->m_dimpulses[0]+=li;
cluster->m_dimpulses[1]+=ai;
cluster->m_ndimpulses++;
@@ -704,6 +808,13 @@ void btSoftBody::clusterDCImpulse(Cluster* cluster,const btVector3& impulse)
cluster->m_ndimpulses++;
}
+struct NodeLinks
+{
+ btAlignedObjectArray<int> m_links;
+};
+
+
+
//
int btSoftBody::generateBendingConstraints(int distance,Material* mat)
{
@@ -715,14 +826,21 @@ int btSoftBody::generateBendingConstraints(int distance,Material* mat)
const int n=m_nodes.size();
const unsigned inf=(~(unsigned)0)>>1;
unsigned* adj=new unsigned[n*n];
+
+
#define IDX(_x_,_y_) ((_y_)*n+(_x_))
for(j=0;j<n;++j)
{
for(i=0;i<n;++i)
{
- if(i!=j) adj[IDX(i,j)]=adj[IDX(j,i)]=inf;
+ if(i!=j)
+ {
+ adj[IDX(i,j)]=adj[IDX(j,i)]=inf;
+ }
else
+ {
adj[IDX(i,j)]=adj[IDX(j,i)]=0;
+ }
}
}
for( i=0;i<m_links.size();++i)
@@ -732,20 +850,71 @@ int btSoftBody::generateBendingConstraints(int distance,Material* mat)
adj[IDX(ia,ib)]=1;
adj[IDX(ib,ia)]=1;
}
- for(int k=0;k<n;++k)
+
+
+ //special optimized case for distance == 2
+ if (distance == 2)
+ {
+
+ btAlignedObjectArray<NodeLinks> nodeLinks;
+
+
+ /* Build node links */
+ nodeLinks.resize(m_nodes.size());
+
+ for( i=0;i<m_links.size();++i)
+ {
+ const int ia=(int)(m_links[i].m_n[0]-&m_nodes[0]);
+ const int ib=(int)(m_links[i].m_n[1]-&m_nodes[0]);
+ if (nodeLinks[ia].m_links.findLinearSearch(ib)==nodeLinks[ia].m_links.size())
+ nodeLinks[ia].m_links.push_back(ib);
+
+ if (nodeLinks[ib].m_links.findLinearSearch(ia)==nodeLinks[ib].m_links.size())
+ nodeLinks[ib].m_links.push_back(ia);
+ }
+ for (int ii=0;ii<nodeLinks.size();ii++)
+ {
+ int i=ii;
+
+ for (int jj=0;jj<nodeLinks[ii].m_links.size();jj++)
+ {
+ int k = nodeLinks[ii].m_links[jj];
+ for (int kk=0;kk<nodeLinks[k].m_links.size();kk++)
+ {
+ int j = nodeLinks[k].m_links[kk];
+ if (i!=j)
+ {
+ const unsigned sum=adj[IDX(i,k)]+adj[IDX(k,j)];
+ btAssert(sum==2);
+ if(adj[IDX(i,j)]>sum)
+ {
+ adj[IDX(i,j)]=adj[IDX(j,i)]=sum;
+ }
+ }
+
+ }
+ }
+ }
+ } else
{
- for(j=0;j<n;++j)
+ ///generic Floyd's algorithm
+ for(int k=0;k<n;++k)
{
- for(i=j+1;i<n;++i)
+ for(j=0;j<n;++j)
{
- const unsigned sum=adj[IDX(i,k)]+adj[IDX(k,j)];
- if(adj[IDX(i,j)]>sum)
+ for(i=j+1;i<n;++i)
{
- adj[IDX(i,j)]=adj[IDX(j,i)]=sum;
+ const unsigned sum=adj[IDX(i,k)]+adj[IDX(k,j)];
+ if(adj[IDX(i,j)]>sum)
+ {
+ adj[IDX(i,j)]=adj[IDX(j,i)]=sum;
+ }
}
}
}
}
+
+
/* Build links */
int nlinks=0;
for(j=0;j<n;++j)
@@ -917,10 +1086,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());
{
@@ -948,10 +1157,9 @@ int btSoftBody::generateClusters(int k,int maxiterations)
}
}
}
-
- return(m_clusters.size());
}
- return(0);
+
+ return(m_clusters.size());
}
//
@@ -1311,6 +1519,7 @@ void btSoftBody::setSolver(eSolverPresets::_ preset)
//
void btSoftBody::predictMotion(btScalar dt)
{
+
int i,ni;
/* Update */
@@ -1402,6 +1611,7 @@ void btSoftBody::predictMotion(btScalar dt)
//
void btSoftBody::solveConstraints()
{
+
/* Apply clusters */
applyClusters(false);
/* Prepare links */
@@ -1585,19 +1795,19 @@ btScalar btSoftBody::RayFromToCaster::rayFromToTriangle( const btVector3& rayF
static const btScalar ceps=-SIMD_EPSILON*10;
static const btScalar teps=SIMD_EPSILON*10;
- const btVector3 n=cross(b-a,c-a);
- const btScalar d=dot(a,n);
- const btScalar den=dot(rayNormalizedDirection,n);
+ const btVector3 n=btCross(b-a,c-a);
+ const btScalar d=btDot(a,n);
+ const btScalar den=btDot(rayNormalizedDirection,n);
if(!btFuzzyZero(den))
{
- const btScalar num=dot(rayFrom,n)-d;
+ const btScalar num=btDot(rayFrom,n)-d;
const btScalar t=-num/den;
if((t>teps)&&(t<maxt))
{
const btVector3 hit=rayFrom+rayNormalizedDirection*t;
- if( (dot(n,cross(a-hit,b-hit))>ceps) &&
- (dot(n,cross(b-hit,c-hit))>ceps) &&
- (dot(n,cross(c-hit,a-hit))>ceps))
+ if( (btDot(n,btCross(a-hit,b-hit))>ceps) &&
+ (btDot(n,btCross(b-hit,c-hit))>ceps) &&
+ (btDot(n,btCross(c-hit,a-hit))>ceps))
{
return(t);
}
@@ -1771,20 +1981,21 @@ bool btSoftBody::checkContact( btCollisionObject* colObj,
btScalar margin,
btSoftBody::sCti& cti) const
{
- btVector3 nrm;
- btCollisionShape* shp=colObj->getCollisionShape();
- btRigidBody* tmpRigid = btRigidBody::upcast(colObj);
- const btTransform& wtr=tmpRigid? tmpRigid->getInterpolationWorldTransform() : colObj->getWorldTransform();
- btScalar dst=m_worldInfo->m_sparsesdf.Evaluate( wtr.invXform(x),
- shp,
- nrm,
- margin);
+ btVector3 nrm;
+ btCollisionShape *shp = colObj->getCollisionShape();
+ btRigidBody *tmpRigid = btRigidBody::upcast(colObj);
+ const btTransform &wtr = tmpRigid ? tmpRigid->getWorldTransform() : colObj->getWorldTransform();
+ btScalar dst =
+ m_worldInfo->m_sparsesdf.Evaluate(
+ wtr.invXform(x),
+ shp,
+ nrm,
+ margin);
if(dst<0)
{
- cti.m_colObj = colObj;
- cti.m_normal = wtr.getBasis()*nrm;
- cti.m_offset = -dot( cti.m_normal,
- x-cti.m_normal*dst);
+ cti.m_colObj = colObj;
+ cti.m_normal = wtr.getBasis()*nrm;
+ cti.m_offset = -btDot( cti.m_normal, x - cti.m_normal * dst );
return(true);
}
return(false);
@@ -1793,6 +2004,7 @@ bool btSoftBody::checkContact( btCollisionObject* colObj,
//
void btSoftBody::updateNormals()
{
+
const btVector3 zv(0,0,0);
int i,ni;
@@ -1803,7 +2015,7 @@ void btSoftBody::updateNormals()
for(i=0,ni=m_faces.size();i<ni;++i)
{
btSoftBody::Face& f=m_faces[i];
- const btVector3 n=cross(f.m_n[1]->m_x-f.m_n[0]->m_x,
+ const btVector3 n=btCross(f.m_n[1]->m_x-f.m_n[0]->m_x,
f.m_n[2]->m_x-f.m_n[0]->m_x);
f.m_normal=n.normalized();
f.m_n[0]->m_n+=n;
@@ -1821,29 +2033,42 @@ void btSoftBody::updateNormals()
//
void btSoftBody::updateBounds()
{
- if(m_ndbvt.m_root)
- {
- const btVector3& mins=m_ndbvt.m_root->volume.Mins();
- const btVector3& maxs=m_ndbvt.m_root->volume.Maxs();
- const btScalar csm=getCollisionShape()->getMargin();
- const btVector3 mrg=btVector3( csm,
- csm,
- csm)*1; // ??? to investigate...
- m_bounds[0]=mins-mrg;
- m_bounds[1]=maxs+mrg;
- if(0!=getBroadphaseHandle())
- {
- m_worldInfo->m_broadphase->setAabb( getBroadphaseHandle(),
- m_bounds[0],
- m_bounds[1],
- m_worldInfo->m_dispatcher);
+ /*if( m_acceleratedSoftBody )
+ {
+ // If we have an accelerated softbody we need to obtain the bounds correctly
+ // For now (slightly hackily) just have a very large AABB
+ // TODO: Write get bounds kernel
+ // If that is updating in place, atomic collisions might be low (when the cloth isn't perfectly aligned to an axis) and we could
+ // probably do a test and exchange reasonably efficiently.
+
+ m_bounds[0] = btVector3(-1000, -1000, -1000);
+ m_bounds[1] = btVector3(1000, 1000, 1000);
+
+ } else {*/
+ if(m_ndbvt.m_root)
+ {
+ const btVector3& mins=m_ndbvt.m_root->volume.Mins();
+ const btVector3& maxs=m_ndbvt.m_root->volume.Maxs();
+ const btScalar csm=getCollisionShape()->getMargin();
+ const btVector3 mrg=btVector3( csm,
+ csm,
+ csm)*1; // ??? to investigate...
+ m_bounds[0]=mins-mrg;
+ m_bounds[1]=maxs+mrg;
+ if(0!=getBroadphaseHandle())
+ {
+ m_worldInfo->m_broadphase->setAabb( getBroadphaseHandle(),
+ m_bounds[0],
+ m_bounds[1],
+ m_worldInfo->m_dispatcher);
+ }
}
- }
- else
- {
- m_bounds[0]=
- m_bounds[1]=btVector3(0,0,0);
- }
+ else
+ {
+ m_bounds[0]=
+ m_bounds[1]=btVector3(0,0,0);
+ }
+ //}
}
@@ -1941,10 +2166,17 @@ 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;
+ if (c.m_nodes[j]->m_im==0)
+ {
+ c.m_containsAnchor = true;
+ c.m_masses[j] = BT_LARGE_FLOAT;
+ } else
+ {
+ c.m_masses[j] = btScalar(1.)/c.m_nodes[j]->m_im;
+ }
c.m_imass += c.m_masses[j];
}
- c.m_imass = 1/c.m_imass;
+ c.m_imass = btScalar(1.)/c.m_imass;
c.m_com = btSoftBody::clusterCom(&c);
c.m_lv = btVector3(0,0,0);
c.m_av = btVector3(0,0,0);
@@ -1971,7 +2203,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();
+
+ ii = ii.inverse();
+
/* Frame */
c.m_framexform.setIdentity();
c.m_framexform.setOrigin(c.m_com);
@@ -1996,7 +2230,7 @@ void btSoftBody::updateClusters()
{
btSoftBody::Cluster& c=*m_clusters[i];
const int n=c.m_nodes.size();
- const btScalar invn=1/(btScalar)n;
+ //const btScalar invn=1/(btScalar)n;
if(n)
{
/* Frame */
@@ -2058,7 +2292,7 @@ void btSoftBody::updateClusters()
{
const btVector3 v=c.m_nodes[i]->m_v*c.m_masses[i];
c.m_lv += v;
- c.m_av += cross(c.m_nodes[i]->m_x-c.m_com,v);
+ c.m_av += btCross(c.m_nodes[i]->m_x-c.m_com,v);
}
}
c.m_lv=c.m_imass*c.m_lv*(1-c.m_ldamping);
@@ -2141,8 +2375,8 @@ void btSoftBody::solveClusters(btScalar sor)
void btSoftBody::applyClusters(bool drift)
{
BT_PROFILE("ApplyClusters");
- const btScalar f0=m_sst.sdt;
- const btScalar f1=f0/2;
+// const btScalar f0=m_sst.sdt;
+ //const btScalar f1=f0/2;
btAlignedObjectArray<btVector3> deltas;
btAlignedObjectArray<btScalar> weights;
deltas.resize(m_nodes.size(),btVector3(0,0,0));
@@ -2174,14 +2408,17 @@ void btSoftBody::applyClusters(bool drift)
const int idx=int(c.m_nodes[j]-&m_nodes[0]);
const btVector3& x=c.m_nodes[j]->m_x;
const btScalar q=c.m_masses[j];
- deltas[idx] += (v+cross(w,x-c.m_com))*q;
+ deltas[idx] += (v+btCross(w,x-c.m_com))*q;
weights[idx] += q;
}
}
}
for(i=0;i<deltas.size();++i)
{
- if(weights[i]>0) m_nodes[i].m_x+=deltas[i]/weights[i];
+ if(weights[i]>0)
+ {
+ m_nodes[i].m_x+=deltas[i]/weights[i];
+ }
}
}
@@ -2200,7 +2437,7 @@ void btSoftBody::dampClusters()
Node& n=*c.m_nodes[j];
if(n.m_im>0)
{
- const btVector3 vx=c.m_lv+cross(c.m_av,c.m_nodes[j]->m_q-c.m_com);
+ const btVector3 vx=c.m_lv+btCross(c.m_av,c.m_nodes[j]->m_q-c.m_com);
if(vx.length2()<=n.m_v.length2())
{
n.m_v += c.m_ndamping*(vx-n.m_v);
@@ -2269,8 +2506,8 @@ void btSoftBody::AJoint::Prepare(btScalar dt,int iterations)
Joint::Prepare(dt,iterations);
m_axis[0] = m_bodies[0].xform().getBasis()*m_refs[0];
m_axis[1] = m_bodies[1].xform().getBasis()*m_refs[1];
- m_drift = NormalizeAny(cross(m_axis[1],m_axis[0]));
- m_drift *= btMin(maxdrift,btAcos(Clamp<btScalar>(dot(m_axis[0],m_axis[1]),-1,+1)));
+ m_drift = NormalizeAny(btCross(m_axis[1],m_axis[0]));
+ m_drift *= btMin(maxdrift,btAcos(Clamp<btScalar>(btDot(m_axis[0],m_axis[1]),-1,+1)));
m_drift *= m_erp/dt;
m_massmatrix= AngularImpulseMatrix(m_bodies[0].invWorldInertia(),m_bodies[1].invWorldInertia());
if(m_split>0)
@@ -2287,7 +2524,7 @@ void btSoftBody::AJoint::Solve(btScalar dt,btScalar sor)
const btVector3 va=m_bodies[0].angularVelocity();
const btVector3 vb=m_bodies[1].angularVelocity();
const btVector3 vr=va-vb;
- const btScalar sp=dot(vr,m_axis[0]);
+ const btScalar sp=btDot(vr,m_axis[0]);
const btVector3 vc=vr-m_axis[0]*m_icontrol->Speed(this,sp);
btSoftBody::Impulse impulse;
impulse.m_asVelocity = 1;
@@ -2334,7 +2571,7 @@ void btSoftBody::CJoint::Solve(btScalar dt,btScalar sor)
const btVector3 va=m_bodies[0].velocity(m_rpos[0]);
const btVector3 vb=m_bodies[1].velocity(m_rpos[1]);
const btVector3 vrel=va-vb;
- const btScalar rvac=dot(vrel,m_normal);
+ const btScalar rvac=btDot(vrel,m_normal);
btSoftBody::Impulse impulse;
impulse.m_asVelocity = 1;
impulse.m_velocity = m_drift;
@@ -2345,8 +2582,29 @@ void btSoftBody::CJoint::Solve(btScalar dt,btScalar sor)
impulse.m_velocity += iv+fv*m_friction;
}
impulse.m_velocity=m_massmatrix*impulse.m_velocity*sor;
- m_bodies[0].applyImpulse(-impulse,m_rpos[0]);
- m_bodies[1].applyImpulse( impulse,m_rpos[1]);
+
+ 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]);
+ }
}
//
@@ -2364,27 +2622,27 @@ void btSoftBody::applyForces()
{
BT_PROFILE("SoftBody applyForces");
- const btScalar dt=m_sst.sdt;
- const btScalar kLF=m_cfg.kLF;
- const btScalar kDG=m_cfg.kDG;
- const btScalar kPR=m_cfg.kPR;
- const btScalar kVC=m_cfg.kVC;
- const bool as_lift=kLF>0;
- const bool as_drag=kDG>0;
- const bool as_pressure=kPR!=0;
- const bool as_volume=kVC>0;
- const bool as_aero= as_lift ||
- as_drag ;
- const bool as_vaero= as_aero &&
- (m_cfg.aeromodel<btSoftBody::eAeroModel::F_TwoSided);
- const bool as_faero= as_aero &&
- (m_cfg.aeromodel>=btSoftBody::eAeroModel::F_TwoSided);
- const bool use_medium= as_aero;
- const bool use_volume= as_pressure ||
+ const btScalar dt = m_sst.sdt;
+ const btScalar kLF = m_cfg.kLF;
+ const btScalar kDG = m_cfg.kDG;
+ const btScalar kPR = m_cfg.kPR;
+ const btScalar kVC = m_cfg.kVC;
+ const bool as_lift = kLF>0;
+ const bool as_drag = kDG>0;
+ const bool as_pressure = kPR!=0;
+ const bool as_volume = kVC>0;
+ const bool as_aero = as_lift ||
+ as_drag ;
+ const bool as_vaero = as_aero &&
+ (m_cfg.aeromodel < btSoftBody::eAeroModel::F_TwoSided);
+ const bool as_faero = as_aero &&
+ (m_cfg.aeromodel >= btSoftBody::eAeroModel::F_TwoSided);
+ const bool use_medium = as_aero;
+ const bool use_volume = as_pressure ||
as_volume ;
- btScalar volume=0;
- btScalar ivolumetp=0;
- btScalar dvolumetv=0;
+ btScalar volume = 0;
+ btScalar ivolumetp = 0;
+ btScalar dvolumetv = 0;
btSoftBody::sMedium medium;
if(use_volume)
{
@@ -2402,33 +2660,41 @@ void btSoftBody::applyForces()
{
if(use_medium)
{
- EvaluateMedium(m_worldInfo,n.m_x,medium);
+ EvaluateMedium(m_worldInfo, n.m_x, medium);
+ medium.m_velocity = m_windVelocity;
+ medium.m_density = m_worldInfo->air_density;
+
/* Aerodynamics */
if(as_vaero)
{
- const btVector3 rel_v=n.m_v-medium.m_velocity;
- const btScalar rel_v2=rel_v.length2();
+ const btVector3 rel_v = n.m_v - medium.m_velocity;
+ const btScalar rel_v2 = rel_v.length2();
if(rel_v2>SIMD_EPSILON)
{
- btVector3 nrm=n.m_n;
+ btVector3 nrm = n.m_n;
/* Setup normal */
switch(m_cfg.aeromodel)
{
case btSoftBody::eAeroModel::V_Point:
- nrm=NormalizeAny(rel_v);break;
+ nrm = NormalizeAny(rel_v);
+ break;
case btSoftBody::eAeroModel::V_TwoSided:
- nrm*=(btScalar)(dot(nrm,rel_v)<0?-1:+1);break;
+ nrm *= (btScalar)( (btDot(nrm,rel_v) < 0) ? -1 : +1);
+ break;
+ default:
+ {
+ }
}
- const btScalar dvn=dot(rel_v,nrm);
+ const btScalar dvn = btDot(rel_v,nrm);
/* Compute forces */
if(dvn>0)
{
btVector3 force(0,0,0);
- const btScalar c0 = n.m_area*dvn*rel_v2/2;
- const btScalar c1 = c0*medium.m_density;
+ const btScalar c0 = n.m_area * dvn * rel_v2/2;
+ const btScalar c1 = c0 * medium.m_density;
force += nrm*(-c1*kLF);
- force += rel_v.normalized()*(-c1*kDG);
- ApplyClampedForce(n,force,dt);
+ force += rel_v.normalized() * (-c1 * kDG);
+ ApplyClampedForce(n, force, dt);
}
}
}
@@ -2463,9 +2729,12 @@ void btSoftBody::applyForces()
switch(m_cfg.aeromodel)
{
case btSoftBody::eAeroModel::F_TwoSided:
- nrm*=(btScalar)(dot(nrm,rel_v)<0?-1:+1);break;
+ nrm*=(btScalar)(btDot(nrm,rel_v)<0?-1:+1);break;
+ default:
+ {
+ }
}
- const btScalar dvn=dot(rel_v,nrm);
+ const btScalar dvn=btDot(rel_v,nrm);
/* Compute forces */
if(dvn>0)
{
@@ -2490,7 +2759,7 @@ void btSoftBody::PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti)
for(int i=0,ni=psb->m_anchors.size();i<ni;++i)
{
const Anchor& a=psb->m_anchors[i];
- const btTransform& t=a.m_body->getInterpolationWorldTransform();
+ const btTransform& t=a.m_body->getWorldTransform();
Node& n=*a.m_node;
const btVector3 wa=t*a.m_local;
const btVector3 va=a.m_body->getVelocityInLocalPoint(a.m_c1)*dt;
@@ -2503,26 +2772,27 @@ void btSoftBody::PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti)
}
//
-void btSoftBody::PSolve_RContacts(btSoftBody* psb,btScalar kst,btScalar ti)
+void btSoftBody::PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti)
{
- const btScalar dt=psb->m_sst.sdt;
- const btScalar mrg=psb->getCollisionShape()->getMargin();
+ const btScalar dt = psb->m_sst.sdt;
+ const btScalar mrg = psb->getCollisionShape()->getMargin();
for(int i=0,ni=psb->m_rcontacts.size();i<ni;++i)
{
- const RContact& c=psb->m_rcontacts[i];
- const sCti& cti=c.m_cti;
+ const RContact& c = psb->m_rcontacts[i];
+ const sCti& cti = c.m_cti;
btRigidBody* tmpRigid = btRigidBody::upcast(cti.m_colObj);
- const btVector3 va=tmpRigid ? tmpRigid->getVelocityInLocalPoint(c.m_c1)*dt : btVector3(0,0,0);
- const btVector3 vb=c.m_node->m_x-c.m_node->m_q;
- const btVector3 vr=vb-va;
- const btScalar dn=dot(vr,cti.m_normal);
+ const btVector3 va = tmpRigid ? tmpRigid->getVelocityInLocalPoint(c.m_c1)*dt : btVector3(0,0,0);
+ const btVector3 vb = c.m_node->m_x-c.m_node->m_q;
+ const btVector3 vr = vb-va;
+ const btScalar dn = btDot(vr, cti.m_normal);
if(dn<=SIMD_EPSILON)
{
- const btScalar dp=btMin(dot(c.m_node->m_x,cti.m_normal)+cti.m_offset,mrg);
- const btVector3 fv=vr-cti.m_normal*dn;
- const btVector3 impulse=c.m_c0*((vr-fv*c.m_c3+cti.m_normal*(dp*c.m_c4))*kst);
- c.m_node->m_x-=impulse*c.m_c2;
+ const btScalar dp = btMin( (btDot(c.m_node->m_x, cti.m_normal) + cti.m_offset), mrg );
+ const btVector3 fv = vr - (cti.m_normal * dn);
+ // c0 is the impulse matrix, c3 is 1 - the friction coefficient or 0, c4 is the contact hardness coefficient
+ const btVector3 impulse = c.m_c0 * ( (vr - (fv * c.m_c3) + (cti.m_normal * (dp * c.m_c4))) * kst );
+ c.m_node->m_x -= impulse * c.m_c2;
if (tmpRigid)
tmpRigid->applyImpulse(impulse,c.m_c1);
}
@@ -2548,9 +2818,10 @@ 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(dot(vr,nr)<0)
+ btScalar dot = btDot(vr,nr);
+ if(dot<0)
{
- const btScalar j=c.m_margin-(dot(nr,n.m_x)-dot(nr,p));
+ const btScalar j=c.m_margin-(btDot(nr,n.m_x)-btDot(nr,p));
corr+=c.m_normal*j;
}
corr -= ProjectOnPlane(vr,nr)*c.m_friction;
@@ -2573,10 +2844,12 @@ void btSoftBody::PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti)
Node& b=*l.m_n[1];
const btVector3 del=b.m_x-a.m_x;
const btScalar len=del.length2();
- const btScalar k=((l.m_c1-len)/(l.m_c0*(l.m_c1+len)))*kst;
- const btScalar t=k*a.m_im;
- a.m_x-=del*(k*a.m_im);
- b.m_x+=del*(k*b.m_im);
+ if (l.m_c1+len > SIMD_EPSILON)
+ {
+ const btScalar k=((l.m_c1-len)/(l.m_c0*(l.m_c1+len)))*kst;
+ a.m_x-=del*(k*a.m_im);
+ b.m_x+=del*(k*b.m_im);
+ }
}
}
}
@@ -2588,7 +2861,7 @@ void btSoftBody::VSolve_Links(btSoftBody* psb,btScalar kst)
{
Link& l=psb->m_links[i];
Node** n=l.m_n;
- const btScalar j=-dot(l.m_c3,n[0]->m_v-n[1]->m_v)*l.m_c2*kst;
+ const btScalar j=-btDot(l.m_c3,n[0]->m_v-n[1]->m_v)*l.m_c2*kst;
n[0]->m_v+= l.m_c3*(j*n[0]->m_im);
n[1]->m_v-= l.m_c3*(j*n[1]->m_im);
}
@@ -2599,10 +2872,17 @@ 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);
+ default:
+ {
+ }
}
return(0);
}
@@ -2613,6 +2893,9 @@ btSoftBody::vsolver_t btSoftBody::getSolver(eVSolver::_ solver)
switch(solver)
{
case eVSolver::Linear: return(&btSoftBody::VSolve_Links);
+ default:
+ {
+ }
}
return(0);
}
@@ -2620,13 +2903,14 @@ btSoftBody::vsolver_t btSoftBody::getSolver(eVSolver::_ solver)
//
void btSoftBody::defaultCollisionHandler(btCollisionObject* pco)
{
+
switch(m_cfg.collisions&fCollision::RVSmask)
{
case fCollision::SDF_RS:
{
btSoftColliders::CollideSDF_RS docollide;
btRigidBody* prb1=btRigidBody::upcast(pco);
- btTransform wtr=prb1 ? prb1->getInterpolationWorldTransform() : pco->getWorldTransform();
+ btTransform wtr=pco->getWorldTransform();
const btTransform ctr=pco->getWorldTransform();
const btScalar timemargin=(wtr.getOrigin()-ctr.getOrigin()).length();
@@ -2634,7 +2918,7 @@ void btSoftBody::defaultCollisionHandler(btCollisionObject* pco)
btVector3 mins;
btVector3 maxs;
ATTRIBUTE_ALIGNED16(btDbvtVolume) volume;
- pco->getCollisionShape()->getAabb( pco->getInterpolationWorldTransform(),
+ pco->getCollisionShape()->getAabb( pco->getWorldTransform(),
mins,
maxs);
volume=btDbvtVolume::FromMM(mins,maxs);
@@ -2665,8 +2949,14 @@ void btSoftBody::defaultCollisionHandler(btSoftBody* psb)
{
case fCollision::CL_SS:
{
- btSoftColliders::CollideCL_SS docollide;
- docollide.Process(this,psb);
+
+ //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:
@@ -2693,5 +2983,426 @@ void btSoftBody::defaultCollisionHandler(btSoftBody* psb)
}
}
break;
+ default:
+ {
+
+ }
+ }
+}
+
+
+
+void btSoftBody::setWindVelocity( const btVector3 &velocity )
+{
+ m_windVelocity = velocity;
+}
+
+
+const btVector3& btSoftBody::getWindVelocity()
+{
+ return m_windVelocity;
+}
+
+
+
+int btSoftBody::calculateSerializeBufferSize() const
+{
+ int sz = sizeof(btSoftBodyData);
+ return sz;
+}
+
+ ///fills the dataBuffer and returns the struct name (and 0 on failure)
+const char* btSoftBody::serialize(void* dataBuffer, class btSerializer* serializer) const
+{
+ btSoftBodyData* sbd = (btSoftBodyData*) dataBuffer;
+
+ btCollisionObject::serialize(&sbd->m_collisionObjectData, serializer);
+
+ btHashMap<btHashPtr,int> m_nodeIndexMap;
+
+ sbd->m_numMaterials = m_materials.size();
+ sbd->m_materials = sbd->m_numMaterials? (SoftBodyMaterialData**) serializer->getUniquePointer((void*)&m_materials): 0;
+
+ if (sbd->m_materials)
+ {
+ int sz = sizeof(SoftBodyMaterialData*);
+ int numElem = sbd->m_numMaterials;
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ //SoftBodyMaterialData** memPtr = chunk->m_oldPtr;
+ SoftBodyMaterialData** memPtr = (SoftBodyMaterialData**)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ btSoftBody::Material* mat = m_materials[i];
+ *memPtr = mat ? (SoftBodyMaterialData*)serializer->getUniquePointer((void*)mat) : 0;
+ if (!serializer->findPointer(mat))
+ {
+ //serialize it here
+ btChunk* chunk = serializer->allocate(sizeof(SoftBodyMaterialData),1);
+ SoftBodyMaterialData* memPtr = (SoftBodyMaterialData*)chunk->m_oldPtr;
+ memPtr->m_flags = mat->m_flags;
+ memPtr->m_angularStiffness = mat->m_kAST;
+ memPtr->m_linearStiffness = mat->m_kLST;
+ memPtr->m_volumeStiffness = mat->m_kVST;
+ serializer->finalizeChunk(chunk,"SoftBodyMaterialData",BT_SBMATERIAL_CODE,mat);
+ }
+ }
+ serializer->finalizeChunk(chunk,"SoftBodyMaterialData",BT_ARRAY_CODE,(void*) &m_materials);
+ }
+
+
+
+
+ sbd->m_numNodes = m_nodes.size();
+ sbd->m_nodes = sbd->m_numNodes ? (SoftBodyNodeData*)serializer->getUniquePointer((void*)&m_nodes): 0;
+ if (sbd->m_nodes)
+ {
+ int sz = sizeof(SoftBodyNodeData);
+ int numElem = sbd->m_numNodes;
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ SoftBodyNodeData* memPtr = (SoftBodyNodeData*)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ m_nodes[i].m_f.serializeFloat( memPtr->m_accumulatedForce);
+ memPtr->m_area = m_nodes[i].m_area;
+ memPtr->m_attach = m_nodes[i].m_battach;
+ memPtr->m_inverseMass = m_nodes[i].m_im;
+ memPtr->m_material = m_nodes[i].m_material? (SoftBodyMaterialData*)serializer->getUniquePointer((void*) m_nodes[i].m_material):0;
+ m_nodes[i].m_n.serializeFloat(memPtr->m_normal);
+ m_nodes[i].m_x.serializeFloat(memPtr->m_position);
+ m_nodes[i].m_q.serializeFloat(memPtr->m_previousPosition);
+ m_nodes[i].m_v.serializeFloat(memPtr->m_velocity);
+ m_nodeIndexMap.insert(&m_nodes[i],i);
+ }
+ serializer->finalizeChunk(chunk,"SoftBodyNodeData",BT_SBNODE_CODE,(void*) &m_nodes);
+ }
+
+ sbd->m_numLinks = m_links.size();
+ sbd->m_links = sbd->m_numLinks? (SoftBodyLinkData*) serializer->getUniquePointer((void*)&m_links[0]):0;
+ if (sbd->m_links)
+ {
+ int sz = sizeof(SoftBodyLinkData);
+ int numElem = sbd->m_numLinks;
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ SoftBodyLinkData* memPtr = (SoftBodyLinkData*)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ memPtr->m_bbending = m_links[i].m_bbending;
+ memPtr->m_material = m_links[i].m_material? (SoftBodyMaterialData*)serializer->getUniquePointer((void*) m_links[i].m_material):0;
+ memPtr->m_nodeIndices[0] = m_links[i].m_n[0] ? m_links[i].m_n[0] - &m_nodes[0]: -1;
+ memPtr->m_nodeIndices[1] = m_links[i].m_n[1] ? m_links[i].m_n[1] - &m_nodes[0]: -1;
+ btAssert(memPtr->m_nodeIndices[0]<m_nodes.size());
+ btAssert(memPtr->m_nodeIndices[1]<m_nodes.size());
+ memPtr->m_restLength = m_links[i].m_rl;
+ }
+ serializer->finalizeChunk(chunk,"SoftBodyLinkData",BT_ARRAY_CODE,(void*) &m_links[0]);
+
+ }
+
+
+ sbd->m_numFaces = m_faces.size();
+ sbd->m_faces = sbd->m_numFaces? (SoftBodyFaceData*) serializer->getUniquePointer((void*)&m_faces[0]):0;
+ if (sbd->m_faces)
+ {
+ int sz = sizeof(SoftBodyFaceData);
+ int numElem = sbd->m_numFaces;
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ SoftBodyFaceData* memPtr = (SoftBodyFaceData*)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ memPtr->m_material = m_faces[i].m_material ? (SoftBodyMaterialData*) serializer->getUniquePointer((void*)m_faces[i].m_material): 0;
+ m_faces[i].m_normal.serializeFloat( memPtr->m_normal);
+ for (int j=0;j<3;j++)
+ {
+ memPtr->m_nodeIndices[j] = m_faces[i].m_n[j]? m_faces[i].m_n[j] - &m_nodes[0]: -1;
+ }
+ memPtr->m_restArea = m_faces[i].m_ra;
+ }
+ serializer->finalizeChunk(chunk,"SoftBodyFaceData",BT_ARRAY_CODE,(void*) &m_faces[0]);
+ }
+
+
+ sbd->m_numTetrahedra = m_tetras.size();
+ sbd->m_tetrahedra = sbd->m_numTetrahedra ? (SoftBodyTetraData*) serializer->getUniquePointer((void*)&m_tetras[0]):0;
+ if (sbd->m_tetrahedra)
+ {
+ int sz = sizeof(SoftBodyTetraData);
+ int numElem = sbd->m_numTetrahedra;
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ SoftBodyTetraData* memPtr = (SoftBodyTetraData*)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ for (int j=0;j<4;j++)
+ {
+ m_tetras[i].m_c0[j].serializeFloat( memPtr->m_c0[j] );
+ memPtr->m_nodeIndices[j] = m_tetras[j].m_n[j]? m_tetras[j].m_n[j]-&m_nodes[0] : -1;
+ }
+ memPtr->m_c1 = m_tetras[i].m_c1;
+ memPtr->m_c2 = m_tetras[i].m_c2;
+ memPtr->m_material = m_tetras[i].m_material ? (SoftBodyMaterialData*)serializer->getUniquePointer((void*) m_tetras[i].m_material): 0;
+ memPtr->m_restVolume = m_tetras[i].m_rv;
+ }
+ serializer->finalizeChunk(chunk,"SoftBodyTetraData",BT_ARRAY_CODE,(void*) &m_tetras[0]);
+ }
+
+ sbd->m_numAnchors = m_anchors.size();
+ sbd->m_anchors = sbd->m_numAnchors ? (SoftRigidAnchorData*) serializer->getUniquePointer((void*)&m_anchors[0]):0;
+ if (sbd->m_anchors)
+ {
+ int sz = sizeof(SoftRigidAnchorData);
+ int numElem = sbd->m_numAnchors;
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ SoftRigidAnchorData* memPtr = (SoftRigidAnchorData*)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ m_anchors[i].m_c0.serializeFloat(memPtr->m_c0);
+ m_anchors[i].m_c1.serializeFloat(memPtr->m_c1);
+ memPtr->m_c2 = m_anchors[i].m_c2;
+ m_anchors[i].m_local.serializeFloat(memPtr->m_localFrame);
+ memPtr->m_nodeIndex = m_anchors[i].m_node? m_anchors[i].m_node-&m_nodes[0]: -1;
+
+ memPtr->m_rigidBody = m_anchors[i].m_body? (btRigidBodyData*) serializer->getUniquePointer((void*)m_anchors[i].m_body): 0;
+ btAssert(memPtr->m_nodeIndex < m_nodes.size());
+ }
+ serializer->finalizeChunk(chunk,"SoftRigidAnchorData",BT_ARRAY_CODE,(void*) &m_anchors[0]);
+ }
+
+
+ sbd->m_config.m_dynamicFriction = m_cfg.kDF;
+ sbd->m_config.m_baumgarte = m_cfg.kVCF;
+ sbd->m_config.m_pressure = m_cfg.kPR;
+ sbd->m_config.m_aeroModel = this->m_cfg.aeromodel;
+ sbd->m_config.m_lift = m_cfg.kLF;
+ sbd->m_config.m_drag = m_cfg.kDG;
+ sbd->m_config.m_positionIterations = m_cfg.piterations;
+ sbd->m_config.m_driftIterations = m_cfg.diterations;
+ sbd->m_config.m_clusterIterations = m_cfg.citerations;
+ sbd->m_config.m_velocityIterations = m_cfg.viterations;
+ sbd->m_config.m_maxVolume = m_cfg.maxvolume;
+ sbd->m_config.m_damping = m_cfg.kDP;
+ sbd->m_config.m_poseMatch = m_cfg.kMT;
+ sbd->m_config.m_collisionFlags = m_cfg.collisions;
+ sbd->m_config.m_volume = m_cfg.kVC;
+ sbd->m_config.m_rigidContactHardness = m_cfg.kCHR;
+ sbd->m_config.m_kineticContactHardness = m_cfg.kKHR;
+ sbd->m_config.m_softContactHardness = m_cfg.kSHR;
+ sbd->m_config.m_anchorHardness = m_cfg.kAHR;
+ sbd->m_config.m_timeScale = m_cfg.timescale;
+ sbd->m_config.m_maxVolume = m_cfg.maxvolume;
+ sbd->m_config.m_softRigidClusterHardness = m_cfg.kSRHR_CL;
+ sbd->m_config.m_softKineticClusterHardness = m_cfg.kSKHR_CL;
+ sbd->m_config.m_softSoftClusterHardness = m_cfg.kSSHR_CL;
+ sbd->m_config.m_softRigidClusterImpulseSplit = m_cfg.kSR_SPLT_CL;
+ sbd->m_config.m_softKineticClusterImpulseSplit = m_cfg.kSK_SPLT_CL;
+ sbd->m_config.m_softSoftClusterImpulseSplit = m_cfg.kSS_SPLT_CL;
+
+ //pose for shape matching
+ {
+ sbd->m_pose = (SoftBodyPoseData*)serializer->getUniquePointer((void*)&m_pose);
+
+ int sz = sizeof(SoftBodyPoseData);
+ btChunk* chunk = serializer->allocate(sz,1);
+ SoftBodyPoseData* memPtr = (SoftBodyPoseData*)chunk->m_oldPtr;
+
+ m_pose.m_aqq.serializeFloat(memPtr->m_aqq);
+ memPtr->m_bframe = m_pose.m_bframe;
+ memPtr->m_bvolume = m_pose.m_bvolume;
+ m_pose.m_com.serializeFloat(memPtr->m_com);
+
+ memPtr->m_numPositions = m_pose.m_pos.size();
+ memPtr->m_positions = memPtr->m_numPositions ? (btVector3FloatData*)serializer->getUniquePointer((void*)&m_pose.m_pos[0]): 0;
+ if (memPtr->m_numPositions)
+ {
+ int numElem = memPtr->m_numPositions;
+ int sz = sizeof(btVector3Data);
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ btVector3FloatData* memPtr = (btVector3FloatData*)chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ m_pose.m_pos[i].serializeFloat(*memPtr);
+ }
+ serializer->finalizeChunk(chunk,"btVector3FloatData",BT_ARRAY_CODE,(void*)&m_pose.m_pos[0]);
+ }
+ memPtr->m_restVolume = m_pose.m_volume;
+ m_pose.m_rot.serializeFloat(memPtr->m_rot);
+ m_pose.m_scl.serializeFloat(memPtr->m_scale);
+
+ memPtr->m_numWeigts = m_pose.m_wgh.size();
+ memPtr->m_weights = memPtr->m_numWeigts? (float*) serializer->getUniquePointer((void*) &m_pose.m_wgh[0]) : 0;
+ if (memPtr->m_numWeigts)
+ {
+
+ int numElem = memPtr->m_numWeigts;
+ int sz = sizeof(float);
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ float* memPtr = (float*) chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ *memPtr = m_pose.m_wgh[i];
+ }
+ serializer->finalizeChunk(chunk,"float",BT_ARRAY_CODE,(void*)&m_pose.m_wgh[0]);
+ }
+
+ serializer->finalizeChunk(chunk,"SoftBodyPoseData",BT_ARRAY_CODE,(void*)&m_pose);
+ }
+
+ //clusters for convex-cluster collision detection
+
+ sbd->m_numClusters = m_clusters.size();
+ sbd->m_clusters = sbd->m_numClusters? (SoftBodyClusterData*) serializer->getUniquePointer((void*)m_clusters[0]) : 0;
+ if (sbd->m_numClusters)
+ {
+ int numElem = sbd->m_numClusters;
+ int sz = sizeof(SoftBodyClusterData);
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ SoftBodyClusterData* memPtr = (SoftBodyClusterData*) chunk->m_oldPtr;
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ memPtr->m_adamping= m_clusters[i]->m_adamping;
+ m_clusters[i]->m_av.serializeFloat(memPtr->m_av);
+ memPtr->m_clusterIndex = m_clusters[i]->m_clusterIndex;
+ memPtr->m_collide = m_clusters[i]->m_collide;
+ m_clusters[i]->m_com.serializeFloat(memPtr->m_com);
+ memPtr->m_containsAnchor = m_clusters[i]->m_containsAnchor;
+ m_clusters[i]->m_dimpulses[0].serializeFloat(memPtr->m_dimpulses[0]);
+ m_clusters[i]->m_dimpulses[1].serializeFloat(memPtr->m_dimpulses[1]);
+ m_clusters[i]->m_framexform.serializeFloat(memPtr->m_framexform);
+ memPtr->m_idmass = m_clusters[i]->m_idmass;
+ memPtr->m_imass = m_clusters[i]->m_imass;
+ m_clusters[i]->m_invwi.serializeFloat(memPtr->m_invwi);
+ memPtr->m_ldamping = m_clusters[i]->m_ldamping;
+ m_clusters[i]->m_locii.serializeFloat(memPtr->m_locii);
+ m_clusters[i]->m_lv.serializeFloat(memPtr->m_lv);
+ memPtr->m_matching = m_clusters[i]->m_matching;
+ memPtr->m_maxSelfCollisionImpulse = m_clusters[i]->m_maxSelfCollisionImpulse;
+ memPtr->m_ndamping = m_clusters[i]->m_ndamping;
+ memPtr->m_ldamping = m_clusters[i]->m_ldamping;
+ memPtr->m_adamping = m_clusters[i]->m_adamping;
+ memPtr->m_selfCollisionImpulseFactor = m_clusters[i]->m_selfCollisionImpulseFactor;
+
+ memPtr->m_numFrameRefs = m_clusters[i]->m_framerefs.size();
+ memPtr->m_numMasses = m_clusters[i]->m_masses.size();
+ memPtr->m_numNodes = m_clusters[i]->m_nodes.size();
+
+ memPtr->m_nvimpulses = m_clusters[i]->m_nvimpulses;
+ m_clusters[i]->m_vimpulses[0].serializeFloat(memPtr->m_vimpulses[0]);
+ m_clusters[i]->m_vimpulses[1].serializeFloat(memPtr->m_vimpulses[1]);
+ memPtr->m_ndimpulses = m_clusters[i]->m_ndimpulses;
+
+
+
+ memPtr->m_framerefs = memPtr->m_numFrameRefs? (btVector3FloatData*)serializer->getUniquePointer((void*)&m_clusters[i]->m_framerefs[0]) : 0;
+ if (memPtr->m_framerefs)
+ {
+ int numElem = memPtr->m_numFrameRefs;
+ int sz = sizeof(btVector3FloatData);
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ btVector3FloatData* memPtr = (btVector3FloatData*) chunk->m_oldPtr;
+ for (int j=0;j<numElem;j++,memPtr++)
+ {
+ m_clusters[i]->m_framerefs[j].serializeFloat(*memPtr);
+ }
+ serializer->finalizeChunk(chunk,"btVector3FloatData",BT_ARRAY_CODE,(void*)&m_clusters[i]->m_framerefs[0]);
+ }
+
+ memPtr->m_masses = memPtr->m_numMasses ? (float*) serializer->getUniquePointer((void*)&m_clusters[i]->m_masses[0]): 0;
+ if (memPtr->m_masses)
+ {
+ int numElem = memPtr->m_numMasses;
+ int sz = sizeof(float);
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ float* memPtr = (float*) chunk->m_oldPtr;
+ for (int j=0;j<numElem;j++,memPtr++)
+ {
+ *memPtr = m_clusters[i]->m_masses[j];
+ }
+ serializer->finalizeChunk(chunk,"float",BT_ARRAY_CODE,(void*)&m_clusters[i]->m_masses[0]);
+ }
+
+ memPtr->m_nodeIndices = memPtr->m_numNodes ? (int*) serializer->getUniquePointer((void*) &m_clusters[i]->m_nodes) : 0;
+ if (memPtr->m_nodeIndices )
+ {
+ int numElem = memPtr->m_numMasses;
+ int sz = sizeof(int);
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ int* memPtr = (int*) chunk->m_oldPtr;
+ for (int j=0;j<numElem;j++,memPtr++)
+ {
+ int* indexPtr = m_nodeIndexMap.find(m_clusters[i]->m_nodes[j]);
+ btAssert(indexPtr);
+ *memPtr = *indexPtr;
+ }
+ serializer->finalizeChunk(chunk,"int",BT_ARRAY_CODE,(void*)&m_clusters[i]->m_nodes);
+ }
+ }
+ serializer->finalizeChunk(chunk,"SoftBodyClusterData",BT_ARRAY_CODE,(void*)m_clusters[0]);
+
+ }
+
+
+
+ sbd->m_numJoints = m_joints.size();
+ sbd->m_joints = m_joints.size()? (btSoftBodyJointData*) serializer->getUniquePointer((void*)&m_joints[0]) : 0;
+
+ if (sbd->m_joints)
+ {
+ int sz = sizeof(btSoftBodyJointData);
+ int numElem = m_joints.size();
+ btChunk* chunk = serializer->allocate(sz,numElem);
+ btSoftBodyJointData* memPtr = (btSoftBodyJointData*)chunk->m_oldPtr;
+
+ for (int i=0;i<numElem;i++,memPtr++)
+ {
+ memPtr->m_jointType = (int)m_joints[i]->Type();
+ m_joints[i]->m_refs[0].serializeFloat(memPtr->m_refs[0]);
+ m_joints[i]->m_refs[1].serializeFloat(memPtr->m_refs[1]);
+ memPtr->m_cfm = m_joints[i]->m_cfm;
+ memPtr->m_erp = m_joints[i]->m_erp;
+ memPtr->m_split = m_joints[i]->m_split;
+ memPtr->m_delete = m_joints[i]->m_delete;
+
+ for (int j=0;j<4;j++)
+ {
+ memPtr->m_relPosition[0].m_floats[j] = 0.f;
+ memPtr->m_relPosition[1].m_floats[j] = 0.f;
+ }
+ memPtr->m_bodyA = 0;
+ memPtr->m_bodyB = 0;
+ if (m_joints[i]->m_bodies[0].m_soft)
+ {
+ memPtr->m_bodyAtype = BT_JOINT_SOFT_BODY_CLUSTER;
+ memPtr->m_bodyA = serializer->getUniquePointer((void*)m_joints[i]->m_bodies[0].m_soft);
+ }
+ if (m_joints[i]->m_bodies[0].m_collisionObject)
+ {
+ memPtr->m_bodyAtype = BT_JOINT_COLLISION_OBJECT;
+ memPtr->m_bodyA = serializer->getUniquePointer((void*)m_joints[i]->m_bodies[0].m_collisionObject);
+ }
+ if (m_joints[i]->m_bodies[0].m_rigid)
+ {
+ memPtr->m_bodyAtype = BT_JOINT_RIGID_BODY;
+ memPtr->m_bodyA = serializer->getUniquePointer((void*)m_joints[i]->m_bodies[0].m_rigid);
+ }
+
+ if (m_joints[i]->m_bodies[1].m_soft)
+ {
+ memPtr->m_bodyBtype = BT_JOINT_SOFT_BODY_CLUSTER;
+ memPtr->m_bodyB = serializer->getUniquePointer((void*)m_joints[i]->m_bodies[1].m_soft);
+ }
+ if (m_joints[i]->m_bodies[1].m_collisionObject)
+ {
+ memPtr->m_bodyBtype = BT_JOINT_COLLISION_OBJECT;
+ memPtr->m_bodyB = serializer->getUniquePointer((void*)m_joints[i]->m_bodies[1].m_collisionObject);
+ }
+ if (m_joints[i]->m_bodies[1].m_rigid)
+ {
+ memPtr->m_bodyBtype = BT_JOINT_RIGID_BODY;
+ memPtr->m_bodyB = serializer->getUniquePointer((void*)m_joints[i]->m_bodies[1].m_rigid);
+ }
+ }
+ serializer->finalizeChunk(chunk,"btSoftBodyJointData",BT_ARRAY_CODE,(void*) &m_joints[0]);
}
+
+
+ return btSoftBodyDataName;
}
+
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBody.h b/extern/bullet2/src/BulletSoftBody/btSoftBody.h
index a62c21883c8..87247c3c1c0 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftBody.h
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBody.h
@@ -27,8 +27,17 @@ subject to the following restrictions:
#include "btSparseSDF.h"
#include "BulletCollision/BroadphaseCollision/btDbvt.h"
+//#ifdef BT_USE_DOUBLE_PRECISION
+//#define btRigidBodyData btRigidBodyDoubleData
+//#define btRigidBodyDataName "btRigidBodyDoubleData"
+//#else
+#define btSoftBodyData btSoftBodyFloatData
+#define btSoftBodyDataName "btSoftBodyFloatData"
+//#endif //BT_USE_DOUBLE_PRECISION
+
class btBroadphaseInterface;
class btDispatcher;
+class btSoftBodySolver;
/* btSoftBodyWorldInfo */
struct btSoftBodyWorldInfo
@@ -41,6 +50,17 @@ struct btSoftBodyWorldInfo
btDispatcher* m_dispatcher;
btVector3 m_gravity;
btSparseSdf<3> m_sparsesdf;
+
+ btSoftBodyWorldInfo()
+ :air_density((btScalar)1.2),
+ water_density(0),
+ water_offset(0),
+ water_normal(0,0,0),
+ m_broadphase(0),
+ m_dispatcher(0),
+ m_gravity(0,-10,0)
+ {
+ }
};
@@ -51,6 +71,9 @@ class btSoftBody : public btCollisionObject
public:
btAlignedObjectArray<class btCollisionObject*> m_collisionDisabledObjects;
+ // The solver object that handles this soft body
+ btSoftBodySolver *m_softBodySolver;
+
//
// Enumerations
//
@@ -110,9 +133,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
@@ -181,12 +205,14 @@ public:
btScalar m_kAST; // Area/Angular stiffness coefficient [0,1]
btScalar m_kVST; // Volume stiffness coefficient [0,1]
int m_flags; // Flags
+ Material() : Element() {}
};
/* Feature */
struct Feature : Element
{
Material* m_material; // Material
+ Feature() : Element() {}
};
/* Node */
struct Node : Feature
@@ -200,6 +226,7 @@ public:
btScalar m_area; // Area
btDbvtNode* m_leaf; // Leaf data
int m_battach:1; // Attached
+ Node() : Feature() {}
};
/* Link */
struct Link : Feature
@@ -211,6 +238,7 @@ public:
btScalar m_c1; // rl^2
btScalar m_c2; // |gradient|^2/c0
btVector3 m_c3; // gradient
+ Link() : Feature() {}
};
/* Face */
struct Face : Feature
@@ -219,6 +247,18 @@ public:
btVector3 m_normal; // Normal
btScalar m_ra; // Rest area
btDbvtNode* m_leaf; // Leaf data
+ Face() : Feature() {}
+ };
+ /* Tetra */
+ struct Tetra : Feature
+ {
+ Node* m_n[4]; // Node pointers
+ btScalar m_rv; // Rest volume
+ btDbvtNode* m_leaf; // Leaf data
+ btVector3 m_c0[4]; // gradients
+ btScalar m_c1; // (4*kVST)/(im0+im1+im2+im3)
+ btScalar m_c2; // m_c1/sum(|g0..3|^2)
+ Tetra() : Feature() {}
};
/* RContact */
struct RContact
@@ -260,6 +300,7 @@ public:
int m_rank; // Rank
Node* m_nodes[4]; // Nodes
btScalar m_coords[4]; // Coordinates
+ Note() : Element() {}
};
/* Pose */
struct Pose
@@ -276,9 +317,9 @@ public:
};
/* Cluster */
struct Cluster
- {
- btAlignedObjectArray<Node*> m_nodes;
+ {
tScalarArray m_masses;
+ btAlignedObjectArray<Node*> m_nodes;
tVector3Array m_framerefs;
btTransform m_framexform;
btScalar m_idmass;
@@ -297,9 +338,16 @@ public:
btScalar m_ldamping; /* Linear damping */
btScalar m_adamping; /* Angular damping */
btScalar m_matching;
+ btScalar m_maxSelfCollisionImpulse;
+ btScalar m_selfCollisionImpulseFactor;
+ bool m_containsAnchor;
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),
+ m_containsAnchor(false)
+ {}
};
/* Impulse */
struct Impulse
@@ -340,7 +388,11 @@ public:
void activate() const
{
- if(m_rigid) m_rigid->activate();
+ if(m_rigid)
+ m_rigid->activate();
+ if (m_collisionObject)
+ m_collisionObject->activate();
+
}
const btMatrix3x3& invWorldInertia() const
{
@@ -358,7 +410,7 @@ public:
const btTransform& xform() const
{
static const btTransform identity=btTransform::getIdentity();
- if(m_collisionObject) return(m_collisionObject->getInterpolationWorldTransform());
+ if(m_collisionObject) return(m_collisionObject->getWorldTransform());
if(m_soft) return(m_soft->m_framexform);
return(identity);
}
@@ -370,8 +422,8 @@ public:
}
btVector3 angularVelocity(const btVector3& rpos) const
{
- if(m_rigid) return(cross(m_rigid->getAngularVelocity(),rpos));
- if(m_soft) return(cross(m_soft->m_av,rpos));
+ if(m_rigid) return(btCross(m_rigid->getAngularVelocity(),rpos));
+ if(m_soft) return(btCross(m_soft->m_av,rpos));
return(btVector3(0,0,0));
}
btVector3 angularVelocity() const
@@ -396,8 +448,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
{
@@ -424,7 +484,7 @@ public:
struct Joint
{
struct eType { enum _ {
- Linear,
+ Linear=0,
Angular,
Contact
};};
@@ -563,7 +623,7 @@ public:
};
//
- // Typedef's
+ // Typedefs
//
typedef void (*psolver_t)(btSoftBody*,btScalar,btScalar);
@@ -574,6 +634,7 @@ public:
typedef btAlignedObjectArray<btDbvtNode*> tLeafArray;
typedef btAlignedObjectArray<Link> tLinkArray;
typedef btAlignedObjectArray<Face> tFaceArray;
+ typedef btAlignedObjectArray<Tetra> tTetraArray;
typedef btAlignedObjectArray<Anchor> tAnchorArray;
typedef btAlignedObjectArray<RContact> tRContactArray;
typedef btAlignedObjectArray<SContact> tSContactArray;
@@ -594,6 +655,7 @@ public:
tNodeArray m_nodes; // Nodes
tLinkArray m_links; // Links
tFaceArray m_faces; // Faces
+ tTetraArray m_tetras; // Tetras
tAnchorArray m_anchors; // Anchors
tRContactArray m_rcontacts; // Rigid contacts
tSContactArray m_scontacts; // Soft contacts
@@ -611,14 +673,19 @@ public:
btTransform m_initialWorldTransform;
+ btVector3 m_windVelocity;
//
// Api
//
/* ctor */
- btSoftBody( btSoftBodyWorldInfo* worldInfo,int node_count,
- const btVector3* x,
- const btScalar* m);
+ btSoftBody( btSoftBodyWorldInfo* worldInfo,int node_count, const btVector3* x, const btScalar* m);
+
+ /* ctor */
+ btSoftBody( btSoftBodyWorldInfo* worldInfo);
+
+ void initDefaults();
+
/* dtor */
virtual ~btSoftBody();
/* Check for existing link */
@@ -681,9 +748,19 @@ public:
int node1,
int node2,
Material* mat=0);
+ void appendTetra(int model,Material* mat);
+ //
+ void appendTetra(int node0,
+ int node1,
+ int node2,
+ int node3,
+ Material* mat=0);
+
+
/* Append anchor */
void appendAnchor( int node,
btRigidBody* body, bool disableCollisionBetweenLinkedBodies=false);
+ void appendAnchor(int node,btRigidBody* body, const btVector3& localPivot,bool disableCollisionBetweenLinkedBodies=false);
/* Append linear joint */
void appendLinearJoint(const LJoint::Specs& specs,Cluster* body0,Body body1);
void appendLinearJoint(const LJoint::Specs& specs,Body body=Body());
@@ -718,6 +795,10 @@ public:
bool fromfaces=false);
/* Set total density */
void setTotalDensity(btScalar density);
+ /* Set volume mass (using tetrahedrons) */
+ void setVolumeMass( btScalar mass);
+ /* Set volume density (using tetrahedrons) */
+ void setVolumeDensity( btScalar density);
/* Transform */
void transform( const btTransform& trs);
/* Translate */
@@ -755,6 +836,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);
@@ -784,6 +867,49 @@ public:
void defaultCollisionHandler(btCollisionObject* pco);
void defaultCollisionHandler(btSoftBody* psb);
+
+
+ //
+ // Functionality to deal with new accelerated solvers.
+ //
+
+ /**
+ * Set a wind velocity for interaction with the air.
+ */
+ void setWindVelocity( const btVector3 &velocity );
+
+
+ /**
+ * Return the wind velocity for interaction with the air.
+ */
+ const btVector3& getWindVelocity();
+
+ //
+ // Set the solver that handles this soft body
+ // Should not be allowed to get out of sync with reality
+ // Currently called internally on addition to the world
+ void setSoftBodySolver( btSoftBodySolver *softBodySolver )
+ {
+ m_softBodySolver = softBodySolver;
+ }
+
+ //
+ // Return the solver that handles this soft body
+ //
+ btSoftBodySolver *getSoftBodySolver()
+ {
+ return m_softBodySolver;
+ }
+
+ //
+ // Return the solver that handles this soft body
+ //
+ btSoftBodySolver *getSoftBodySolver() const
+ {
+ return m_softBodySolver;
+ }
+
+
//
// Cast
//
@@ -841,8 +967,18 @@ public:
static psolver_t getSolver(ePSolver::_ solver);
static vsolver_t getSolver(eVSolver::_ solver);
+
+ virtual int calculateSerializeBufferSize() const;
+
+ ///fills the dataBuffer and returns the struct name (and 0 on failure)
+ virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
+
+ //virtual void serializeSingleObject(class btSerializer* serializer) const;
+
+
};
+
#endif //_BT_SOFT_BODY_H
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp b/extern/bullet2/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp
index f334e15e0d3..04ee7ea77cf 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp
@@ -95,9 +95,9 @@ 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);
+ btVector3 color(1,1,0);
btTransform& tr = ob->getWorldTransform();
m_dispatchInfoPtr->m_debugDraw->drawLine(tr(triangle[0]),tr(triangle[1]),color);
m_dispatchInfoPtr->m_debugDraw->drawLine(tr(triangle[1]),tr(triangle[2]),color);
@@ -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();
@@ -219,7 +218,7 @@ void btSoftBodyConcaveCollisionAlgorithm::processCollision (btCollisionObject* b
{
- btCollisionObject* convexBody = m_isSwapped ? body1 : body0;
+ //btCollisionObject* convexBody = m_isSwapped ? body1 : body0;
btCollisionObject* triBody = m_isSwapped ? body0 : body1;
if (triBody->getCollisionShape()->isConcave())
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodyData.h b/extern/bullet2/src/BulletSoftBody/btSoftBodyData.h
new file mode 100644
index 00000000000..40dc65c3d8c
--- /dev/null
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodyData.h
@@ -0,0 +1,217 @@
+/*
+Bullet Continuous Collision Detection and Physics Library
+Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
+
+This software is provided 'as-is', without any express or implied warranty.
+In no event will the authors be held liable for any damages arising from the use of this software.
+Permission is granted to anyone to use this software for any purpose,
+including commercial applications, and to alter it and redistribute it freely,
+subject to the following restrictions:
+
+1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
+2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
+3. This notice may not be removed or altered from any source distribution.
+*/
+
+#ifndef BT_SOFTBODY_FLOAT_DATA
+#define BT_SOFTBODY_FLOAT_DATA
+
+#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
+
+
+
+struct SoftBodyMaterialData
+{
+ float m_linearStiffness;
+ float m_angularStiffness;
+ float m_volumeStiffness;
+ int m_flags;
+};
+
+struct SoftBodyNodeData
+{
+ SoftBodyMaterialData *m_material;
+ btVector3FloatData m_position;
+ btVector3FloatData m_previousPosition;
+ btVector3FloatData m_velocity;
+ btVector3FloatData m_accumulatedForce;
+ btVector3FloatData m_normal;
+ float m_inverseMass;
+ float m_area;
+ int m_attach;
+ int m_pad;
+};
+
+struct SoftBodyLinkData
+{
+ SoftBodyMaterialData *m_material;
+ int m_nodeIndices[2]; // Node pointers
+ float m_restLength; // Rest length
+ int m_bbending; // Bending link
+};
+
+struct SoftBodyFaceData
+{
+ btVector3FloatData m_normal; // Normal
+ SoftBodyMaterialData *m_material;
+ int m_nodeIndices[3]; // Node pointers
+ float m_restArea; // Rest area
+};
+
+struct SoftBodyTetraData
+{
+ btVector3FloatData m_c0[4]; // gradients
+ SoftBodyMaterialData *m_material;
+ int m_nodeIndices[4]; // Node pointers
+ float m_restVolume; // Rest volume
+ float m_c1; // (4*kVST)/(im0+im1+im2+im3)
+ float m_c2; // m_c1/sum(|g0..3|^2)
+ int m_pad;
+};
+
+struct SoftRigidAnchorData
+{
+ btMatrix3x3FloatData m_c0; // Impulse matrix
+ btVector3FloatData m_c1; // Relative anchor
+ btVector3FloatData m_localFrame; // Anchor position in body space
+ btRigidBodyData *m_rigidBody;
+ int m_nodeIndex; // Node pointer
+ float m_c2; // ima*dt
+};
+
+
+
+struct SoftBodyConfigData
+{
+ int m_aeroModel; // Aerodynamic model (default: V_Point)
+ float m_baumgarte; // Velocities correction factor (Baumgarte)
+ float m_damping; // Damping coefficient [0,1]
+ float m_drag; // Drag coefficient [0,+inf]
+ float m_lift; // Lift coefficient [0,+inf]
+ float m_pressure; // Pressure coefficient [-inf,+inf]
+ float m_volume; // Volume conversation coefficient [0,+inf]
+ float m_dynamicFriction; // Dynamic friction coefficient [0,1]
+ float m_poseMatch; // Pose matching coefficient [0,1]
+ float m_rigidContactHardness; // Rigid contacts hardness [0,1]
+ float m_kineticContactHardness; // Kinetic contacts hardness [0,1]
+ float m_softContactHardness; // Soft contacts hardness [0,1]
+ float m_anchorHardness; // Anchors hardness [0,1]
+ float m_softRigidClusterHardness; // Soft vs rigid hardness [0,1] (cluster only)
+ float m_softKineticClusterHardness; // Soft vs kinetic hardness [0,1] (cluster only)
+ float m_softSoftClusterHardness; // Soft vs soft hardness [0,1] (cluster only)
+ float m_softRigidClusterImpulseSplit; // Soft vs rigid impulse split [0,1] (cluster only)
+ float m_softKineticClusterImpulseSplit; // Soft vs rigid impulse split [0,1] (cluster only)
+ float m_softSoftClusterImpulseSplit; // Soft vs rigid impulse split [0,1] (cluster only)
+ float m_maxVolume; // Maximum volume ratio for pose
+ float m_timeScale; // Time scale
+ int m_velocityIterations; // Velocities solver iterations
+ int m_positionIterations; // Positions solver iterations
+ int m_driftIterations; // Drift solver iterations
+ int m_clusterIterations; // Cluster solver iterations
+ int m_collisionFlags; // Collisions flags
+};
+
+struct SoftBodyPoseData
+{
+ btMatrix3x3FloatData m_rot; // Rotation
+ btMatrix3x3FloatData m_scale; // Scale
+ btMatrix3x3FloatData m_aqq; // Base scaling
+ btVector3FloatData m_com; // COM
+
+ btVector3FloatData *m_positions; // Reference positions
+ float *m_weights; // Weights
+ int m_numPositions;
+ int m_numWeigts;
+
+ int m_bvolume; // Is valid
+ int m_bframe; // Is frame
+ float m_restVolume; // Rest volume
+ int m_pad;
+};
+
+struct SoftBodyClusterData
+{
+ btTransformFloatData m_framexform;
+ btMatrix3x3FloatData m_locii;
+ btMatrix3x3FloatData m_invwi;
+ btVector3FloatData m_com;
+ btVector3FloatData m_vimpulses[2];
+ btVector3FloatData m_dimpulses[2];
+ btVector3FloatData m_lv;
+ btVector3FloatData m_av;
+
+ btVector3FloatData *m_framerefs;
+ int *m_nodeIndices;
+ float *m_masses;
+
+ int m_numFrameRefs;
+ int m_numNodes;
+ int m_numMasses;
+
+ float m_idmass;
+ float m_imass;
+ int m_nvimpulses;
+ int m_ndimpulses;
+ float m_ndamping;
+ float m_ldamping;
+ float m_adamping;
+ float m_matching;
+ float m_maxSelfCollisionImpulse;
+ float m_selfCollisionImpulseFactor;
+ int m_containsAnchor;
+ int m_collide;
+ int m_clusterIndex;
+};
+
+
+enum btSoftJointBodyType
+{
+ BT_JOINT_SOFT_BODY_CLUSTER=1,
+ BT_JOINT_RIGID_BODY,
+ BT_JOINT_COLLISION_OBJECT
+};
+
+struct btSoftBodyJointData
+{
+ void *m_bodyA;
+ void *m_bodyB;
+ btVector3FloatData m_refs[2];
+ float m_cfm;
+ float m_erp;
+ float m_split;
+ int m_delete;
+ btVector3FloatData m_relPosition[2];//linear
+ int m_bodyAtype;
+ int m_bodyBtype;
+ int m_jointType;
+ int m_pad;
+};
+
+///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
+struct btSoftBodyFloatData
+{
+ btCollisionObjectFloatData m_collisionObjectData;
+
+ SoftBodyPoseData *m_pose;
+ SoftBodyMaterialData **m_materials;
+ SoftBodyNodeData *m_nodes;
+ SoftBodyLinkData *m_links;
+ SoftBodyFaceData *m_faces;
+ SoftBodyTetraData *m_tetrahedra;
+ SoftRigidAnchorData *m_anchors;
+ SoftBodyClusterData *m_clusters;
+ btSoftBodyJointData *m_joints;
+
+ int m_numMaterials;
+ int m_numNodes;
+ int m_numLinks;
+ int m_numFaces;
+ int m_numTetrahedra;
+ int m_numAnchors;
+ int m_numClusters;
+ int m_numJoints;
+ SoftBodyConfigData m_config;
+};
+
+#endif //BT_SOFTBODY_FLOAT_DATA
+
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.cpp b/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.cpp
index 61aac5b4ce5..1a271066497 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.cpp
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.cpp
@@ -130,7 +130,7 @@ static inline btScalar tetravolume(const btVector3& x0,
const btVector3 a=x1-x0;
const btVector3 b=x2-x0;
const btVector3 c=x3-x0;
- return(dot(a,cross(b,c)));
+ return(btDot(a,btCross(b,c)));
}
//
@@ -165,98 +165,7 @@ void btSoftBodyHelpers::Draw( btSoftBody* psb,
const btVector3 ccolor=btVector3(1,0,0);
int i,j,nj;
- /* Nodes */
- if(0!=(drawflags&fDrawFlags::Nodes))
- {
- for(i=0;i<psb->m_nodes.size();++i)
- {
- const btSoftBody::Node& n=psb->m_nodes[i];
- if(0==(n.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
- idraw->drawLine(n.m_x-btVector3(scl,0,0),n.m_x+btVector3(scl,0,0),btVector3(1,0,0));
- idraw->drawLine(n.m_x-btVector3(0,scl,0),n.m_x+btVector3(0,scl,0),btVector3(0,1,0));
- idraw->drawLine(n.m_x-btVector3(0,0,scl),n.m_x+btVector3(0,0,scl),btVector3(0,0,1));
- }
- }
- /* Links */
- if(0!=(drawflags&fDrawFlags::Links))
- {
- for(i=0;i<psb->m_links.size();++i)
- {
- const btSoftBody::Link& l=psb->m_links[i];
- if(0==(l.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
- idraw->drawLine(l.m_n[0]->m_x,l.m_n[1]->m_x,lcolor);
- }
- }
- /* Normals */
- if(0!=(drawflags&fDrawFlags::Normals))
- {
- for(i=0;i<psb->m_nodes.size();++i)
- {
- const btSoftBody::Node& n=psb->m_nodes[i];
- if(0==(n.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
- const btVector3 d=n.m_n*nscl;
- idraw->drawLine(n.m_x,n.m_x+d,ncolor);
- idraw->drawLine(n.m_x,n.m_x-d,ncolor*0.5);
- }
- }
- /* Contacts */
- if(0!=(drawflags&fDrawFlags::Contacts))
- {
- static const btVector3 axis[]={btVector3(1,0,0),
- btVector3(0,1,0),
- btVector3(0,0,1)};
- for(i=0;i<psb->m_rcontacts.size();++i)
- {
- const btSoftBody::RContact& c=psb->m_rcontacts[i];
- const btVector3 o= c.m_node->m_x-c.m_cti.m_normal*
- (dot(c.m_node->m_x,c.m_cti.m_normal)+c.m_cti.m_offset);
- const btVector3 x=cross(c.m_cti.m_normal,axis[c.m_cti.m_normal.minAxis()]).normalized();
- const btVector3 y=cross(x,c.m_cti.m_normal).normalized();
- idraw->drawLine(o-x*nscl,o+x*nscl,ccolor);
- idraw->drawLine(o-y*nscl,o+y*nscl,ccolor);
- idraw->drawLine(o,o+c.m_cti.m_normal*nscl*3,btVector3(1,1,0));
- }
- }
- /* Anchors */
- if(0!=(drawflags&fDrawFlags::Anchors))
- {
- for(i=0;i<psb->m_anchors.size();++i)
- {
- const btSoftBody::Anchor& a=psb->m_anchors[i];
- const btVector3 q=a.m_body->getWorldTransform()*a.m_local;
- drawVertex(idraw,a.m_node->m_x,0.25,btVector3(1,0,0));
- drawVertex(idraw,q,0.25,btVector3(0,1,0));
- idraw->drawLine(a.m_node->m_x,q,btVector3(1,1,1));
- }
- for(i=0;i<psb->m_nodes.size();++i)
- {
- const btSoftBody::Node& n=psb->m_nodes[i];
- if(0==(n.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
- if(n.m_im<=0)
- {
- drawVertex(idraw,n.m_x,0.25,btVector3(1,0,0));
- }
- }
- }
- /* Faces */
- if(0!=(drawflags&fDrawFlags::Faces))
- {
- const btScalar scl=(btScalar)0.8;
- const btScalar alp=(btScalar)1;
- const btVector3 col(0,(btScalar)0.7,0);
- for(i=0;i<psb->m_faces.size();++i)
- {
- const btSoftBody::Face& f=psb->m_faces[i];
- if(0==(f.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
- const btVector3 x[]={f.m_n[0]->m_x,f.m_n[1]->m_x,f.m_n[2]->m_x};
- const btVector3 c=(x[0]+x[1]+x[2])/3;
- idraw->drawTriangle((x[0]-c)*scl+c,
- (x[1]-c)*scl+c,
- (x[2]-c)*scl+c,
- col,alp);
- }
- }
- /* Clusters */
+ /* Clusters */
if(0!=(drawflags&fDrawFlags::Clusters))
{
srand(1806);
@@ -299,17 +208,131 @@ void btSoftBodyHelpers::Draw( btSoftBody* psb,
{
const btSoftBody::Cluster& c=psb->m_clusters[i];
const btVector3 r=c.m_nodes[j]->m_x-c.m_com;
- const btVector3 v=c.m_lv+cross(c.m_av,r);
+ const btVector3 v=c.m_lv+btCross(c.m_av,r);
idraw->drawLine(c.m_nodes[j]->m_x,c.m_nodes[j]->m_x+v,btVector3(1,0,0));
}
#endif
/* Frame */
- btSoftBody::Cluster& c=*psb->m_clusters[i];
- idraw->drawLine(c.m_com,c.m_framexform*btVector3(10,0,0),btVector3(1,0,0));
- idraw->drawLine(c.m_com,c.m_framexform*btVector3(0,10,0),btVector3(0,1,0));
- idraw->drawLine(c.m_com,c.m_framexform*btVector3(0,0,10),btVector3(0,0,1));
+ // btSoftBody::Cluster& c=*psb->m_clusters[i];
+ // idraw->drawLine(c.m_com,c.m_framexform*btVector3(10,0,0),btVector3(1,0,0));
+ // idraw->drawLine(c.m_com,c.m_framexform*btVector3(0,10,0),btVector3(0,1,0));
+ // idraw->drawLine(c.m_com,c.m_framexform*btVector3(0,0,10),btVector3(0,0,1));
}
}
+ else
+ {
+ /* Nodes */
+ if(0!=(drawflags&fDrawFlags::Nodes))
+ {
+ for(i=0;i<psb->m_nodes.size();++i)
+ {
+ const btSoftBody::Node& n=psb->m_nodes[i];
+ if(0==(n.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
+ idraw->drawLine(n.m_x-btVector3(scl,0,0),n.m_x+btVector3(scl,0,0),btVector3(1,0,0));
+ idraw->drawLine(n.m_x-btVector3(0,scl,0),n.m_x+btVector3(0,scl,0),btVector3(0,1,0));
+ idraw->drawLine(n.m_x-btVector3(0,0,scl),n.m_x+btVector3(0,0,scl),btVector3(0,0,1));
+ }
+ }
+ /* Links */
+ if(0!=(drawflags&fDrawFlags::Links))
+ {
+ for(i=0;i<psb->m_links.size();++i)
+ {
+ const btSoftBody::Link& l=psb->m_links[i];
+ if(0==(l.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
+ idraw->drawLine(l.m_n[0]->m_x,l.m_n[1]->m_x,lcolor);
+ }
+ }
+ /* Normals */
+ if(0!=(drawflags&fDrawFlags::Normals))
+ {
+ for(i=0;i<psb->m_nodes.size();++i)
+ {
+ const btSoftBody::Node& n=psb->m_nodes[i];
+ if(0==(n.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
+ const btVector3 d=n.m_n*nscl;
+ idraw->drawLine(n.m_x,n.m_x+d,ncolor);
+ idraw->drawLine(n.m_x,n.m_x-d,ncolor*0.5);
+ }
+ }
+ /* Contacts */
+ if(0!=(drawflags&fDrawFlags::Contacts))
+ {
+ static const btVector3 axis[]={btVector3(1,0,0),
+ btVector3(0,1,0),
+ btVector3(0,0,1)};
+ for(i=0;i<psb->m_rcontacts.size();++i)
+ {
+ const btSoftBody::RContact& c=psb->m_rcontacts[i];
+ const btVector3 o= c.m_node->m_x-c.m_cti.m_normal*
+ (btDot(c.m_node->m_x,c.m_cti.m_normal)+c.m_cti.m_offset);
+ const btVector3 x=btCross(c.m_cti.m_normal,axis[c.m_cti.m_normal.minAxis()]).normalized();
+ const btVector3 y=btCross(x,c.m_cti.m_normal).normalized();
+ idraw->drawLine(o-x*nscl,o+x*nscl,ccolor);
+ idraw->drawLine(o-y*nscl,o+y*nscl,ccolor);
+ idraw->drawLine(o,o+c.m_cti.m_normal*nscl*3,btVector3(1,1,0));
+ }
+ }
+ /* Faces */
+ if(0!=(drawflags&fDrawFlags::Faces))
+ {
+ const btScalar scl=(btScalar)0.8;
+ const btScalar alp=(btScalar)1;
+ const btVector3 col(0,(btScalar)0.7,0);
+ for(i=0;i<psb->m_faces.size();++i)
+ {
+ const btSoftBody::Face& f=psb->m_faces[i];
+ if(0==(f.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
+ const btVector3 x[]={f.m_n[0]->m_x,f.m_n[1]->m_x,f.m_n[2]->m_x};
+ const btVector3 c=(x[0]+x[1]+x[2])/3;
+ idraw->drawTriangle((x[0]-c)*scl+c,
+ (x[1]-c)*scl+c,
+ (x[2]-c)*scl+c,
+ col,alp);
+ }
+ }
+ /* Tetras */
+ if(0!=(drawflags&fDrawFlags::Tetras))
+ {
+ const btScalar scl=(btScalar)0.8;
+ const btScalar alp=(btScalar)1;
+ const btVector3 col((btScalar)0.7,(btScalar)0.7,(btScalar)0.7);
+ for(int i=0;i<psb->m_tetras.size();++i)
+ {
+ const btSoftBody::Tetra& t=psb->m_tetras[i];
+ if(0==(t.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
+ const btVector3 x[]={t.m_n[0]->m_x,t.m_n[1]->m_x,t.m_n[2]->m_x,t.m_n[3]->m_x};
+ const btVector3 c=(x[0]+x[1]+x[2]+x[3])/4;
+ idraw->drawTriangle((x[0]-c)*scl+c,(x[1]-c)*scl+c,(x[2]-c)*scl+c,col,alp);
+ idraw->drawTriangle((x[0]-c)*scl+c,(x[1]-c)*scl+c,(x[3]-c)*scl+c,col,alp);
+ idraw->drawTriangle((x[1]-c)*scl+c,(x[2]-c)*scl+c,(x[3]-c)*scl+c,col,alp);
+ idraw->drawTriangle((x[2]-c)*scl+c,(x[0]-c)*scl+c,(x[3]-c)*scl+c,col,alp);
+ }
+ }
+ }
+ /* Anchors */
+ if(0!=(drawflags&fDrawFlags::Anchors))
+ {
+ for(i=0;i<psb->m_anchors.size();++i)
+ {
+ const btSoftBody::Anchor& a=psb->m_anchors[i];
+ const btVector3 q=a.m_body->getWorldTransform()*a.m_local;
+ drawVertex(idraw,a.m_node->m_x,0.25,btVector3(1,0,0));
+ drawVertex(idraw,q,0.25,btVector3(0,1,0));
+ idraw->drawLine(a.m_node->m_x,q,btVector3(1,1,1));
+ }
+ for(i=0;i<psb->m_nodes.size();++i)
+ {
+ const btSoftBody::Node& n=psb->m_nodes[i];
+ if(0==(n.m_material->m_flags&btSoftBody::fMaterial::DebugDraw)) continue;
+ if(n.m_im<=0)
+ {
+ drawVertex(idraw,n.m_x,0.25,btVector3(1,0,0));
+ }
+ }
+ }
+
+
/* Notes */
if(0!=(drawflags&fDrawFlags::Notes))
{
@@ -351,7 +374,7 @@ void btSoftBodyHelpers::Draw( btSoftBody* psb,
break;
case btSoftBody::Joint::eType::Angular:
{
- const btSoftBody::AJoint* pja=(const btSoftBody::AJoint*)pj;
+ //const btSoftBody::AJoint* pja=(const btSoftBody::AJoint*)pj;
const btVector3 o0=pj->m_bodies[0].xform().getOrigin();
const btVector3 o1=pj->m_bodies[1].xform().getOrigin();
const btVector3 a0=pj->m_bodies[0].xform().getBasis()*pj->m_refs[0];
@@ -360,7 +383,12 @@ void btSoftBodyHelpers::Draw( btSoftBody* psb,
idraw->drawLine(o0,o0+a1*10,btVector3(1,1,0));
idraw->drawLine(o1,o1+a0*10,btVector3(0,1,1));
idraw->drawLine(o1,o1+a1*10,btVector3(0,1,1));
+ break;
+ }
+ default:
+ {
}
+
}
}
}
@@ -828,10 +856,12 @@ btSoftBody* btSoftBodyHelpers::CreateFromTriMesh(btSoftBodyWorldInfo& worldInfo
#undef IDX
psb->appendFace(idx[0],idx[1],idx[2]);
}
+
if (randomizeConstraints)
{
psb->randomizeConstraints();
}
+
return(psb);
}
@@ -863,3 +893,130 @@ btSoftBody* btSoftBodyHelpers::CreateFromConvexHull(btSoftBodyWorldInfo& worldI
}
return(psb);
}
+
+
+
+
+static int nextLine(const char* buffer)
+{
+ int numBytesRead=0;
+
+ while (*buffer != '\n')
+ {
+ buffer++;
+ numBytesRead++;
+ }
+
+
+ if (buffer[0]==0x0a)
+ {
+ buffer++;
+ numBytesRead++;
+ }
+ return numBytesRead;
+}
+
+/* Create from TetGen .ele, .face, .node data */
+btSoftBody* btSoftBodyHelpers::CreateFromTetGenData(btSoftBodyWorldInfo& worldInfo,
+ const char* ele,
+ const char* face,
+ const char* node,
+ bool bfacelinks,
+ bool btetralinks,
+ bool bfacesfromtetras)
+{
+btAlignedObjectArray<btVector3> pos;
+int nnode=0;
+int ndims=0;
+int nattrb=0;
+int hasbounds=0;
+int result = sscanf(node,"%d %d %d %d",&nnode,&ndims,&nattrb,&hasbounds);
+result = sscanf(node,"%d %d %d %d",&nnode,&ndims,&nattrb,&hasbounds);
+node += nextLine(node);
+
+pos.resize(nnode);
+for(int i=0;i<pos.size();++i)
+ {
+ int index=0;
+ //int bound=0;
+ float x,y,z;
+ sscanf(node,"%d %f %f %f",&index,&x,&y,&z);
+
+// sn>>index;
+// sn>>x;sn>>y;sn>>z;
+ node += nextLine(node);
+
+ //for(int j=0;j<nattrb;++j)
+ // sn>>a;
+
+ //if(hasbounds)
+ // sn>>bound;
+
+ pos[index].setX(btScalar(x));
+ pos[index].setY(btScalar(y));
+ pos[index].setZ(btScalar(z));
+ }
+btSoftBody* psb=new btSoftBody(&worldInfo,nnode,&pos[0],0);
+#if 0
+if(face&&face[0])
+ {
+ int nface=0;
+ sf>>nface;sf>>hasbounds;
+ for(int i=0;i<nface;++i)
+ {
+ int index=0;
+ int bound=0;
+ int ni[3];
+ sf>>index;
+ sf>>ni[0];sf>>ni[1];sf>>ni[2];
+ sf>>bound;
+ psb->appendFace(ni[0],ni[1],ni[2]);
+ if(btetralinks)
+ {
+ psb->appendLink(ni[0],ni[1],0,true);
+ psb->appendLink(ni[1],ni[2],0,true);
+ psb->appendLink(ni[2],ni[0],0,true);
+ }
+ }
+ }
+#endif
+
+if(ele&&ele[0])
+ {
+ int ntetra=0;
+ int ncorner=0;
+ int neattrb=0;
+ sscanf(ele,"%d %d %d",&ntetra,&ncorner,&neattrb);
+ ele += nextLine(ele);
+
+ //se>>ntetra;se>>ncorner;se>>neattrb;
+ for(int i=0;i<ntetra;++i)
+ {
+ int index=0;
+ int ni[4];
+
+ //se>>index;
+ //se>>ni[0];se>>ni[1];se>>ni[2];se>>ni[3];
+ sscanf(ele,"%d %d %d %d %d",&index,&ni[0],&ni[1],&ni[2],&ni[3]);
+ ele+=nextLine(ele);
+ //for(int j=0;j<neattrb;++j)
+ // se>>a;
+ psb->appendTetra(ni[0],ni[1],ni[2],ni[3]);
+ if(btetralinks)
+ {
+ psb->appendLink(ni[0],ni[1],0,true);
+ psb->appendLink(ni[1],ni[2],0,true);
+ psb->appendLink(ni[2],ni[0],0,true);
+ psb->appendLink(ni[0],ni[3],0,true);
+ psb->appendLink(ni[1],ni[3],0,true);
+ psb->appendLink(ni[2],ni[3],0,true);
+ }
+ }
+ }
+printf("Nodes: %u\r\n",psb->m_nodes.size());
+printf("Links: %u\r\n",psb->m_links.size());
+printf("Faces: %u\r\n",psb->m_faces.size());
+printf("Tetras: %u\r\n",psb->m_tetras.size());
+return(psb);
+}
+
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.h b/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.h
index 5eb2ebc0735..49b1f0bbce8 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.h
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodyHelpers.h
@@ -110,12 +110,34 @@ struct btSoftBodyHelpers
const btScalar* vertices,
const int* triangles,
int ntriangles,
- bool randomizeConstraints = true);
+ bool randomizeConstraints = true);
/* Create from convex-hull */
static btSoftBody* CreateFromConvexHull( btSoftBodyWorldInfo& worldInfo,
const btVector3* vertices,
int nvertices,
- bool randomizeConstraints = true);
+ bool randomizeConstraints = true);
+
+
+ /* Export TetGen compatible .smesh file */
+// static void ExportAsSMeshFile( btSoftBody* psb,
+// const char* filename);
+ /* Create from TetGen .ele, .face, .node files */
+// static btSoftBody* CreateFromTetGenFile( btSoftBodyWorldInfo& worldInfo,
+// const char* ele,
+// const char* face,
+// const char* node,
+// bool bfacelinks,
+// bool btetralinks,
+// bool bfacesfromtetras);
+ /* Create from TetGen .ele, .face, .node data */
+ static btSoftBody* CreateFromTetGenData( btSoftBodyWorldInfo& worldInfo,
+ const char* ele,
+ const char* face,
+ const char* node,
+ bool bfacelinks,
+ bool btetralinks,
+ bool bfacesfromtetras);
+
};
#endif //SOFT_BODY_HELPERS_H
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodyInternals.h b/extern/bullet2/src/BulletSoftBody/btSoftBodyInternals.h
index 5f0f7d54318..885571069d0 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftBodyInternals.h
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodyInternals.h
@@ -19,12 +19,13 @@ subject to the following restrictions:
#include "btSoftBody.h"
+
#include "LinearMath/btQuickprof.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btConvexInternalShape.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
-
+#include <string.h> //for memset
//
// btSymMatrix
//
@@ -124,11 +125,11 @@ public:
virtual btVector3 localGetSupportingVertex(const btVector3& vec) const
{
btSoftBody::Node* const * n=&m_cluster->m_nodes[0];
- btScalar d=dot(vec,n[0]->m_x);
+ btScalar d=btDot(vec,n[0]->m_x);
int j=0;
for(int i=1,ni=m_cluster->m_nodes.size();i<ni;++i)
{
- const btScalar k=dot(vec,n[i]->m_x);
+ const btScalar k=btDot(vec,n[i]->m_x);
if(k>d) { d=k;j=i; }
}
return(n[j]->m_x);
@@ -171,8 +172,7 @@ public:
template <typename T>
static inline void ZeroInitialize(T& value)
{
- static const T zerodummy;
- value=zerodummy;
+ memset(&value,0,sizeof(T));
}
//
template <typename T>
@@ -296,9 +296,9 @@ static inline btMatrix3x3 Mul(const btMatrix3x3& a,
//
static inline void Orthogonalize(btMatrix3x3& m)
{
- m[2]=cross(m[0],m[1]).normalized();
- m[1]=cross(m[2],m[0]).normalized();
- m[0]=cross(m[1],m[2]).normalized();
+ m[2]=btCross(m[0],m[1]).normalized();
+ m[1]=btCross(m[2],m[0]).normalized();
+ m[0]=btCross(m[1],m[2]).normalized();
}
//
static inline btMatrix3x3 MassMatrix(btScalar im,const btMatrix3x3& iwi,const btVector3& r)
@@ -335,7 +335,7 @@ static inline btMatrix3x3 AngularImpulseMatrix( const btMatrix3x3& iia,
static inline btVector3 ProjectOnAxis( const btVector3& v,
const btVector3& a)
{
- return(a*dot(v,a));
+ return(a*btDot(v,a));
}
//
static inline btVector3 ProjectOnPlane( const btVector3& v,
@@ -354,7 +354,7 @@ static inline void ProjectOrigin( const btVector3& a,
const btScalar m2=d.length2();
if(m2>SIMD_EPSILON)
{
- const btScalar t=Clamp<btScalar>(-dot(a,d)/m2,0,1);
+ const btScalar t=Clamp<btScalar>(-btDot(a,d)/m2,0,1);
const btVector3 p=a+d*t;
const btScalar l2=p.length2();
if(l2<sqd)
@@ -371,19 +371,19 @@ static inline void ProjectOrigin( const btVector3& a,
btVector3& prj,
btScalar& sqd)
{
- const btVector3& q=cross(b-a,c-a);
+ const btVector3& q=btCross(b-a,c-a);
const btScalar m2=q.length2();
if(m2>SIMD_EPSILON)
{
const btVector3 n=q/btSqrt(m2);
- const btScalar k=dot(a,n);
+ const btScalar k=btDot(a,n);
const btScalar k2=k*k;
if(k2<sqd)
{
const btVector3 p=n*k;
- if( (dot(cross(a-p,b-p),q)>0)&&
- (dot(cross(b-p,c-p),q)>0)&&
- (dot(cross(c-p,a-p),q)>0))
+ if( (btDot(btCross(a-p,b-p),q)>0)&&
+ (btDot(btCross(b-p,c-p),q)>0)&&
+ (btDot(btCross(c-p,a-p),q)>0))
{
prj=p;
sqd=k2;
@@ -413,9 +413,9 @@ static inline btVector3 BaryCoord( const btVector3& a,
const btVector3& c,
const btVector3& p)
{
- const btScalar w[]={ cross(a-p,b-p).length(),
- cross(b-p,c-p).length(),
- cross(c-p,a-p).length()};
+ const btScalar w[]={ btCross(a-p,b-p).length(),
+ btCross(b-p,c-p).length(),
+ btCross(c-p,a-p).length()};
const btScalar isum=1/(w[0]+w[1]+w[2]);
return(btVector3(w[1]*isum,w[2]*isum,w[0]*isum));
}
@@ -485,7 +485,7 @@ static inline btScalar AreaOf( const btVector3& x0,
{
const btVector3 a=x1-x0;
const btVector3 b=x2-x0;
- const btVector3 cr=cross(a,b);
+ const btVector3 cr=btCross(a,b);
const btScalar area=cr.length();
return(area);
}
@@ -499,7 +499,7 @@ static inline btScalar VolumeOf( const btVector3& x0,
const btVector3 a=x1-x0;
const btVector3 b=x2-x0;
const btVector3 c=x3-x0;
- return(dot(a,cross(b,c)));
+ return(btDot(a,btCross(b,c)));
}
//
@@ -512,7 +512,7 @@ static void EvaluateMedium( const btSoftBodyWorldInfo* wfi,
medium.m_density = wfi->air_density;
if(wfi->water_density>0)
{
- const btScalar depth=-(dot(x,wfi->water_normal)+wfi->water_offset);
+ const btScalar depth=-(btDot(x,wfi->water_normal)+wfi->water_offset);
if(depth>0)
{
medium.m_density = wfi->water_density;
@@ -654,14 +654,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 +669,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=dot(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 +696,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,10 +723,16 @@ struct btSoftColliders
{
btSoftBody::Cluster* cluster=(btSoftBody::Cluster*)leaf->data;
btSoftClusterCollisionShape cshape(cluster);
+
const btConvexShape* rshape=(const btConvexShape*)m_colObj->getCollisionShape();
+
+ ///don't collide an anchored cluster with a static/kinematic object
+ if(m_colObj->isStaticOrKinematicObject() && cluster->m_containsAnchor)
+ return;
+
btGjkEpaSolver2::sResults res;
if(btGjkEpaSolver2::SignedDistance( &cshape,btTransform::getIdentity(),
- rshape,m_colObj->getInterpolationWorldTransform(),
+ rshape,m_colObj->getWorldTransform(),
btVector3(1,0,0),res))
{
btSoftBody::CJoint joint;
@@ -743,16 +758,16 @@ 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;
btVector3 maxs;
ATTRIBUTE_ALIGNED16(btDbvtVolume) volume;
- colOb->getCollisionShape()->getAabb(colOb->getInterpolationWorldTransform(),mins,maxs);
+ colOb->getCollisionShape()->getAabb(colOb->getWorldTransform(),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 +818,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;
@@ -832,14 +848,14 @@ struct btSoftColliders
const btScalar ms=ima+imb;
if(ms>0)
{
- const btTransform& wtr=m_rigidBody?m_rigidBody->getInterpolationWorldTransform() : m_colObj1->getWorldTransform();
+ const btTransform& wtr=m_rigidBody?m_rigidBody->getWorldTransform() : m_colObj1->getWorldTransform();
static const btMatrix3x3 iwiStatic(0,0,0,0,0,0,0,0,0);
const btMatrix3x3& iwi=m_rigidBody?m_rigidBody->getInvInertiaTensorWorld() : iwiStatic;
const btVector3 ra=n.m_x-wtr.getOrigin();
const btVector3 va=m_rigidBody ? m_rigidBody->getVelocityInLocalPoint(ra)*psb->m_sst.sdt : btVector3(0,0,0);
const btVector3 vb=n.m_x-n.m_q;
const btVector3 vr=vb-va;
- const btScalar dn=dot(vr,c.m_cti.m_normal);
+ const btScalar dn=btDot(vr,c.m_cti.m_normal);
const btVector3 fv=vr-c.m_cti.m_normal*dn;
const btScalar fc=psb->m_cfg.kDF*m_colObj1->getFriction();
c.m_node = &n;
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h b/extern/bullet2/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h
new file mode 100644
index 00000000000..c4733d64000
--- /dev/null
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodySolverVertexBuffer.h
@@ -0,0 +1,165 @@
+/*
+Bullet Continuous Collision Detection and Physics Library
+Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
+
+This software is provided 'as-is', without any express or implied warranty.
+In no event will the authors be held liable for any damages arising from the use of this software.
+Permission is granted to anyone to use this software for any purpose,
+including commercial applications, and to alter it and redistribute it freely,
+subject to the following restrictions:
+
+1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
+2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
+3. This notice may not be removed or altered from any source distribution.
+*/
+
+#ifndef BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
+#define BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
+
+
+class btVertexBufferDescriptor
+{
+public:
+ enum BufferTypes
+ {
+ CPU_BUFFER,
+ DX11_BUFFER,
+ OPENGL_BUFFER
+ };
+
+protected:
+
+ bool m_hasVertexPositions;
+ bool m_hasNormals;
+
+ int m_vertexOffset;
+ int m_vertexStride;
+
+ int m_normalOffset;
+ int m_normalStride;
+
+public:
+ btVertexBufferDescriptor()
+ {
+ m_hasVertexPositions = false;
+ m_hasNormals = false;
+ m_vertexOffset = 0;
+ m_vertexStride = 0;
+ m_normalOffset = 0;
+ m_normalStride = 0;
+ }
+
+ virtual ~btVertexBufferDescriptor()
+ {
+
+ }
+
+ virtual bool hasVertexPositions() const
+ {
+ return m_hasVertexPositions;
+ }
+
+ virtual bool hasNormals() const
+ {
+ return m_hasNormals;
+ }
+
+ /**
+ * Return the type of the vertex buffer descriptor.
+ */
+ virtual BufferTypes getBufferType() const = 0;
+
+ /**
+ * Return the vertex offset in floats from the base pointer.
+ */
+ virtual int getVertexOffset() const
+ {
+ return m_vertexOffset;
+ }
+
+ /**
+ * Return the vertex stride in number of floats between vertices.
+ */
+ virtual int getVertexStride() const
+ {
+ return m_vertexStride;
+ }
+
+ /**
+ * Return the vertex offset in floats from the base pointer.
+ */
+ virtual int getNormalOffset() const
+ {
+ return m_normalOffset;
+ }
+
+ /**
+ * Return the vertex stride in number of floats between vertices.
+ */
+ virtual int getNormalStride() const
+ {
+ return m_normalStride;
+ }
+};
+
+
+class btCPUVertexBufferDescriptor : public btVertexBufferDescriptor
+{
+protected:
+ float *m_basePointer;
+
+public:
+ /**
+ * vertexBasePointer is pointer to beginning of the buffer.
+ * vertexOffset is the offset in floats to the first vertex.
+ * vertexStride is the stride in floats between vertices.
+ */
+ btCPUVertexBufferDescriptor( float *basePointer, int vertexOffset, int vertexStride )
+ {
+ m_basePointer = basePointer;
+ m_vertexOffset = vertexOffset;
+ m_vertexStride = vertexStride;
+ m_hasVertexPositions = true;
+ }
+
+ /**
+ * vertexBasePointer is pointer to beginning of the buffer.
+ * vertexOffset is the offset in floats to the first vertex.
+ * vertexStride is the stride in floats between vertices.
+ */
+ btCPUVertexBufferDescriptor( float *basePointer, int vertexOffset, int vertexStride, int normalOffset, int normalStride )
+ {
+ m_basePointer = basePointer;
+
+ m_vertexOffset = vertexOffset;
+ m_vertexStride = vertexStride;
+ m_hasVertexPositions = true;
+
+ m_normalOffset = normalOffset;
+ m_normalStride = normalStride;
+ m_hasNormals = true;
+ }
+
+ virtual ~btCPUVertexBufferDescriptor()
+ {
+
+ }
+
+ /**
+ * Return the type of the vertex buffer descriptor.
+ */
+ virtual BufferTypes getBufferType() const
+ {
+ return CPU_BUFFER;
+ }
+
+ /**
+ * Return the base pointer in memory to the first vertex.
+ */
+ virtual float *getBasePointer() const
+ {
+ return m_basePointer;
+ }
+};
+
+#endif // #ifndef BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftBodySolvers.h b/extern/bullet2/src/BulletSoftBody/btSoftBodySolvers.h
new file mode 100644
index 00000000000..440084c5f7b
--- /dev/null
+++ b/extern/bullet2/src/BulletSoftBody/btSoftBodySolvers.h
@@ -0,0 +1,154 @@
+/*
+Bullet Continuous Collision Detection and Physics Library
+Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
+
+This software is provided 'as-is', without any express or implied warranty.
+In no event will the authors be held liable for any damages arising from the use of this software.
+Permission is granted to anyone to use this software for any purpose,
+including commercial applications, and to alter it and redistribute it freely,
+subject to the following restrictions:
+
+1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
+2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
+3. This notice may not be removed or altered from any source distribution.
+*/
+
+#ifndef BT_SOFT_BODY_SOLVERS_H
+#define BT_SOFT_BODY_SOLVERS_H
+
+#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
+
+
+class btSoftBodyTriangleData;
+class btSoftBodyLinkData;
+class btSoftBodyVertexData;
+class btVertexBufferDescriptor;
+class btCollisionObject;
+class btSoftBody;
+
+
+class btSoftBodySolver
+{
+public:
+ enum SolverTypes
+ {
+ DEFAULT_SOLVER,
+ CPU_SOLVER,
+ CL_SOLVER,
+ CL_SIMD_SOLVER,
+ DX_SOLVER,
+ DX_SIMD_SOLVER
+ };
+
+
+protected:
+ int m_numberOfPositionIterations;
+ int m_numberOfVelocityIterations;
+ // Simulation timescale
+ float m_timeScale;
+
+public:
+ btSoftBodySolver() :
+ m_numberOfPositionIterations( 10 ),
+ m_timeScale( 1 )
+ {
+ m_numberOfVelocityIterations = 0;
+ m_numberOfPositionIterations = 5;
+ }
+
+ virtual ~btSoftBodySolver()
+ {
+ }
+
+ /**
+ * Return the type of the solver.
+ */
+ virtual SolverTypes getSolverType() const = 0;
+
+
+ /** Ensure that this solver is initialized. */
+ virtual bool checkInitialized() = 0;
+
+ /** Optimize soft bodies in this solver. */
+ virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate=false) = 0;
+
+ /** Copy necessary data back to the original soft body source objects. */
+ virtual void copyBackToSoftBodies() = 0;
+
+ /** Predict motion of soft bodies into next timestep */
+ virtual void predictMotion( float solverdt ) = 0;
+
+ /** Solve constraints for a set of soft bodies */
+ virtual void solveConstraints( float solverdt ) = 0;
+
+ /** Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes */
+ virtual void updateSoftBodies() = 0;
+
+ /** Process a collision between one of the world's soft bodies and another collision object */
+ virtual void processCollision( btSoftBody *, btCollisionObject* ) = 0;
+
+ /** Process a collision between two soft bodies */
+ virtual void processCollision( btSoftBody*, btSoftBody* ) = 0;
+
+ /** Set the number of velocity constraint solver iterations this solver uses. */
+ virtual void setNumberOfPositionIterations( int iterations )
+ {
+ m_numberOfPositionIterations = iterations;
+ }
+
+ /** Get the number of velocity constraint solver iterations this solver uses. */
+ virtual int getNumberOfPositionIterations()
+ {
+ return m_numberOfPositionIterations;
+ }
+
+ /** Set the number of velocity constraint solver iterations this solver uses. */
+ virtual void setNumberOfVelocityIterations( int iterations )
+ {
+ m_numberOfVelocityIterations = iterations;
+ }
+
+ /** Get the number of velocity constraint solver iterations this solver uses. */
+ virtual int getNumberOfVelocityIterations()
+ {
+ return m_numberOfVelocityIterations;
+ }
+
+ /** Return the timescale that the simulation is using */
+ float getTimeScale()
+ {
+ return m_timeScale;
+ }
+
+#if 0
+ /**
+ * Add a collision object to be used by the indicated softbody.
+ */
+ virtual void addCollisionObjectForSoftBody( int clothIdentifier, btCollisionObject *collisionObject ) = 0;
+#endif
+};
+
+/**
+ * Class to manage movement of data from a solver to a given target.
+ * This version is abstract. Subclasses will have custom pairings for different combinations.
+ */
+class btSoftBodySolverOutput
+{
+protected:
+
+public:
+ btSoftBodySolverOutput()
+ {
+ }
+
+ virtual ~btSoftBodySolverOutput()
+ {
+ }
+
+
+ /** Output current computed vertex data to the vertex buffers for all cloths in the solver. */
+ virtual void copySoftBodyToVertexBuffer( const btSoftBody * const softBody, btVertexBufferDescriptor *vertexBuffer ) = 0;
+};
+
+
+#endif // #ifndef BT_SOFT_BODY_SOLVERS_H
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp b/extern/bullet2/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp
index 11ad9e7daba..bc374c805e7 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp
+++ b/extern/bullet2/src/BulletSoftBody/btSoftRigidCollisionAlgorithm.cpp
@@ -19,6 +19,8 @@ subject to the following restrictions:
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "btSoftBody.h"
+#include "BulletSoftBody/btSoftBodySolvers.h"
+
///TODO: include all the shapes that the softbody can collide with
///alternatively, implement special case collision algorithms (just like for rigid collision shapes)
@@ -61,7 +63,7 @@ void btSoftRigidCollisionAlgorithm::processCollision (btCollisionObject* body0,b
if (softBody->m_collisionDisabledObjects.findLinearSearch(rigidCollisionObject)==softBody->m_collisionDisabledObjects.size())
{
- softBody->defaultCollisionHandler(rigidCollisionObject);
+ softBody->getSoftBodySolver()->processCollision(softBody, rigidCollisionObject);
}
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp b/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp
index 982ec3e5eb3..1b9b5e392a1 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp
+++ b/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.cpp
@@ -20,15 +20,28 @@ subject to the following restrictions:
//softbody & helpers
#include "btSoftBody.h"
#include "btSoftBodyHelpers.h"
-
-
-//#define USE_BRUTEFORCE_RAYBROADPHASE 1
-
-
-
-btSoftRigidDynamicsWorld::btSoftRigidDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration)
-:btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration)
+#include "btSoftBodySolvers.h"
+#include "btDefaultSoftBodySolver.h"
+#include "LinearMath/btSerializer.h"
+
+
+btSoftRigidDynamicsWorld::btSoftRigidDynamicsWorld(
+ btDispatcher* dispatcher,
+ btBroadphaseInterface* pairCache,
+ btConstraintSolver* constraintSolver,
+ btCollisionConfiguration* collisionConfiguration,
+ btSoftBodySolver *softBodySolver ) :
+ btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration),
+ m_softBodySolver( softBodySolver ),
+ m_ownsSolver(false)
{
+ if( !m_softBodySolver )
+ {
+ void* ptr = btAlignedAlloc(sizeof(btDefaultSoftBodySolver),16);
+ m_softBodySolver = new(ptr) btDefaultSoftBodySolver();
+ m_ownsSolver = true;
+ }
+
m_drawFlags = fDrawFlags::Std;
m_drawNodeTree = true;
m_drawFaceTree = false;
@@ -38,31 +51,50 @@ btSoftRigidDynamicsWorld::btSoftRigidDynamicsWorld(btDispatcher* dispatcher,btBr
m_sbi.m_sparsesdf.Initialize();
m_sbi.m_sparsesdf.Reset();
+ m_sbi.air_density = (btScalar)1.2;
+ m_sbi.water_density = 0;
+ m_sbi.water_offset = 0;
+ m_sbi.water_normal = btVector3(0,0,0);
+ m_sbi.m_gravity.setValue(0,-10,0);
+
+ m_sbi.m_sparsesdf.Initialize();
+
+
}
btSoftRigidDynamicsWorld::~btSoftRigidDynamicsWorld()
{
-
+ if (m_ownsSolver)
+ {
+ m_softBodySolver->~btSoftBodySolver();
+ btAlignedFree(m_softBodySolver);
+ }
}
void btSoftRigidDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
{
- btDiscreteDynamicsWorld::predictUnconstraintMotion( timeStep);
-
- for ( int i=0;i<m_softBodies.size();++i)
+ btDiscreteDynamicsWorld::predictUnconstraintMotion( timeStep );
{
- btSoftBody* psb= m_softBodies[i];
-
- psb->predictMotion(timeStep);
+ BT_PROFILE("predictUnconstraintMotionSoftBody");
+ m_softBodySolver->predictMotion( timeStep );
}
}
-void btSoftRigidDynamicsWorld::internalSingleStepSimulation( btScalar timeStep)
+void btSoftRigidDynamicsWorld::internalSingleStepSimulation( btScalar timeStep )
{
+
+ // Let the solver grab the soft bodies and if necessary optimize for it
+ m_softBodySolver->optimize( getSoftBodyArray() );
+
+ if( !m_softBodySolver->checkInitialized() )
+ {
+ btAssert( "Solver initialization failed\n" );
+ }
+
btDiscreteDynamicsWorld::internalSingleStepSimulation( timeStep );
///solve soft bodies constraints
- solveSoftBodiesConstraints();
+ solveSoftBodiesConstraints( timeStep );
//self collisions
for ( int i=0;i<m_softBodies.size();i++)
@@ -72,22 +104,14 @@ void btSoftRigidDynamicsWorld::internalSingleStepSimulation( btScalar timeStep)
}
///update soft bodies
- updateSoftBodies();
-
-}
-
-void btSoftRigidDynamicsWorld::updateSoftBodies()
-{
- BT_PROFILE("updateSoftBodies");
+ m_softBodySolver->updateSoftBodies( );
+
+ // End solver-wise simulation step
+ // ///////////////////////////////
- for ( int i=0;i<m_softBodies.size();i++)
- {
- btSoftBody* psb=(btSoftBody*)m_softBodies[i];
- psb->integrateMotion();
- }
}
-void btSoftRigidDynamicsWorld::solveSoftBodiesConstraints()
+void btSoftRigidDynamicsWorld::solveSoftBodiesConstraints( btScalar timeStep )
{
BT_PROFILE("solveSoftConstraints");
@@ -96,20 +120,22 @@ void btSoftRigidDynamicsWorld::solveSoftBodiesConstraints()
btSoftBody::solveClusters(m_softBodies);
}
- for(int i=0;i<m_softBodies.size();++i)
- {
- btSoftBody* psb=(btSoftBody*)m_softBodies[i];
- psb->solveConstraints();
- }
+ // Solve constraints solver-wise
+ m_softBodySolver->solveConstraints( timeStep * m_softBodySolver->getTimeScale() );
+
}
-void btSoftRigidDynamicsWorld::addSoftBody(btSoftBody* body)
+void btSoftRigidDynamicsWorld::addSoftBody(btSoftBody* body,short int collisionFilterGroup,short int collisionFilterMask)
{
m_softBodies.push_back(body);
+ // Set the soft body solver that will deal with this body
+ // to be the world's solver
+ body->setSoftBodySolver( m_softBodySolver );
+
btCollisionWorld::addCollisionObject(body,
- btBroadphaseProxy::DefaultFilter,
- btBroadphaseProxy::AllFilter);
+ collisionFilterGroup,
+ collisionFilterMask);
}
@@ -120,6 +146,15 @@ void btSoftRigidDynamicsWorld::removeSoftBody(btSoftBody* body)
btCollisionWorld::removeCollisionObject(body);
}
+void btSoftRigidDynamicsWorld::removeCollisionObject(btCollisionObject* collisionObject)
+{
+ btSoftBody* body = btSoftBody::upcast(collisionObject);
+ if (body)
+ removeSoftBody(body);
+ else
+ btDiscreteDynamicsWorld::removeCollisionObject(collisionObject);
+}
+
void btSoftRigidDynamicsWorld::debugDrawWorld()
{
btDiscreteDynamicsWorld::debugDrawWorld();
@@ -130,8 +165,12 @@ void btSoftRigidDynamicsWorld::debugDrawWorld()
for ( i=0;i<this->m_softBodies.size();i++)
{
btSoftBody* psb=(btSoftBody*)this->m_softBodies[i];
- btSoftBodyHelpers::DrawFrame(psb,m_debugDrawer);
- btSoftBodyHelpers::Draw(psb,m_debugDrawer,m_drawFlags);
+ if (getDebugDrawer() && getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe))
+ {
+ btSoftBodyHelpers::DrawFrame(psb,m_debugDrawer);
+ btSoftBodyHelpers::Draw(psb,m_debugDrawer,m_drawFlags);
+ }
+
if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb))
{
if(m_drawNodeTree) btSoftBodyHelpers::DrawNodeTree(psb,m_debugDrawer);
@@ -143,6 +182,8 @@ void btSoftRigidDynamicsWorld::debugDrawWorld()
}
+
+
struct btSoftSingleRayCallback : public btBroadphaseRayCallback
{
btVector3 m_rayFromWorld;
@@ -251,8 +292,10 @@ void btSoftRigidDynamicsWorld::rayTestSingle(const btTransform& rayFromTrans,con
btSoftBody::sRayCast softResult;
if (softBody->rayTest(rayFromTrans.getOrigin(), rayToTrans.getOrigin(), softResult))
{
- if (softResult.fraction<= resultCallback.m_closestHitFraction)
+
+ if (softResult.fraction<= resultCallback.m_closestHitFraction)
{
+
btCollisionWorld::LocalShapeInfo shapeInfo;
shapeInfo.m_shapePart = 0;
shapeInfo.m_triangleIndex = softResult.index;
@@ -260,14 +303,14 @@ void btSoftRigidDynamicsWorld::rayTestSingle(const btTransform& rayFromTrans,con
btVector3 normal = softBody->m_faces[softResult.index].m_normal;
btVector3 rayDir = rayToTrans.getOrigin() - rayFromTrans.getOrigin();
if (normal.dot(rayDir) > 0) {
- // normal must always point toward origin of the ray
+ // normal always point toward origin of the ray
normal = -normal;
}
btCollisionWorld::LocalRayResult rayResult
(collisionObject,
- &shapeInfo,
- normal,
- softResult.fraction);
+ &shapeInfo,
+ normal,
+ softResult.fraction);
bool normalInWorldSpace = true;
resultCallback.addSingleResult(rayResult,normalInWorldSpace);
}
@@ -278,3 +321,38 @@ void btSoftRigidDynamicsWorld::rayTestSingle(const btTransform& rayFromTrans,con
btCollisionWorld::rayTestSingle(rayFromTrans,rayToTrans,collisionObject,collisionShape,colObjWorldTransform,resultCallback);
}
}
+
+
+void btSoftRigidDynamicsWorld::serializeSoftBodies(btSerializer* serializer)
+{
+ int i;
+ //serialize all collision objects
+ for (i=0;i<m_collisionObjects.size();i++)
+ {
+ btCollisionObject* colObj = m_collisionObjects[i];
+ if (colObj->getInternalType() & btCollisionObject::CO_SOFT_BODY)
+ {
+ int len = colObj->calculateSerializeBufferSize();
+ btChunk* chunk = serializer->allocate(len,1);
+ const char* structType = colObj->serialize(chunk->m_oldPtr, serializer);
+ serializer->finalizeChunk(chunk,structType,BT_SOFTBODY_CODE,colObj);
+ }
+ }
+
+}
+
+void btSoftRigidDynamicsWorld::serialize(btSerializer* serializer)
+{
+
+ serializer->startSerialization();
+
+ serializeSoftBodies(serializer);
+
+ serializeRigidBodies(serializer);
+
+ serializeCollisionObjects(serializer);
+
+ serializer->finishSerialization();
+}
+
+
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.h b/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.h
index 14220ee7564..7d8d0cb7daa 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.h
+++ b/extern/bullet2/src/BulletSoftBody/btSoftRigidDynamicsWorld.h
@@ -21,6 +21,8 @@ subject to the following restrictions:
typedef btAlignedObjectArray<btSoftBody*> btSoftBodyArray;
+class btSoftBodySolver;
+
class btSoftRigidDynamicsWorld : public btDiscreteDynamicsWorld
{
@@ -30,6 +32,9 @@ class btSoftRigidDynamicsWorld : public btDiscreteDynamicsWorld
bool m_drawFaceTree;
bool m_drawClusterTree;
btSoftBodyWorldInfo m_sbi;
+ ///Solver classes that encapsulate multiple soft bodies for solving
+ btSoftBodySolver *m_softBodySolver;
+ bool m_ownsSolver;
protected:
@@ -37,23 +42,25 @@ protected:
virtual void internalSingleStepSimulation( btScalar timeStep);
- void updateSoftBodies();
-
- void solveSoftBodiesConstraints();
+ void solveSoftBodiesConstraints( btScalar timeStep );
+ void serializeSoftBodies(btSerializer* serializer);
public:
- btSoftRigidDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration);
+ btSoftRigidDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver = 0 );
virtual ~btSoftRigidDynamicsWorld();
virtual void debugDrawWorld();
- void addSoftBody(btSoftBody* body);
+ void addSoftBody(btSoftBody* body,short int collisionFilterGroup=btBroadphaseProxy::DefaultFilter,short int collisionFilterMask=btBroadphaseProxy::AllFilter);
void removeSoftBody(btSoftBody* body);
+ ///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btDiscreteDynamicsWorld::removeCollisionObject
+ virtual void removeCollisionObject(btCollisionObject* collisionObject);
+
int getDrawFlags() const { return(m_drawFlags); }
void setDrawFlags(int f) { m_drawFlags=f; }
@@ -77,6 +84,7 @@ public:
return m_softBodies;
}
+
virtual void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const;
/// rayTestSingle performs a raycast call and calls the resultCallback. It is used internally by rayTest.
@@ -88,6 +96,8 @@ public:
const btTransform& colObjWorldTransform,
RayResultCallback& resultCallback);
+ virtual void serialize(btSerializer* serializer);
+
};
#endif //BT_SOFT_RIGID_DYNAMICS_WORLD_H
diff --git a/extern/bullet2/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp b/extern/bullet2/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp
index 85a727944e0..1b8cfa72371 100644
--- a/extern/bullet2/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp
+++ b/extern/bullet2/src/BulletSoftBody/btSoftSoftCollisionAlgorithm.cpp
@@ -17,6 +17,7 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
+#include "BulletSoftBody/btSoftBodySolvers.h"
#include "btSoftBody.h"
#define USE_PERSISTENT_CONTACTS 1
@@ -36,7 +37,7 @@ void btSoftSoftCollisionAlgorithm::processCollision (btCollisionObject* body0,bt
{
btSoftBody* soft0 = (btSoftBody*)body0;
btSoftBody* soft1 = (btSoftBody*)body1;
- soft0->defaultCollisionHandler(soft1);
+ soft0->getSoftBodySolver()->processCollision(soft0, soft1);
}
btScalar btSoftSoftCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* /*body0*/,btCollisionObject* /*body1*/,const btDispatcherInfo& /*dispatchInfo*/,btManifoldResult* /*resultOut*/)