Applied polar decomposition patch. Fixes Issue 621. Thanks to Christian for the report, Joshua for the fix, Dongsoo for checking the fix.
Applied picking cloth patch. Fixes Issue 646. Thanks to Dongsoo. Applied patch Softbody updateConstraints. Fixes Issue 503. Thanks to Dave Bruce Phillips and Dongsoo. Fix various warnigns under Mac OSX.
This commit is contained in:
@@ -501,7 +501,7 @@ void btCollisionWorld::rayTestSingleInternal(const btTransform& rayFromTrans,con
|
||||
|
||||
}
|
||||
|
||||
void Process(int i)
|
||||
void ProcessLeaf(int i)
|
||||
{
|
||||
const btCollisionShape* childCollisionShape = m_compoundShape->getChildShape(i);
|
||||
const btTransform& childTrans = m_compoundShape->getChildTransform(i);
|
||||
@@ -521,10 +521,10 @@ void btCollisionWorld::rayTestSingleInternal(const btTransform& rayFromTrans,con
|
||||
my_cb);
|
||||
|
||||
}
|
||||
|
||||
|
||||
void Process(const btDbvtNode* leaf)
|
||||
{
|
||||
Process(leaf->dataAsInt);
|
||||
ProcessLeaf(leaf->dataAsInt);
|
||||
}
|
||||
};
|
||||
|
||||
@@ -551,7 +551,7 @@ void btCollisionWorld::rayTestSingleInternal(const btTransform& rayFromTrans,con
|
||||
{
|
||||
for (int i = 0, n = compoundShape->getNumChildShapes(); i < n; ++i)
|
||||
{
|
||||
rayCB.Process(i);
|
||||
rayCB.ProcessLeaf(i);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -40,10 +40,10 @@ public:
|
||||
|
||||
struct CreateFunc :public btCollisionAlgorithmCreateFunc
|
||||
{
|
||||
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, btCollisionObject* body0,btCollisionObject* body1)
|
||||
{
|
||||
(void)body0;
|
||||
(void)body1;
|
||||
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
|
||||
{
|
||||
(void)body0Wrap;
|
||||
(void)body1Wrap;
|
||||
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(btEmptyAlgorithm));
|
||||
return new(mem) btEmptyAlgorithm(ci);
|
||||
}
|
||||
|
||||
@@ -639,7 +639,7 @@ public:
|
||||
{
|
||||
if(indicestype == PHY_SHORT)
|
||||
{
|
||||
short * s_indices = (short *)(indexbase + face_index*indexstride);
|
||||
unsigned short * s_indices = (unsigned short *)(indexbase + face_index*indexstride);
|
||||
i0 = s_indices[0];
|
||||
i1 = s_indices[1];
|
||||
i2 = s_indices[2];
|
||||
|
||||
@@ -449,6 +449,7 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject&
|
||||
{
|
||||
//body has already been converted
|
||||
solverBodyIdA = body.getCompanionId();
|
||||
btAssert(solverBodyIdA < m_tmpSolverBodyPool.size());
|
||||
} else
|
||||
{
|
||||
btRigidBody* rb = btRigidBody::upcast(&body);
|
||||
@@ -1085,7 +1086,14 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration
|
||||
{
|
||||
for (int j=0;j<numConstraints;j++)
|
||||
{
|
||||
constraints[j]->solveConstraintObsolete(constraints[j]->getRigidBodyA(),constraints[j]->getRigidBodyB(),infoGlobal.m_timeStep);
|
||||
if (constraints[j]->isEnabled())
|
||||
{
|
||||
int bodyAid = getOrInitSolverBody(constraints[j]->getRigidBodyA());
|
||||
int bodyBid = getOrInitSolverBody(constraints[j]->getRigidBodyB());
|
||||
btSolverBody& bodyA = m_tmpSolverBodyPool[bodyAid];
|
||||
btSolverBody& bodyB = m_tmpSolverBodyPool[bodyBid];
|
||||
constraints[j]->solveConstraintObsolete(bodyA,bodyB,infoGlobal.m_timeStep);
|
||||
}
|
||||
}
|
||||
|
||||
///solve all contact constraints using SIMD, if available
|
||||
@@ -1181,7 +1189,14 @@ btScalar btSequentialImpulseConstraintSolver::solveSingleIteration(int iteration
|
||||
{
|
||||
for (int j=0;j<numConstraints;j++)
|
||||
{
|
||||
constraints[j]->solveConstraintObsolete(constraints[j]->getRigidBodyA(),constraints[j]->getRigidBodyB(),infoGlobal.m_timeStep);
|
||||
if (constraints[j]->isEnabled())
|
||||
{
|
||||
int bodyAid = getOrInitSolverBody(constraints[j]->getRigidBodyA());
|
||||
int bodyBid = getOrInitSolverBody(constraints[j]->getRigidBodyB());
|
||||
btSolverBody& bodyA = m_tmpSolverBodyPool[bodyAid];
|
||||
btSolverBody& bodyB = m_tmpSolverBodyPool[bodyBid];
|
||||
constraints[j]->solveConstraintObsolete(bodyA,bodyB,infoGlobal.m_timeStep);
|
||||
}
|
||||
}
|
||||
///solve all contact constraints
|
||||
int numPoolConstraints = m_tmpSolverContactConstraintPool.size();
|
||||
|
||||
@@ -198,7 +198,7 @@ public:
|
||||
|
||||
|
||||
///internal method used by the constraint solver, don't use them directly
|
||||
virtual void solveConstraintObsolete(btRigidBody& /*bodyA*/,btRigidBody& /*bodyB*/,btScalar /*timeStep*/) {};
|
||||
virtual void solveConstraintObsolete(btSolverBody& /*bodyA*/,btSolverBody& /*bodyB*/,btScalar /*timeStep*/) {};
|
||||
|
||||
|
||||
const btRigidBody& getRigidBodyA() const
|
||||
|
||||
@@ -981,7 +981,7 @@ void btOpenCLSoftBodySolver::updateSoftBodies()
|
||||
|
||||
|
||||
int numVertices = m_vertexData.getNumVertices();
|
||||
int numTriangles = m_triangleData.getNumTriangles();
|
||||
// int numTriangles = m_triangleData.getNumTriangles();
|
||||
|
||||
// Ensure data is on accelerator
|
||||
m_vertexData.moveToAccelerator();
|
||||
@@ -1240,8 +1240,8 @@ void btOpenCLSoftBodySolver::solveConstraints( float solverdt )
|
||||
using Vectormath::Aos::dot;
|
||||
|
||||
// Prepare links
|
||||
int numLinks = m_linkData.getNumLinks();
|
||||
int numVertices = m_vertexData.getNumVertices();
|
||||
// int numLinks = m_linkData.getNumLinks();
|
||||
// int numVertices = m_vertexData.getNumVertices();
|
||||
|
||||
float kst = 1.f;
|
||||
float ti = 0.f;
|
||||
|
||||
@@ -34,7 +34,7 @@ btScalar SpuContactManifoldCollisionAlgorithm::calculateTimeOfImpact(btCollision
|
||||
}
|
||||
|
||||
#ifndef __SPU__
|
||||
SpuContactManifoldCollisionAlgorithm::SpuContactManifoldCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci,btCollisionObject* body0,btCollisionObject* body1)
|
||||
SpuContactManifoldCollisionAlgorithm::SpuContactManifoldCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObject* body0,const btCollisionObject* body1)
|
||||
:btCollisionAlgorithm(ci)
|
||||
#ifdef USE_SEPDISTANCE_UTIL
|
||||
,m_sepDistance(body0->getCollisionShape()->getAngularMotionDisc(),body1->getCollisionShape()->getAngularMotionDisc())
|
||||
|
||||
@@ -21,6 +21,7 @@ subject to the following restrictions:
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
|
||||
#include "LinearMath/btTransformUtil.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
|
||||
|
||||
class btPersistentManifold;
|
||||
|
||||
@@ -37,8 +38,8 @@ ATTRIBUTE_ALIGNED16(class) SpuContactManifoldCollisionAlgorithm : public btColli
|
||||
float m_collisionMargin0;
|
||||
float m_collisionMargin1;
|
||||
|
||||
btCollisionObject* m_collisionObject0;
|
||||
btCollisionObject* m_collisionObject1;
|
||||
const btCollisionObject* m_collisionObject0;
|
||||
const btCollisionObject* m_collisionObject1;
|
||||
|
||||
|
||||
|
||||
@@ -50,7 +51,7 @@ public:
|
||||
virtual btScalar calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
|
||||
|
||||
|
||||
SpuContactManifoldCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci,btCollisionObject* body0,btCollisionObject* body1);
|
||||
SpuContactManifoldCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObject* body0,const btCollisionObject* body1);
|
||||
#ifdef USE_SEPDISTANCE_UTIL
|
||||
btConvexSeparatingDistanceUtil m_sepDistance;
|
||||
#endif //USE_SEPDISTANCE_UTIL
|
||||
@@ -68,12 +69,12 @@ public:
|
||||
return m_manifoldPtr;
|
||||
}
|
||||
|
||||
btCollisionObject* getCollisionObject0()
|
||||
const btCollisionObject* getCollisionObject0()
|
||||
{
|
||||
return m_collisionObject0;
|
||||
}
|
||||
|
||||
btCollisionObject* getCollisionObject1()
|
||||
const btCollisionObject* getCollisionObject1()
|
||||
{
|
||||
return m_collisionObject1;
|
||||
}
|
||||
@@ -108,10 +109,10 @@ public:
|
||||
|
||||
struct CreateFunc :public btCollisionAlgorithmCreateFunc
|
||||
{
|
||||
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, btCollisionObject* body0,btCollisionObject* body1)
|
||||
{
|
||||
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
|
||||
{
|
||||
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(SpuContactManifoldCollisionAlgorithm));
|
||||
return new(mem) SpuContactManifoldCollisionAlgorithm(ci,body0,body1);
|
||||
return new(mem) SpuContactManifoldCollisionAlgorithm(ci,body0Wrap->getCollisionObject(),body1Wrap->getCollisionObject());
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
@@ -393,7 +393,7 @@ void btGpu3DGridBroadphase::addLarge2LargePairsToCache(btDispatcher* dispatcher)
|
||||
|
||||
|
||||
|
||||
void btGpu3DGridBroadphase::rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback)
|
||||
void btGpu3DGridBroadphase::rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback,const btVector3& aabbMin,const btVector3& aabbMax)
|
||||
{
|
||||
btSimpleBroadphase::rayTest(rayFrom, rayTo, rayCallback);
|
||||
for (int i=0; i <= m_LastLargeHandleIndex; i++)
|
||||
|
||||
@@ -103,7 +103,9 @@ public:
|
||||
|
||||
virtual btBroadphaseProxy* createProxy(const btVector3& aabbMin, const btVector3& aabbMax,int shapeType,void* userPtr ,short int collisionFilterGroup,short int collisionFilterMask, btDispatcher* dispatcher,void* multiSapProxy);
|
||||
virtual void destroyProxy(btBroadphaseProxy* proxy,btDispatcher* dispatcher);
|
||||
virtual void rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback);
|
||||
virtual void rayTest(const btVector3& rayFrom,const btVector3& rayTo, btBroadphaseRayCallback& rayCallback, const btVector3& aabbMin=btVector3(0,0,0),const btVector3& aabbMax=btVector3(0,0,0));
|
||||
|
||||
|
||||
virtual void resetPool(btDispatcher* dispatcher);
|
||||
|
||||
protected:
|
||||
|
||||
@@ -1271,7 +1271,7 @@ btScalar btParallelConstraintSolver::solveGroup(btCollisionObject** bodies1,int
|
||||
|
||||
PfxBroadphasePair& pair = m_memoryCache->m_mypairs[actualNumManifolds];
|
||||
//init those
|
||||
float compFric = obA->getFriction()*obB->getFriction();//@todo
|
||||
// float compFric = obA->getFriction()*obB->getFriction();//@todo
|
||||
int idA = obA->getCompanionId();
|
||||
int idB = obB->getCompanionId();
|
||||
|
||||
@@ -1291,7 +1291,6 @@ btScalar btParallelConstraintSolver::solveGroup(btCollisionObject** bodies1,int
|
||||
}
|
||||
|
||||
|
||||
numPosPoints = numPosPoints;
|
||||
totalPoints+=numPosPoints;
|
||||
pfxSetRigidBodyIdA(pair,idA);
|
||||
pfxSetRigidBodyIdB(pair,idB);
|
||||
|
||||
@@ -110,7 +110,7 @@ void btSoftBody::initDefaults()
|
||||
m_initialWorldTransform.setIdentity();
|
||||
|
||||
m_windVelocity = btVector3(0,0,0);
|
||||
|
||||
m_restLengthScale = btScalar(1.0);
|
||||
}
|
||||
|
||||
//
|
||||
@@ -505,6 +505,18 @@ void btSoftBody::addAeroForceToNode(const btVector3& windVelocity,int nodeInde
|
||||
if ( 0 < n_dot_v && n_dot_v < 0.98480f)
|
||||
fLift = 0.5f * kLF * medium.m_density * rel_v_len * tri_area * btSqrt(1.0f-n_dot_v*n_dot_v) * (nrm.cross(rel_v_nrm).cross(rel_v_nrm));
|
||||
|
||||
// Check if the velocity change resulted by aero drag force exceeds the current velocity of the node.
|
||||
btVector3 del_v_by_fDrag = fDrag*n.m_im*m_sst.sdt;
|
||||
btScalar del_v_by_fDrag_len2 = del_v_by_fDrag.length2();
|
||||
btScalar v_len2 = n.m_v.length2();
|
||||
|
||||
if (del_v_by_fDrag_len2 >= v_len2 && del_v_by_fDrag_len2 > 0)
|
||||
{
|
||||
btScalar del_v_by_fDrag_len = del_v_by_fDrag.length();
|
||||
btScalar v_len = n.m_v.length();
|
||||
fDrag *= 0.8*(v_len / del_v_by_fDrag_len);
|
||||
}
|
||||
|
||||
n.m_f += fDrag;
|
||||
n.m_f += fLift;
|
||||
}
|
||||
@@ -535,8 +547,8 @@ void btSoftBody::addAeroForceToFace(const btVector3& windVelocity,int faceInde
|
||||
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 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_aero = as_lift || as_drag;
|
||||
@@ -586,6 +598,18 @@ void btSoftBody::addAeroForceToFace(const btVector3& windVelocity,int faceInde
|
||||
{
|
||||
if (f.m_n[j]->m_im>0)
|
||||
{
|
||||
// Check if the velocity change resulted by aero drag force exceeds the current velocity of the node.
|
||||
btVector3 del_v_by_fDrag = fDrag*f.m_n[j]->m_im*m_sst.sdt;
|
||||
btScalar del_v_by_fDrag_len2 = del_v_by_fDrag.length2();
|
||||
btScalar v_len2 = f.m_n[j]->m_v.length2();
|
||||
|
||||
if (del_v_by_fDrag_len2 >= v_len2 && del_v_by_fDrag_len2 > 0)
|
||||
{
|
||||
btScalar del_v_by_fDrag_len = del_v_by_fDrag.length();
|
||||
btScalar v_len = f.m_n[j]->m_v.length();
|
||||
fDrag *= 0.8*(v_len / del_v_by_fDrag_len);
|
||||
}
|
||||
|
||||
f.m_n[j]->m_f += fDrag;
|
||||
f.m_n[j]->m_f += fLift;
|
||||
}
|
||||
@@ -816,6 +840,27 @@ void btSoftBody::scale(const btVector3& scl)
|
||||
updateConstants();
|
||||
}
|
||||
|
||||
//
|
||||
btScalar btSoftBody::getRestLengthScale()
|
||||
{
|
||||
return m_restLengthScale;
|
||||
}
|
||||
|
||||
//
|
||||
void btSoftBody::setRestLengthScale(btScalar restLengthScale)
|
||||
{
|
||||
for(int i=0, ni=m_links.size(); i<ni; ++i)
|
||||
{
|
||||
Link& l=m_links[i];
|
||||
l.m_rl = l.m_rl / m_restLengthScale * restLengthScale;
|
||||
l.m_c1 = l.m_rl*l.m_rl;
|
||||
}
|
||||
m_restLengthScale = restLengthScale;
|
||||
|
||||
if (getActivationState() == ISLAND_SLEEPING);
|
||||
activate();
|
||||
}
|
||||
|
||||
//
|
||||
void btSoftBody::setPose(bool bvolume,bool bframe)
|
||||
{
|
||||
@@ -863,9 +908,20 @@ void btSoftBody::setPose(bool bvolume,bool bframe)
|
||||
m_pose.m_aqq[2]+=mq.z()*q;
|
||||
}
|
||||
m_pose.m_aqq=m_pose.m_aqq.inverse();
|
||||
|
||||
updateConstants();
|
||||
}
|
||||
|
||||
void btSoftBody::resetLinkRestLengths()
|
||||
{
|
||||
for(int i=0, ni=m_links.size();i<ni;++i)
|
||||
{
|
||||
Link& l = m_links[i];
|
||||
l.m_rl = (l.m_n[0]->m_x-l.m_n[1]->m_x).length();
|
||||
l.m_c1 = l.m_rl*l.m_rl;
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
btScalar btSoftBody::getVolume() const
|
||||
{
|
||||
@@ -1587,7 +1643,7 @@ bool btSoftBody::cutLink(int node0,int node1,btScalar position)
|
||||
{
|
||||
bool done=false;
|
||||
int i,ni;
|
||||
const btVector3 d=m_nodes[node0].m_x-m_nodes[node1].m_x;
|
||||
// const btVector3 d=m_nodes[node0].m_x-m_nodes[node1].m_x;
|
||||
const btVector3 x=Lerp(m_nodes[node0].m_x,m_nodes[node1].m_x,position);
|
||||
const btVector3 v=Lerp(m_nodes[node0].m_v,m_nodes[node1].m_v,position);
|
||||
const btScalar m=1;
|
||||
@@ -2178,7 +2234,7 @@ bool btSoftBody::checkContact( const btCollisionObjectWrapper* colObjWrap,
|
||||
{
|
||||
btVector3 nrm;
|
||||
const btCollisionShape *shp = colObjWrap->getCollisionShape();
|
||||
const btRigidBody *tmpRigid = btRigidBody::upcast(colObjWrap->getCollisionObject());
|
||||
// const btRigidBody *tmpRigid = btRigidBody::upcast(colObjWrap->getCollisionObject());
|
||||
//const btTransform &wtr = tmpRigid ? tmpRigid->getWorldTransform() : colObjWrap->getWorldTransform();
|
||||
const btTransform &wtr = colObjWrap->getWorldTransform();
|
||||
//todo: check which transform is needed here
|
||||
@@ -2307,51 +2363,93 @@ void btSoftBody::updatePose()
|
||||
}
|
||||
|
||||
//
|
||||
void btSoftBody::updateConstants()
|
||||
void btSoftBody::updateArea(bool averageArea)
|
||||
{
|
||||
int i,ni;
|
||||
|
||||
/* Face area */
|
||||
for(i=0,ni=m_faces.size();i<ni;++i)
|
||||
{
|
||||
Face& f=m_faces[i];
|
||||
f.m_ra = AreaOf(f.m_n[0]->m_x,f.m_n[1]->m_x,f.m_n[2]->m_x);
|
||||
}
|
||||
|
||||
/* Node area */
|
||||
|
||||
if (averageArea)
|
||||
{
|
||||
btAlignedObjectArray<int> counts;
|
||||
counts.resize(m_nodes.size(),0);
|
||||
for(i=0,ni=m_nodes.size();i<ni;++i)
|
||||
{
|
||||
m_nodes[i].m_area = 0;
|
||||
}
|
||||
for(i=0,ni=m_faces.size();i<ni;++i)
|
||||
{
|
||||
btSoftBody::Face& f=m_faces[i];
|
||||
for(int j=0;j<3;++j)
|
||||
{
|
||||
const int index=(int)(f.m_n[j]-&m_nodes[0]);
|
||||
counts[index]++;
|
||||
f.m_n[j]->m_area+=btFabs(f.m_ra);
|
||||
}
|
||||
}
|
||||
for(i=0,ni=m_nodes.size();i<ni;++i)
|
||||
{
|
||||
if(counts[i]>0)
|
||||
m_nodes[i].m_area/=(btScalar)counts[i];
|
||||
else
|
||||
m_nodes[i].m_area=0;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// initialize node area as zero
|
||||
for(i=0,ni=m_nodes.size();i<ni;++i)
|
||||
{
|
||||
m_nodes[i].m_area=0;
|
||||
}
|
||||
|
||||
for(i=0,ni=m_faces.size();i<ni;++i)
|
||||
{
|
||||
btSoftBody::Face& f=m_faces[i];
|
||||
|
||||
for(int j=0;j<3;++j)
|
||||
{
|
||||
f.m_n[j]->m_area += f.m_ra;
|
||||
}
|
||||
}
|
||||
|
||||
for(i=0,ni=m_nodes.size();i<ni;++i)
|
||||
{
|
||||
m_nodes[i].m_area *= 0.3333333f;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void btSoftBody::updateLinkConstants()
|
||||
{
|
||||
int i,ni;
|
||||
|
||||
/* Links */
|
||||
for(i=0,ni=m_links.size();i<ni;++i)
|
||||
{
|
||||
Link& l=m_links[i];
|
||||
Material& m=*l.m_material;
|
||||
l.m_rl = (l.m_n[0]->m_x-l.m_n[1]->m_x).length();
|
||||
l.m_c0 = (l.m_n[0]->m_im+l.m_n[1]->m_im)/m.m_kLST;
|
||||
l.m_c1 = l.m_rl*l.m_rl;
|
||||
}
|
||||
/* Faces */
|
||||
for(i=0,ni=m_faces.size();i<ni;++i)
|
||||
{
|
||||
Face& f=m_faces[i];
|
||||
f.m_ra = AreaOf(f.m_n[0]->m_x,f.m_n[1]->m_x,f.m_n[2]->m_x);
|
||||
}
|
||||
/* Area's */
|
||||
btAlignedObjectArray<int> counts;
|
||||
counts.resize(m_nodes.size(),0);
|
||||
for(i=0,ni=m_nodes.size();i<ni;++i)
|
||||
{
|
||||
m_nodes[i].m_area = 0;
|
||||
}
|
||||
for(i=0,ni=m_faces.size();i<ni;++i)
|
||||
{
|
||||
btSoftBody::Face& f=m_faces[i];
|
||||
for(int j=0;j<3;++j)
|
||||
{
|
||||
const int index=(int)(f.m_n[j]-&m_nodes[0]);
|
||||
counts[index]++;
|
||||
f.m_n[j]->m_area+=btFabs(f.m_ra);
|
||||
}
|
||||
}
|
||||
for(i=0,ni=m_nodes.size();i<ni;++i)
|
||||
{
|
||||
if(counts[i]>0)
|
||||
m_nodes[i].m_area/=(btScalar)counts[i];
|
||||
else
|
||||
m_nodes[i].m_area=0;
|
||||
}
|
||||
}
|
||||
|
||||
void btSoftBody::updateConstants()
|
||||
{
|
||||
resetLinkRestLengths();
|
||||
updateLinkConstants();
|
||||
updateArea();
|
||||
}
|
||||
|
||||
|
||||
|
||||
//
|
||||
void btSoftBody::initializeClusters()
|
||||
{
|
||||
@@ -2820,7 +2918,7 @@ void btSoftBody::applyForces()
|
||||
{
|
||||
|
||||
BT_PROFILE("SoftBody applyForces");
|
||||
const btScalar dt = m_sst.sdt;
|
||||
// const btScalar dt = m_sst.sdt;
|
||||
const btScalar kLF = m_cfg.kLF;
|
||||
const btScalar kDG = m_cfg.kDG;
|
||||
const btScalar kPR = m_cfg.kPR;
|
||||
@@ -2831,10 +2929,10 @@ void btSoftBody::applyForces()
|
||||
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 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 ;
|
||||
@@ -2877,7 +2975,7 @@ void btSoftBody::applyForces()
|
||||
/* Per face forces */
|
||||
for(i=0,ni=m_faces.size();i<ni;++i)
|
||||
{
|
||||
btSoftBody::Face& f=m_faces[i];
|
||||
// btSoftBody::Face& f=m_faces[i];
|
||||
|
||||
/* Aerodynamics */
|
||||
addAeroForceToFace(m_windVelocity, i);
|
||||
@@ -3068,7 +3166,7 @@ void btSoftBody::defaultCollisionHandler(const btCollisionObjectWrapper* pcoWr
|
||||
case fCollision::CL_RS:
|
||||
{
|
||||
btSoftColliders::CollideCL_RS collider;
|
||||
collider.Process(this,pcoWrap);
|
||||
collider.ProcessColObj(this,pcoWrap);
|
||||
}
|
||||
break;
|
||||
}
|
||||
@@ -3087,7 +3185,7 @@ void btSoftBody::defaultCollisionHandler(btSoftBody* psb)
|
||||
if (this!=psb || psb->m_cfg.collisions&fCollision::CL_SELF)
|
||||
{
|
||||
btSoftColliders::CollideCL_SS docollide;
|
||||
docollide.Process(this,psb);
|
||||
docollide.ProcessSoftSoft(this,psb);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -671,6 +671,9 @@ public:
|
||||
btTransform m_initialWorldTransform;
|
||||
|
||||
btVector3 m_windVelocity;
|
||||
|
||||
btScalar m_restLengthScale;
|
||||
|
||||
//
|
||||
// Api
|
||||
//
|
||||
@@ -810,9 +813,15 @@ public:
|
||||
void rotate( const btQuaternion& rot);
|
||||
/* Scale */
|
||||
void scale( const btVector3& scl);
|
||||
/* Get link resting lengths scale */
|
||||
btScalar getRestLengthScale();
|
||||
/* Scale resting length of all springs */
|
||||
void setRestLengthScale(btScalar restLength);
|
||||
/* Set current state as pose */
|
||||
void setPose( bool bvolume,
|
||||
bool bframe);
|
||||
/* Set current link lengths as resting lengths */
|
||||
void resetLinkRestLengths();
|
||||
/* Return the volume */
|
||||
btScalar getVolume() const;
|
||||
/* Cluster count */
|
||||
@@ -954,6 +963,8 @@ public:
|
||||
void updateBounds();
|
||||
void updatePose();
|
||||
void updateConstants();
|
||||
void updateLinkConstants();
|
||||
void updateArea(bool averageArea = true);
|
||||
void initializeClusters();
|
||||
void updateClusters();
|
||||
void cleanupClusters();
|
||||
|
||||
@@ -21,6 +21,7 @@ subject to the following restrictions:
|
||||
|
||||
|
||||
#include "LinearMath/btQuickprof.h"
|
||||
#include "LinearMath/btPolarDecomposition.h"
|
||||
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
|
||||
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
|
||||
#include "BulletCollision/CollisionShapes/btConvexInternalShape.h"
|
||||
@@ -614,32 +615,8 @@ private:
|
||||
//
|
||||
static inline int PolarDecompose( const btMatrix3x3& m,btMatrix3x3& q,btMatrix3x3& s)
|
||||
{
|
||||
static const btScalar half=(btScalar)0.5;
|
||||
static const btScalar accuracy=(btScalar)0.0001;
|
||||
static const int maxiterations=16;
|
||||
int i=0;
|
||||
btScalar det=0;
|
||||
q = Mul(m,1/btVector3(m[0][0],m[1][1],m[2][2]).length());
|
||||
det = q.determinant();
|
||||
if(!btFuzzyZero(det))
|
||||
{
|
||||
for(;i<maxiterations;++i)
|
||||
{
|
||||
q=Mul(Add(q,Mul(q.adjoint(),1/det).transpose()),half);
|
||||
const btScalar ndet=q.determinant();
|
||||
if(Sq(ndet-det)>accuracy) det=ndet; else break;
|
||||
}
|
||||
/* Final orthogonalization */
|
||||
Orthogonalize(q);
|
||||
/* Compute 'S' */
|
||||
s=q.transpose()*m;
|
||||
}
|
||||
else
|
||||
{
|
||||
q.setIdentity();
|
||||
s.setIdentity();
|
||||
}
|
||||
return(i);
|
||||
static const btPolarDecomposition polar;
|
||||
return polar.decompose(m, q, s);
|
||||
}
|
||||
|
||||
//
|
||||
@@ -753,7 +730,7 @@ struct btSoftColliders
|
||||
}
|
||||
}
|
||||
}
|
||||
void Process(btSoftBody* ps,const btCollisionObjectWrapper* colObWrap)
|
||||
void ProcessColObj(btSoftBody* ps,const btCollisionObjectWrapper* colObWrap)
|
||||
{
|
||||
psb = ps;
|
||||
m_colObjWrap = colObWrap;
|
||||
@@ -815,7 +792,7 @@ struct btSoftColliders
|
||||
|
||||
}
|
||||
}
|
||||
void Process(btSoftBody* psa,btSoftBody* psb)
|
||||
void ProcessSoftSoft(btSoftBody* psa,btSoftBody* psb)
|
||||
{
|
||||
idt = psa->m_sst.isdt;
|
||||
//m_margin = (psa->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin())/2;
|
||||
|
||||
@@ -58,8 +58,8 @@ void btSoftRigidCollisionAlgorithm::processCollision (const btCollisionObjectWra
|
||||
(void)dispatchInfo;
|
||||
(void)resultOut;
|
||||
//printf("btSoftRigidCollisionAlgorithm\n");
|
||||
const btCollisionObjectWrapper* softWrap = m_isSwapped?body1Wrap:body0Wrap;
|
||||
const btCollisionObjectWrapper* rigidWrap = m_isSwapped?body0Wrap:body1Wrap;
|
||||
// const btCollisionObjectWrapper* softWrap = m_isSwapped?body1Wrap:body0Wrap;
|
||||
// const btCollisionObjectWrapper* rigidWrap = m_isSwapped?body0Wrap:body1Wrap;
|
||||
btSoftBody* softBody = m_isSwapped? (btSoftBody*)body1Wrap->getCollisionObject() : (btSoftBody*)body0Wrap->getCollisionObject();
|
||||
const btCollisionObjectWrapper* rigidCollisionObjectWrap = m_isSwapped? body0Wrap : body1Wrap;
|
||||
|
||||
|
||||
@@ -8,6 +8,7 @@ SET(LinearMath_SRCS
|
||||
btConvexHull.cpp
|
||||
btConvexHullComputer.cpp
|
||||
btGeometryUtil.cpp
|
||||
btPolarDecomposition.cpp
|
||||
btQuickprof.cpp
|
||||
btSerializer.cpp
|
||||
btVector3.cpp
|
||||
@@ -28,6 +29,7 @@ SET(LinearMath_HDRS
|
||||
btMatrix3x3.h
|
||||
btMinMax.h
|
||||
btMotionState.h
|
||||
btPolarDecomposition.h
|
||||
btPoolAllocator.h
|
||||
btQuadWord.h
|
||||
btQuaternion.h
|
||||
|
||||
@@ -280,6 +280,7 @@ class btIDebugDraw
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
virtual void drawBox(const btVector3& bbMin, const btVector3& bbMax, const btVector3& color)
|
||||
{
|
||||
drawLine(btVector3(bbMin[0], bbMin[1], bbMin[2]), btVector3(bbMax[0], bbMin[1], bbMin[2]), color);
|
||||
|
||||
99
src/LinearMath/btPolarDecomposition.cpp
Normal file
99
src/LinearMath/btPolarDecomposition.cpp
Normal file
@@ -0,0 +1,99 @@
|
||||
#include "btPolarDecomposition.h"
|
||||
#include "btMinMax.h"
|
||||
|
||||
namespace
|
||||
{
|
||||
btScalar abs_column_sum(const btMatrix3x3& a, int i)
|
||||
{
|
||||
return btFabs(a[0][i]) + btFabs(a[1][i]) + btFabs(a[2][i]);
|
||||
}
|
||||
|
||||
btScalar abs_row_sum(const btMatrix3x3& a, int i)
|
||||
{
|
||||
return btFabs(a[i][0]) + btFabs(a[i][1]) + btFabs(a[i][2]);
|
||||
}
|
||||
|
||||
btScalar p1_norm(const btMatrix3x3& a)
|
||||
{
|
||||
const btScalar sum0 = abs_column_sum(a,0);
|
||||
const btScalar sum1 = abs_column_sum(a,1);
|
||||
const btScalar sum2 = abs_column_sum(a,2);
|
||||
return btMax(btMax(sum0, sum1), sum2);
|
||||
}
|
||||
|
||||
btScalar pinf_norm(const btMatrix3x3& a)
|
||||
{
|
||||
const btScalar sum0 = abs_row_sum(a,0);
|
||||
const btScalar sum1 = abs_row_sum(a,1);
|
||||
const btScalar sum2 = abs_row_sum(a,2);
|
||||
return btMax(btMax(sum0, sum1), sum2);
|
||||
}
|
||||
}
|
||||
|
||||
const btScalar btPolarDecomposition::DEFAULT_TOLERANCE = btScalar(0.0001);
|
||||
const unsigned int btPolarDecomposition::DEFAULT_MAX_ITERATIONS = 16;
|
||||
|
||||
btPolarDecomposition::btPolarDecomposition(btScalar tolerance, unsigned int maxIterations)
|
||||
: m_tolerance(tolerance)
|
||||
, m_maxIterations(maxIterations)
|
||||
{
|
||||
}
|
||||
|
||||
unsigned int btPolarDecomposition::decompose(const btMatrix3x3& a, btMatrix3x3& u, btMatrix3x3& h) const
|
||||
{
|
||||
// Use the 'u' and 'h' matrices for intermediate calculations
|
||||
u = a;
|
||||
h = a.inverse();
|
||||
|
||||
for (unsigned int i = 0; i < m_maxIterations; ++i)
|
||||
{
|
||||
const btScalar h_1 = p1_norm(h);
|
||||
const btScalar h_inf = pinf_norm(h);
|
||||
const btScalar u_1 = p1_norm(u);
|
||||
const btScalar u_inf = pinf_norm(u);
|
||||
|
||||
const btScalar h_norm = h_1 * h_inf;
|
||||
const btScalar u_norm = u_1 * u_inf;
|
||||
|
||||
// The matrix is effectively singular so we cannot invert it
|
||||
if (btFuzzyZero(h_norm) || btFuzzyZero(u_norm))
|
||||
break;
|
||||
|
||||
const btScalar gamma = btPow(h_norm / u_norm, 0.25f);
|
||||
const btScalar inv_gamma = 1.0 / gamma;
|
||||
|
||||
// Determine the delta to 'u'
|
||||
const btMatrix3x3 delta = (u * (gamma - 2.0) + h.transpose() * inv_gamma) * 0.5;
|
||||
|
||||
// Update the matrices
|
||||
u += delta;
|
||||
h = u.inverse();
|
||||
|
||||
// Check for convergence
|
||||
if (p1_norm(delta) <= m_tolerance * u_1)
|
||||
{
|
||||
h = u.transpose() * a;
|
||||
h = (h + h.transpose()) * 0.5;
|
||||
return i;
|
||||
}
|
||||
}
|
||||
|
||||
// The algorithm has failed to converge to the specified tolerance, but we
|
||||
// want to make sure that the matrices returned are in the right form.
|
||||
h = u.transpose() * a;
|
||||
h = (h + h.transpose()) * 0.5;
|
||||
|
||||
return m_maxIterations;
|
||||
}
|
||||
|
||||
unsigned int btPolarDecomposition::maxIterations() const
|
||||
{
|
||||
return m_maxIterations;
|
||||
}
|
||||
|
||||
unsigned int polarDecompose(const btMatrix3x3& a, btMatrix3x3& u, btMatrix3x3& h)
|
||||
{
|
||||
static btPolarDecomposition polar;
|
||||
return polar.decompose(a, u, h);
|
||||
}
|
||||
|
||||
73
src/LinearMath/btPolarDecomposition.h
Normal file
73
src/LinearMath/btPolarDecomposition.h
Normal file
@@ -0,0 +1,73 @@
|
||||
#ifndef POLARDECOMPOSITION_H
|
||||
#define POLARDECOMPOSITION_H
|
||||
|
||||
#include "btMatrix3x3.h"
|
||||
|
||||
/**
|
||||
* This class is used to compute the polar decomposition of a matrix. In
|
||||
* general, the polar decomposition factorizes a matrix, A, into two parts: a
|
||||
* unitary matrix (U) and a positive, semi-definite Hermitian matrix (H).
|
||||
* However, in this particular implementation the original matrix, A, is
|
||||
* required to be a square 3x3 matrix with real elements. This means that U will
|
||||
* be an orthogonal matrix and H with be a positive-definite, symmetric matrix.
|
||||
*/
|
||||
class btPolarDecomposition
|
||||
{
|
||||
public:
|
||||
static const btScalar DEFAULT_TOLERANCE;
|
||||
static const unsigned int DEFAULT_MAX_ITERATIONS;
|
||||
|
||||
/**
|
||||
* Creates an instance with optional parameters.
|
||||
*
|
||||
* @param tolerance - the tolerance used to determine convergence of the
|
||||
* algorithm
|
||||
* @param maxIterations - the maximum number of iterations used to achieve
|
||||
* convergence
|
||||
*/
|
||||
btPolarDecomposition(btScalar tolerance = DEFAULT_TOLERANCE,
|
||||
unsigned int maxIterations = DEFAULT_MAX_ITERATIONS);
|
||||
|
||||
/**
|
||||
* Decomposes a matrix into orthogonal and symmetric, positive-definite
|
||||
* parts. If the number of iterations returned by this function is equal to
|
||||
* the maximum number of iterations, the algorithm has failed to converge.
|
||||
*
|
||||
* @param a - the original matrix
|
||||
* @param u - the resulting orthogonal matrix
|
||||
* @param h - the resulting symmetric matrix
|
||||
*
|
||||
* @return the number of iterations performed by the algorithm.
|
||||
*/
|
||||
unsigned int decompose(const btMatrix3x3& a, btMatrix3x3& u, btMatrix3x3& h) const;
|
||||
|
||||
/**
|
||||
* Returns the maximum number of iterations that this algorithm will perform
|
||||
* to achieve convergence.
|
||||
*
|
||||
* @return maximum number of iterations
|
||||
*/
|
||||
unsigned int maxIterations() const;
|
||||
|
||||
private:
|
||||
btScalar m_tolerance;
|
||||
unsigned int m_maxIterations;
|
||||
};
|
||||
|
||||
/**
|
||||
* This functions decomposes the matrix 'a' into two parts: an orthogonal matrix
|
||||
* 'u' and a symmetric, positive-definite matrix 'h'. If the number of
|
||||
* iterations returned by this function is equal to
|
||||
* btPolarDecomposition::DEFAULT_MAX_ITERATIONS, the algorithm has failed to
|
||||
* converge.
|
||||
*
|
||||
* @param a - the original matrix
|
||||
* @param u - the resulting orthogonal matrix
|
||||
* @param h - the resulting symmetric matrix
|
||||
*
|
||||
* @return the number of iterations performed by the algorithm.
|
||||
*/
|
||||
unsigned int polarDecompose(const btMatrix3x3& a, btMatrix3x3& u, btMatrix3x3& h);
|
||||
|
||||
#endif // POLARDECOMPOSITION_H
|
||||
|
||||
@@ -95,6 +95,7 @@ libLinearMath_la_SOURCES = \
|
||||
LinearMath/btAlignedAllocator.cpp \
|
||||
LinearMath/btSerializer.cpp \
|
||||
LinearMath/btConvexHull.cpp \
|
||||
LinearMath/btPolarDecomposition.cpp \
|
||||
LinearMath/btVector3.cpp \
|
||||
LinearMath/btConvexHullComputer.cpp \
|
||||
LinearMath/btHashMap.h \
|
||||
@@ -103,6 +104,7 @@ libLinearMath_la_SOURCES = \
|
||||
LinearMath/btGeometryUtil.h \
|
||||
LinearMath/btQuadWord.h \
|
||||
LinearMath/btPoolAllocator.h \
|
||||
LinearMath/btPolarDecomposition.h \
|
||||
LinearMath/btScalar.h \
|
||||
LinearMath/btMinMax.h \
|
||||
LinearMath/btVector3.h \
|
||||
@@ -538,6 +540,7 @@ nobase_bullet_include_HEADERS += \
|
||||
LinearMath/btMatrix3x3.h \
|
||||
LinearMath/btVector3.h \
|
||||
LinearMath/btPoolAllocator.h \
|
||||
LinearMath/btPolarDecomposition.h \
|
||||
LinearMath/btScalar.h \
|
||||
LinearMath/btDefaultMotionState.h \
|
||||
LinearMath/btTransform.h \
|
||||
|
||||
@@ -128,7 +128,7 @@ CL_API_ENTRY cl_int CL_API_CALL clGetDeviceInfo(
|
||||
sprintf((char*)param_value,"%s",cpuName);
|
||||
} else
|
||||
{
|
||||
printf("error: param_value_size should be at least %d, but it is %d\n",nameLen,param_value_size);
|
||||
printf("error: param_value_size should be at least %d, but it is %zu\n",nameLen,param_value_size);
|
||||
return CL_INVALID_VALUE;
|
||||
}
|
||||
break;
|
||||
@@ -141,7 +141,7 @@ CL_API_ENTRY cl_int CL_API_CALL clGetDeviceInfo(
|
||||
*deviceType = CL_DEVICE_TYPE_CPU;
|
||||
} else
|
||||
{
|
||||
printf("error: param_value_size should be at least %d\n",sizeof(cl_device_type));
|
||||
printf("error: param_value_size should be at least %zu\n",sizeof(cl_device_type));
|
||||
return CL_INVALID_VALUE;
|
||||
}
|
||||
break;
|
||||
@@ -154,7 +154,7 @@ CL_API_ENTRY cl_int CL_API_CALL clGetDeviceInfo(
|
||||
*numUnits= 4;
|
||||
} else
|
||||
{
|
||||
printf("error: param_value_size should be at least %d\n",sizeof(cl_uint));
|
||||
printf("error: param_value_size should be at least %zu\n",sizeof(cl_uint));
|
||||
return CL_INVALID_VALUE;
|
||||
}
|
||||
|
||||
@@ -172,7 +172,7 @@ CL_API_ENTRY cl_int CL_API_CALL clGetDeviceInfo(
|
||||
workItemSize[2] = 16;
|
||||
} else
|
||||
{
|
||||
printf("error: param_value_size should be at least %d\n",sizeof(cl_uint));
|
||||
printf("error: param_value_size should be at least %zu\n",sizeof(cl_uint));
|
||||
return CL_INVALID_VALUE;
|
||||
}
|
||||
break;
|
||||
|
||||
@@ -28,7 +28,7 @@ subject to the following restrictions:
|
||||
#define get_local_size(a) (gMiniCLNumOutstandingTasks)
|
||||
#define get_group_id(a) ((__guid_arg) / gMiniCLNumOutstandingTasks)
|
||||
|
||||
static unsigned int as_uint(float val) { return *((unsigned int*)&val); }
|
||||
//static unsigned int as_uint(float val) { return *((unsigned int*)&val); }
|
||||
|
||||
|
||||
#define CLK_LOCAL_MEM_FENCE 0x01
|
||||
|
||||
Reference in New Issue
Block a user