17 #ifndef _BT_SOFT_BODY_H    18 #define _BT_SOFT_BODY_H    34 #define btSoftBodyData  btSoftBodyFloatData    35 #define btSoftBodyDataName      "btSoftBodyFloatData"    59                 m_maxDisplacement(1000.f),
   349                 Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0) 
   350                 ,m_maxSelfCollisionImpulse(100.f),
   351                 m_selfCollisionImpulseFactor(0.01f),
   352                 m_containsAnchor(false)
   362                 Impulse() : m_velocity(0,0,0),m_drift(0,0,0),m_asVelocity(0),m_asDrift(0)       {}
   385                 Body() : m_soft(0),m_rigid(0),m_collisionObject(0)                              {}
   396                         if (m_collisionObject)
   404                         if(m_soft)      
return(m_soft->
m_invwi);
   410                         if(m_soft)      
return(m_soft->
m_imass);
   423                         if(m_soft)      
return(m_soft->
m_lv);
   435                         if(m_soft)      
return(m_soft->
m_av);
   440                         return(linearVelocity()+angularVelocity(rpos));
   462                                 applyDImpulse(impulse.
m_drift,rpos);
   512                 virtual void                            Prepare(
btScalar dt,
int iterations);
   514                 virtual void                            Terminate(
btScalar dt)=0;
   525                 void                                            Prepare(
btScalar dt,
int iterations);
   528                 eType::_                                        
Type()
 const { 
return(eType::Linear); }
   548                 void                                            Prepare(
btScalar dt,
int iterations);
   551                 eType::_                                        
Type()
 const { 
return(eType::Angular); }
   561                 void                                            Prepare(
btScalar dt,
int iterations);
   564                 eType::_                                        
Type()
 const { 
return(eType::Contact); }
   697         virtual ~btSoftBody();
   713         bool                            checkLink(      
int node0,
   715         bool                            checkLink(      
const Node* node0,
   716                 const Node* node1) 
const;
   718         bool                            checkFace(      
int node0,
   724         void                            appendNote(     
const char* text,
   731         void                            appendNote(     
const char* text,
   734         void                            appendNote(     
const char* text,
   737         void                            appendNote(     
const char* text,
   741         void                            appendNode(     
const btVector3& x,btScalar m);
   743         void                            appendLink(
int model=-1,
Material* mat=0);
   744         void                            appendLink(     
int node0,
   747                 bool bcheckexist=
false);
   748         void                            appendLink(     
Node* node0,
   751                 bool bcheckexist=
false);
   753         void                            appendFace(
int model=-1,
Material* mat=0);
   754         void                            appendFace(     
int node0,
   758         void                    appendTetra(
int model,
Material* mat);
   760         void                    appendTetra(
int node0,
   768         void                            appendAnchor(   
int node,
   769                 btRigidBody* body, 
bool disableCollisionBetweenLinkedBodies=
false,btScalar influence = 1);
   770         void                    appendAnchor(
int node,
btRigidBody* body, 
const btVector3& localPivot,
bool disableCollisionBetweenLinkedBodies=
false,btScalar influence = 1);
   774         void                            appendLinearJoint(
const LJoint::Specs& specs,btSoftBody* body);
   778         void                            appendAngularJoint(
const AJoint::Specs& specs,btSoftBody* body);
   785         void                        addAeroForceToNode(
const btVector3& windVelocity,
int nodeIndex);
   788         void                        addAeroForceToFace(
const btVector3& windVelocity,
int faceIndex);
   791         void                            addVelocity(    
const btVector3& velocity);
   794         void                            setVelocity(    
const btVector3& velocity);
   797         void                            addVelocity(    
const btVector3& velocity,
   800         void                            setMass(                
int node,
   803         btScalar                        getMass(                
int node) 
const;
   805         btScalar                        getTotalMass() 
const;
   807         void                            setTotalMass(   btScalar mass,
   808                 bool fromfaces=
false);
   810         void                            setTotalDensity(btScalar density);
   812         void                            setVolumeMass(          btScalar mass);
   814         void                            setVolumeDensity(       btScalar density);
   824         btScalar                        getRestLengthScale();
   826         void                            setRestLengthScale(btScalar restLength);
   828         void                            setPose(                
bool bvolume,
   831         void                            resetLinkRestLengths();
   833         btScalar                        getVolume() 
const;
   835         int                                     clusterCount() 
const;
   847         static void                     clusterAImpulse(
Cluster* cluster,
const Impulse& impulse);
   850         int                                     generateBendingConstraints(     
int distance,
   853         void                            randomizeConstraints();
   855         void                            releaseCluster(
int index);
   856         void                            releaseClusters();
   860         int                                     generateClusters(
int k,
int maxiterations=8192);
   862         void                            refine(
ImplicitFn* ifn,btScalar accurary,
bool cut);
   864         bool                            cutLink(
int node0,
int node1,btScalar position);
   865         bool                            cutLink(
const Node* node0,
const Node* node1,btScalar position);
   874         void                            predictMotion(btScalar dt);
   876         void                            solveConstraints();
   878         void                            staticSolve(
int iterations);
   880         static void                     solveCommonConstraints(btSoftBody** bodies,
int count,
int iterations);
   884         void                            integrateMotion();
   887         void                            defaultCollisionHandler(btSoftBody* psb);
   898         void setWindVelocity( 
const btVector3 &velocity );
   912                 m_softBodySolver = softBodySolver;
   920                 return m_softBodySolver;
   928                 return m_softBodySolver;
   939                         return (
const btSoftBody*)colObj;
   945                         return (btSoftBody*)colObj;
   955                 aabbMin = m_bounds[0];
   956                 aabbMax = m_bounds[1];
   961         void                            pointersToIndices();
   962         void                            indicesToPointers(
const int* map=0);
   965                 btScalar& mint,
eFeature::_& feature,
int& index,
bool bcountonly) 
const;
   966         void                            initializeFaceTree();
   969         void                            updateNormals();
   972         void                            updateConstants();
   973         void                            updateLinkConstants();
   974         void                            updateArea(
bool averageArea = 
true);
   975         void                            initializeClusters();
   976         void                            updateClusters();
   977         void                            cleanupClusters();
   978         void                            prepareClusters(
int iterations);
   979         void                            solveClusters(btScalar sor);
   980         void                            applyClusters(
bool drift);
   983         static void                     PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti);
   984         static void                     PSolve_RContacts(btSoftBody* psb,btScalar kst,btScalar ti);
   985         static void                     PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti);
   986         static void                     PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti);
   987         static void                     VSolve_Links(btSoftBody* psb,btScalar kst);
   992         virtual int     calculateSerializeBufferSize()  
const;
   995         virtual const char*     serialize(
void* dataBuffer,  
class btSerializer* serializer) 
const;
  1005 #endif //_BT_SOFT_BODY_H 
btScalar getInvMass() const 
const btCollisionObject * m_colObj
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don't store a rigidbody pointer but a rigidbody ...
Impulse operator*(btScalar x) const 
eFeature::_ feature
soft body 
btAlignedObjectArray< Link > tLinkArray
Vertex normals are oriented toward velocity. 
btScalar m_maxDisplacement
btVector3 linearVelocity() const 
void applyTorqueImpulse(const btVector3 &torque)
btAlignedObjectArray< ePSolver::_ > tPSolverArray
btVector3 angularVelocity() const 
Vertex normals are flipped to match velocity. 
btScalar m_restLengthScale
tVector3Array m_framerefs
btAlignedObjectArray< btVector3 > tVector3Array
Body(const btCollisionObject *colObj)
int getInternalType() const 
reserved for Bullet internal usage 
btAlignedObjectArray< bool > m_clusterConnectivity
static int split(btDbvtNode **leaves, int count, const btVector3 &org, const btVector3 &axis)
btAlignedObjectArray< Cluster * > tClusterArray
btVector3 angularVelocity(const btVector3 &rpos) const 
btAlignedObjectArray< Node * > m_nodes
btAlignedObjectArray< btScalar > tScalarArray
static void clusterVImpulse(Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse)
btDispatcher * m_dispatcher
The btDbvt class implements a fast dynamic bounding volume tree based on axis aligned bounding boxes ...
The btCollisionShape class provides an interface for collision shapes that can be shared among btColl...
btScalar fraction
feature index 
virtual btScalar Speed(AJoint *, btScalar current)
const btMatrix3x3 & invWorldInertia() const 
tSContactArray m_scontacts
btAlignedObjectArray< Face > tFaceArray
btAlignedObjectArray< RContact > tRContactArray
btAlignedObjectArray< int > m_userIndexMapping
static IControl * Default()
btAlignedObjectArray< Tetra > tTetraArray
const btTransform & xform() const 
Vertex normals are taken as it is. 
btTransform m_initialWorldTransform
static btSoftBody * upcast(btCollisionObject *colObj)
btAlignedObjectArray< btDbvtNode * > tLeafArray
btSoftBodyWorldInfo * m_worldInfo
virtual void getAabb(btVector3 &aabbMin, btVector3 &aabbMax) const 
btSparseSdf< 3 > m_sparsesdf
btVector3 btCross(const btVector3 &v1, const btVector3 &v2)
Return the cross product of two vectors. 
virtual void setCollisionShape(btCollisionShape *collisionShape)
btTransform & getWorldTransform()
void applyDImpulse(const btVector3 &impulse, const btVector3 &rpos) const 
btSoftBodyWorldInfo * getWorldInfo()
Vertex normals are flipped to match velocity and lift and drag forces are applied. 
btAlignedObjectArray< Material * > tMaterialArray
tMaterialArray m_materials
static void clusterDImpulse(Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse)
btSoftBodySolver * getSoftBodySolver() const 
static const btSoftBody * upcast(const btCollisionObject *colObj)
const btCollisionObject * m_collisionObject
RayFromToCaster takes a ray from, ray to (instead of direction!) 
eVSolver : velocities solvers 
btSoftBodySolver * getSoftBodySolver()
const btVector3 & getAngularVelocity() const 
btCollisionObject can be used to manage collision detection objects. 
static void clusterVAImpulse(Cluster *cluster, const btVector3 &impulse)
The btRigidBody is the main class for rigid body objects. 
tPSolverArray m_dsequence
The btBroadphaseInterface class provides an interface to detect aabb-overlapping object pairs...
btScalar m_maxSelfCollisionImpulse
void activate(bool forceActivation=false) const 
btVector3 can be used to represent 3D points and vectors. 
#define ATTRIBUTE_ALIGNED16(a)
btAlignedObjectArray< Note > tNoteArray
void applyVImpulse(const btVector3 &impulse, const btVector3 &rpos) const 
btAlignedObjectArray< btSoftBody * > tSoftBodyArray
btAlignedObjectArray< SContact > tSContactArray
ePSolver : positions solvers 
btMatrix3x3 operator-(const btMatrix3x3 &m1, const btMatrix3x3 &m2)
btAlignedObjectArray< Joint * > tJointArray
virtual void Prepare(AJoint *)
Face normals are flipped to match velocity. 
void applyDCImpulse(const btVector3 &impulse) const 
Face normals are flipped to match velocity and lift and drag forces are applied. 
#define BT_DECLARE_ALIGNED_ALLOCATOR()
void setSoftBodySolver(btSoftBodySolver *softBodySolver)
void applyVAImpulse(const btVector3 &impulse) const 
const btMatrix3x3 & getInvInertiaTensorWorld() const 
void applyCentralImpulse(const btVector3 &impulse)
tVSolverArray m_vsequence
void applyImpulse(const Impulse &impulse, const btVector3 &rpos) const 
tPSolverArray m_psequence
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
const btVector3 & getLinearVelocity() const 
btBroadphaseInterface * m_broadphase
void applyImpulse(const btVector3 &impulse, const btVector3 &rel_pos)
btSoftBodySolver * m_softBodySolver
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
btAlignedObjectArray< const class btCollisionObject * > m_collisionDisabledObjects
btScalar m_selfCollisionImpulseFactor
The btSoftBody is an class to simulate cloth and volumetric soft bodies. 
btAlignedObjectArray< Node > tNodeArray
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
static void clusterDCImpulse(Cluster *cluster, const btVector3 &impulse)
void applyAImpulse(const Impulse &impulse) const 
void applyDAImpulse(const btVector3 &impulse) const 
tRContactArray m_rcontacts
btAlignedObjectArray< Anchor > tAnchorArray
btVector3 m_rayNormalizedDirection
btAlignedObjectArray< eVSolver::_ > tVSolverArray
btVector3 velocity(const btVector3 &rpos) const 
static void clusterDAImpulse(Cluster *cluster, const btVector3 &impulse)
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...