00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00016
00017 #ifndef _BT_SOFT_BODY_H
00018 #define _BT_SOFT_BODY_H
00019
00020 #include "LinearMath/btAlignedObjectArray.h"
00021 #include "LinearMath/btTransform.h"
00022 #include "LinearMath/btIDebugDraw.h"
00023 #include "BulletDynamics/Dynamics/btRigidBody.h"
00024
00025 #include "BulletCollision/CollisionShapes/btConcaveShape.h"
00026 #include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
00027 #include "btSparseSDF.h"
00028 #include "BulletCollision/BroadphaseCollision/btDbvt.h"
00029
00030 class btBroadphaseInterface;
00031 class btDispatcher;
00032
00033
00034 struct btSoftBodyWorldInfo
00035 {
00036 btScalar air_density;
00037 btScalar water_density;
00038 btScalar water_offset;
00039 btVector3 water_normal;
00040 btBroadphaseInterface* m_broadphase;
00041 btDispatcher* m_dispatcher;
00042 btVector3 m_gravity;
00043 btSparseSdf<3> m_sparsesdf;
00044 };
00045
00046
00049 class btSoftBody : public btCollisionObject
00050 {
00051 public:
00052 btAlignedObjectArray<class btCollisionObject*> m_collisionDisabledObjects;
00053
00054
00055
00056
00057
00059 struct eAeroModel { enum _ {
00060 V_Point,
00061 V_TwoSided,
00062 V_OneSided,
00063 F_TwoSided,
00064 F_OneSided,
00065 END
00066 };};
00067
00069 struct eVSolver { enum _ {
00070 Linear,
00071 END
00072 };};
00073
00075 struct ePSolver { enum _ {
00076 Linear,
00077 Anchors,
00078 RContacts,
00079 SContacts,
00080 END
00081 };};
00082
00084 struct eSolverPresets { enum _ {
00085 Positions,
00086 Velocities,
00087 Default = Positions,
00088 END
00089 };};
00090
00092 struct eFeature { enum _ {
00093 None,
00094 Node,
00095 Link,
00096 Face,
00097 END
00098 };};
00099
00100 typedef btAlignedObjectArray<eVSolver::_> tVSolverArray;
00101 typedef btAlignedObjectArray<ePSolver::_> tPSolverArray;
00102
00103
00104
00105
00106
00108 struct fCollision { enum _ {
00109 RVSmask = 0x000f,
00110 SDF_RS = 0x0001,
00111 CL_RS = 0x0002,
00112
00113 SVSmask = 0x0030,
00114 VF_SS = 0x0010,
00115 CL_SS = 0x0020,
00116 CL_SELF = 0x0040,
00117
00118 Default = SDF_RS,
00119 END
00120 };};
00121
00123 struct fMaterial { enum _ {
00124 DebugDraw = 0x0001,
00125
00126 Default = DebugDraw,
00127 END
00128 };};
00129
00130
00131
00132
00133
00134
00135 struct sRayCast
00136 {
00137 btSoftBody* body;
00138 eFeature::_ feature;
00139 int index;
00140 btScalar fraction;
00141 };
00142
00143
00144 struct ImplicitFn
00145 {
00146 virtual btScalar Eval(const btVector3& x)=0;
00147 };
00148
00149
00150
00151
00152
00153 typedef btAlignedObjectArray<btScalar> tScalarArray;
00154 typedef btAlignedObjectArray<btVector3> tVector3Array;
00155
00156
00157 struct sCti
00158 {
00159 btCollisionObject* m_colObj;
00160 btVector3 m_normal;
00161 btScalar m_offset;
00162 };
00163
00164
00165 struct sMedium
00166 {
00167 btVector3 m_velocity;
00168 btScalar m_pressure;
00169 btScalar m_density;
00170 };
00171
00172
00173 struct Element
00174 {
00175 void* m_tag;
00176 Element() : m_tag(0) {}
00177 };
00178
00179 struct Material : Element
00180 {
00181 btScalar m_kLST;
00182 btScalar m_kAST;
00183 btScalar m_kVST;
00184 int m_flags;
00185 };
00186
00187
00188 struct Feature : Element
00189 {
00190 Material* m_material;
00191 };
00192
00193 struct Node : Feature
00194 {
00195 btVector3 m_x;
00196 btVector3 m_q;
00197 btVector3 m_v;
00198 btVector3 m_f;
00199 btVector3 m_n;
00200 btScalar m_im;
00201 btScalar m_area;
00202 btDbvtNode* m_leaf;
00203 int m_battach:1;
00204 };
00205
00206 struct Link : Feature
00207 {
00208 Node* m_n[2];
00209 btScalar m_rl;
00210 int m_bbending:1;
00211 btScalar m_c0;
00212 btScalar m_c1;
00213 btScalar m_c2;
00214 btVector3 m_c3;
00215 };
00216
00217 struct Face : Feature
00218 {
00219 Node* m_n[3];
00220 btVector3 m_normal;
00221 btScalar m_ra;
00222 btDbvtNode* m_leaf;
00223 };
00224
00225 struct Tetra : Feature
00226 {
00227 Node* m_n[4];
00228 btScalar m_rv;
00229 btDbvtNode* m_leaf;
00230 btVector3 m_c0[4];
00231 btScalar m_c1;
00232 btScalar m_c2;
00233 };
00234
00235 struct RContact
00236 {
00237 sCti m_cti;
00238 Node* m_node;
00239 btMatrix3x3 m_c0;
00240 btVector3 m_c1;
00241 btScalar m_c2;
00242 btScalar m_c3;
00243 btScalar m_c4;
00244 };
00245
00246 struct SContact
00247 {
00248 Node* m_node;
00249 Face* m_face;
00250 btVector3 m_weights;
00251 btVector3 m_normal;
00252 btScalar m_margin;
00253 btScalar m_friction;
00254 btScalar m_cfm[2];
00255 };
00256
00257 struct Anchor
00258 {
00259 Node* m_node;
00260 btVector3 m_local;
00261 btRigidBody* m_body;
00262 btMatrix3x3 m_c0;
00263 btVector3 m_c1;
00264 btScalar m_c2;
00265 };
00266
00267 struct Note : Element
00268 {
00269 const char* m_text;
00270 btVector3 m_offset;
00271 int m_rank;
00272 Node* m_nodes[4];
00273 btScalar m_coords[4];
00274 };
00275
00276 struct Pose
00277 {
00278 bool m_bvolume;
00279 bool m_bframe;
00280 btScalar m_volume;
00281 tVector3Array m_pos;
00282 tScalarArray m_wgh;
00283 btVector3 m_com;
00284 btMatrix3x3 m_rot;
00285 btMatrix3x3 m_scl;
00286 btMatrix3x3 m_aqq;
00287 };
00288
00289 struct Cluster
00290 {
00291 btAlignedObjectArray<Node*> m_nodes;
00292 tScalarArray m_masses;
00293 tVector3Array m_framerefs;
00294 btTransform m_framexform;
00295 btScalar m_idmass;
00296 btScalar m_imass;
00297 btMatrix3x3 m_locii;
00298 btMatrix3x3 m_invwi;
00299 btVector3 m_com;
00300 btVector3 m_vimpulses[2];
00301 btVector3 m_dimpulses[2];
00302 int m_nvimpulses;
00303 int m_ndimpulses;
00304 btVector3 m_lv;
00305 btVector3 m_av;
00306 btDbvtNode* m_leaf;
00307 btScalar m_ndamping;
00308 btScalar m_ldamping;
00309 btScalar m_adamping;
00310 btScalar m_matching;
00311 btScalar m_maxSelfCollisionImpulse;
00312 btScalar m_selfCollisionImpulseFactor;
00313 bool m_containsAnchor;
00314 bool m_collide;
00315 int m_clusterIndex;
00316 Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0)
00317 ,m_maxSelfCollisionImpulse(100.f),
00318 m_selfCollisionImpulseFactor(0.01f),
00319 m_containsAnchor(false)
00320 {}
00321 };
00322
00323 struct Impulse
00324 {
00325 btVector3 m_velocity;
00326 btVector3 m_drift;
00327 int m_asVelocity:1;
00328 int m_asDrift:1;
00329 Impulse() : m_velocity(0,0,0),m_drift(0,0,0),m_asVelocity(0),m_asDrift(0) {}
00330 Impulse operator -() const
00331 {
00332 Impulse i=*this;
00333 i.m_velocity=-i.m_velocity;
00334 i.m_drift=-i.m_drift;
00335 return(i);
00336 }
00337 Impulse operator*(btScalar x) const
00338 {
00339 Impulse i=*this;
00340 i.m_velocity*=x;
00341 i.m_drift*=x;
00342 return(i);
00343 }
00344 };
00345
00346 struct Body
00347 {
00348 Cluster* m_soft;
00349 btRigidBody* m_rigid;
00350 btCollisionObject* m_collisionObject;
00351
00352 Body() : m_soft(0),m_rigid(0),m_collisionObject(0) {}
00353 Body(Cluster* p) : m_soft(p),m_rigid(0),m_collisionObject(0) {}
00354 Body(btCollisionObject* colObj) : m_soft(0),m_collisionObject(colObj)
00355 {
00356 m_rigid = btRigidBody::upcast(m_collisionObject);
00357 }
00358
00359 void activate() const
00360 {
00361 if(m_rigid) m_rigid->activate();
00362 }
00363 const btMatrix3x3& invWorldInertia() const
00364 {
00365 static const btMatrix3x3 iwi(0,0,0,0,0,0,0,0,0);
00366 if(m_rigid) return(m_rigid->getInvInertiaTensorWorld());
00367 if(m_soft) return(m_soft->m_invwi);
00368 return(iwi);
00369 }
00370 btScalar invMass() const
00371 {
00372 if(m_rigid) return(m_rigid->getInvMass());
00373 if(m_soft) return(m_soft->m_imass);
00374 return(0);
00375 }
00376 const btTransform& xform() const
00377 {
00378 static const btTransform identity=btTransform::getIdentity();
00379 if(m_collisionObject) return(m_collisionObject->getInterpolationWorldTransform());
00380 if(m_soft) return(m_soft->m_framexform);
00381 return(identity);
00382 }
00383 btVector3 linearVelocity() const
00384 {
00385 if(m_rigid) return(m_rigid->getLinearVelocity());
00386 if(m_soft) return(m_soft->m_lv);
00387 return(btVector3(0,0,0));
00388 }
00389 btVector3 angularVelocity(const btVector3& rpos) const
00390 {
00391 if(m_rigid) return(btCross(m_rigid->getAngularVelocity(),rpos));
00392 if(m_soft) return(btCross(m_soft->m_av,rpos));
00393 return(btVector3(0,0,0));
00394 }
00395 btVector3 angularVelocity() const
00396 {
00397 if(m_rigid) return(m_rigid->getAngularVelocity());
00398 if(m_soft) return(m_soft->m_av);
00399 return(btVector3(0,0,0));
00400 }
00401 btVector3 velocity(const btVector3& rpos) const
00402 {
00403 return(linearVelocity()+angularVelocity(rpos));
00404 }
00405 void applyVImpulse(const btVector3& impulse,const btVector3& rpos) const
00406 {
00407 if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
00408 if(m_soft) btSoftBody::clusterVImpulse(m_soft,rpos,impulse);
00409 }
00410 void applyDImpulse(const btVector3& impulse,const btVector3& rpos) const
00411 {
00412 if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
00413 if(m_soft) btSoftBody::clusterDImpulse(m_soft,rpos,impulse);
00414 }
00415 void applyImpulse(const Impulse& impulse,const btVector3& rpos) const
00416 {
00417 if(impulse.m_asVelocity)
00418 {
00419
00420 applyVImpulse(impulse.m_velocity,rpos);
00421 }
00422 if(impulse.m_asDrift)
00423 {
00424
00425 applyDImpulse(impulse.m_drift,rpos);
00426 }
00427 }
00428 void applyVAImpulse(const btVector3& impulse) const
00429 {
00430 if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
00431 if(m_soft) btSoftBody::clusterVAImpulse(m_soft,impulse);
00432 }
00433 void applyDAImpulse(const btVector3& impulse) const
00434 {
00435 if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
00436 if(m_soft) btSoftBody::clusterDAImpulse(m_soft,impulse);
00437 }
00438 void applyAImpulse(const Impulse& impulse) const
00439 {
00440 if(impulse.m_asVelocity) applyVAImpulse(impulse.m_velocity);
00441 if(impulse.m_asDrift) applyDAImpulse(impulse.m_drift);
00442 }
00443 void applyDCImpulse(const btVector3& impulse) const
00444 {
00445 if(m_rigid) m_rigid->applyCentralImpulse(impulse);
00446 if(m_soft) btSoftBody::clusterDCImpulse(m_soft,impulse);
00447 }
00448 };
00449
00450 struct Joint
00451 {
00452 struct eType { enum _ {
00453 Linear,
00454 Angular,
00455 Contact
00456 };};
00457 struct Specs
00458 {
00459 Specs() : erp(1),cfm(1),split(1) {}
00460 btScalar erp;
00461 btScalar cfm;
00462 btScalar split;
00463 };
00464 Body m_bodies[2];
00465 btVector3 m_refs[2];
00466 btScalar m_cfm;
00467 btScalar m_erp;
00468 btScalar m_split;
00469 btVector3 m_drift;
00470 btVector3 m_sdrift;
00471 btMatrix3x3 m_massmatrix;
00472 bool m_delete;
00473 virtual ~Joint() {}
00474 Joint() : m_delete(false) {}
00475 virtual void Prepare(btScalar dt,int iterations);
00476 virtual void Solve(btScalar dt,btScalar sor)=0;
00477 virtual void Terminate(btScalar dt)=0;
00478 virtual eType::_ Type() const=0;
00479 };
00480
00481 struct LJoint : Joint
00482 {
00483 struct Specs : Joint::Specs
00484 {
00485 btVector3 position;
00486 };
00487 btVector3 m_rpos[2];
00488 void Prepare(btScalar dt,int iterations);
00489 void Solve(btScalar dt,btScalar sor);
00490 void Terminate(btScalar dt);
00491 eType::_ Type() const { return(eType::Linear); }
00492 };
00493
00494 struct AJoint : Joint
00495 {
00496 struct IControl
00497 {
00498 virtual void Prepare(AJoint*) {}
00499 virtual btScalar Speed(AJoint*,btScalar current) { return(current); }
00500 static IControl* Default() { static IControl def;return(&def); }
00501 };
00502 struct Specs : Joint::Specs
00503 {
00504 Specs() : icontrol(IControl::Default()) {}
00505 btVector3 axis;
00506 IControl* icontrol;
00507 };
00508 btVector3 m_axis[2];
00509 IControl* m_icontrol;
00510 void Prepare(btScalar dt,int iterations);
00511 void Solve(btScalar dt,btScalar sor);
00512 void Terminate(btScalar dt);
00513 eType::_ Type() const { return(eType::Angular); }
00514 };
00515
00516 struct CJoint : Joint
00517 {
00518 int m_life;
00519 int m_maxlife;
00520 btVector3 m_rpos[2];
00521 btVector3 m_normal;
00522 btScalar m_friction;
00523 void Prepare(btScalar dt,int iterations);
00524 void Solve(btScalar dt,btScalar sor);
00525 void Terminate(btScalar dt);
00526 eType::_ Type() const { return(eType::Contact); }
00527 };
00528
00529 struct Config
00530 {
00531 eAeroModel::_ aeromodel;
00532 btScalar kVCF;
00533 btScalar kDP;
00534 btScalar kDG;
00535 btScalar kLF;
00536 btScalar kPR;
00537 btScalar kVC;
00538 btScalar kDF;
00539 btScalar kMT;
00540 btScalar kCHR;
00541 btScalar kKHR;
00542 btScalar kSHR;
00543 btScalar kAHR;
00544 btScalar kSRHR_CL;
00545 btScalar kSKHR_CL;
00546 btScalar kSSHR_CL;
00547 btScalar kSR_SPLT_CL;
00548 btScalar kSK_SPLT_CL;
00549 btScalar kSS_SPLT_CL;
00550 btScalar maxvolume;
00551 btScalar timescale;
00552 int viterations;
00553 int piterations;
00554 int diterations;
00555 int citerations;
00556 int collisions;
00557 tVSolverArray m_vsequence;
00558 tPSolverArray m_psequence;
00559 tPSolverArray m_dsequence;
00560 };
00561
00562 struct SolverState
00563 {
00564 btScalar sdt;
00565 btScalar isdt;
00566 btScalar velmrg;
00567 btScalar radmrg;
00568 btScalar updmrg;
00569 };
00571 struct RayFromToCaster : btDbvt::ICollide
00572 {
00573 btVector3 m_rayFrom;
00574 btVector3 m_rayTo;
00575 btVector3 m_rayNormalizedDirection;
00576 btScalar m_mint;
00577 Face* m_face;
00578 int m_tests;
00579 RayFromToCaster(const btVector3& rayFrom,const btVector3& rayTo,btScalar mxt);
00580 void Process(const btDbvtNode* leaf);
00581
00582 static inline btScalar rayFromToTriangle(const btVector3& rayFrom,
00583 const btVector3& rayTo,
00584 const btVector3& rayNormalizedDirection,
00585 const btVector3& a,
00586 const btVector3& b,
00587 const btVector3& c,
00588 btScalar maxt=SIMD_INFINITY);
00589 };
00590
00591
00592
00593
00594
00595 typedef void (*psolver_t)(btSoftBody*,btScalar,btScalar);
00596 typedef void (*vsolver_t)(btSoftBody*,btScalar);
00597 typedef btAlignedObjectArray<Cluster*> tClusterArray;
00598 typedef btAlignedObjectArray<Note> tNoteArray;
00599 typedef btAlignedObjectArray<Node> tNodeArray;
00600 typedef btAlignedObjectArray<btDbvtNode*> tLeafArray;
00601 typedef btAlignedObjectArray<Link> tLinkArray;
00602 typedef btAlignedObjectArray<Face> tFaceArray;
00603 typedef btAlignedObjectArray<Tetra> tTetraArray;
00604 typedef btAlignedObjectArray<Anchor> tAnchorArray;
00605 typedef btAlignedObjectArray<RContact> tRContactArray;
00606 typedef btAlignedObjectArray<SContact> tSContactArray;
00607 typedef btAlignedObjectArray<Material*> tMaterialArray;
00608 typedef btAlignedObjectArray<Joint*> tJointArray;
00609 typedef btAlignedObjectArray<btSoftBody*> tSoftBodyArray;
00610
00611
00612
00613
00614
00615 Config m_cfg;
00616 SolverState m_sst;
00617 Pose m_pose;
00618 void* m_tag;
00619 btSoftBodyWorldInfo* m_worldInfo;
00620 tNoteArray m_notes;
00621 tNodeArray m_nodes;
00622 tLinkArray m_links;
00623 tFaceArray m_faces;
00624 tTetraArray m_tetras;
00625 tAnchorArray m_anchors;
00626 tRContactArray m_rcontacts;
00627 tSContactArray m_scontacts;
00628 tJointArray m_joints;
00629 tMaterialArray m_materials;
00630 btScalar m_timeacc;
00631 btVector3 m_bounds[2];
00632 bool m_bUpdateRtCst;
00633 btDbvt m_ndbvt;
00634 btDbvt m_fdbvt;
00635 btDbvt m_cdbvt;
00636 tClusterArray m_clusters;
00637
00638 btAlignedObjectArray<bool>m_clusterConnectivity;
00639
00640 btTransform m_initialWorldTransform;
00641
00642
00643
00644
00645
00646
00647 btSoftBody( btSoftBodyWorldInfo* worldInfo,int node_count,
00648 const btVector3* x,
00649 const btScalar* m);
00650
00651 virtual ~btSoftBody();
00652
00653
00654 btAlignedObjectArray<int> m_userIndexMapping;
00655
00656 btSoftBodyWorldInfo* getWorldInfo()
00657 {
00658 return m_worldInfo;
00659 }
00660
00662 virtual void setCollisionShape(btCollisionShape* collisionShape)
00663 {
00664
00665 }
00666
00667 bool checkLink( int node0,
00668 int node1) const;
00669 bool checkLink( const Node* node0,
00670 const Node* node1) const;
00671
00672 bool checkFace( int node0,
00673 int node1,
00674 int node2) const;
00675
00676 Material* appendMaterial();
00677
00678 void appendNote( const char* text,
00679 const btVector3& o,
00680 const btVector4& c=btVector4(1,0,0,0),
00681 Node* n0=0,
00682 Node* n1=0,
00683 Node* n2=0,
00684 Node* n3=0);
00685 void appendNote( const char* text,
00686 const btVector3& o,
00687 Node* feature);
00688 void appendNote( const char* text,
00689 const btVector3& o,
00690 Link* feature);
00691 void appendNote( const char* text,
00692 const btVector3& o,
00693 Face* feature);
00694
00695 void appendNode( const btVector3& x,btScalar m);
00696
00697 void appendLink(int model=-1,Material* mat=0);
00698 void appendLink( int node0,
00699 int node1,
00700 Material* mat=0,
00701 bool bcheckexist=false);
00702 void appendLink( Node* node0,
00703 Node* node1,
00704 Material* mat=0,
00705 bool bcheckexist=false);
00706
00707 void appendFace(int model=-1,Material* mat=0);
00708 void appendFace( int node0,
00709 int node1,
00710 int node2,
00711 Material* mat=0);
00712 void appendTetra(int model,Material* mat);
00713
00714 void appendTetra(int node0,
00715 int node1,
00716 int node2,
00717 int node3,
00718 Material* mat=0);
00719
00720
00721
00722 void appendAnchor( int node,
00723 btRigidBody* body, bool disableCollisionBetweenLinkedBodies=false);
00724
00725 void appendLinearJoint(const LJoint::Specs& specs,Cluster* body0,Body body1);
00726 void appendLinearJoint(const LJoint::Specs& specs,Body body=Body());
00727 void appendLinearJoint(const LJoint::Specs& specs,btSoftBody* body);
00728
00729 void appendAngularJoint(const AJoint::Specs& specs,Cluster* body0,Body body1);
00730 void appendAngularJoint(const AJoint::Specs& specs,Body body=Body());
00731 void appendAngularJoint(const AJoint::Specs& specs,btSoftBody* body);
00732
00733 void addForce( const btVector3& force);
00734
00735 void addForce( const btVector3& force,
00736 int node);
00737
00738 void addVelocity( const btVector3& velocity);
00739
00740
00741 void setVelocity( const btVector3& velocity);
00742
00743
00744 void addVelocity( const btVector3& velocity,
00745 int node);
00746
00747 void setMass( int node,
00748 btScalar mass);
00749
00750 btScalar getMass( int node) const;
00751
00752 btScalar getTotalMass() const;
00753
00754 void setTotalMass( btScalar mass,
00755 bool fromfaces=false);
00756
00757 void setTotalDensity(btScalar density);
00758
00759 void setVolumeMass( btScalar mass);
00760
00761 void setVolumeDensity( btScalar density);
00762
00763 void transform( const btTransform& trs);
00764
00765 void translate( const btVector3& trs);
00766
00767 void rotate( const btQuaternion& rot);
00768
00769 void scale( const btVector3& scl);
00770
00771 void setPose( bool bvolume,
00772 bool bframe);
00773
00774 btScalar getVolume() const;
00775
00776 int clusterCount() const;
00777
00778 static btVector3 clusterCom(const Cluster* cluster);
00779 btVector3 clusterCom(int cluster) const;
00780
00781 static btVector3 clusterVelocity(const Cluster* cluster,const btVector3& rpos);
00782
00783 static void clusterVImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
00784 static void clusterDImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
00785 static void clusterImpulse(Cluster* cluster,const btVector3& rpos,const Impulse& impulse);
00786 static void clusterVAImpulse(Cluster* cluster,const btVector3& impulse);
00787 static void clusterDAImpulse(Cluster* cluster,const btVector3& impulse);
00788 static void clusterAImpulse(Cluster* cluster,const Impulse& impulse);
00789 static void clusterDCImpulse(Cluster* cluster,const btVector3& impulse);
00790
00791 int generateBendingConstraints( int distance,
00792 Material* mat=0);
00793
00794 void randomizeConstraints();
00795
00796 void releaseCluster(int index);
00797 void releaseClusters();
00798
00801 int generateClusters(int k,int maxiterations=8192);
00802
00803 void refine(ImplicitFn* ifn,btScalar accurary,bool cut);
00804
00805 bool cutLink(int node0,int node1,btScalar position);
00806 bool cutLink(const Node* node0,const Node* node1,btScalar position);
00807
00809 bool rayTest(const btVector3& rayFrom,
00810 const btVector3& rayTo,
00811 sRayCast& results);
00812
00813 void setSolver(eSolverPresets::_ preset);
00814
00815 void predictMotion(btScalar dt);
00816
00817 void solveConstraints();
00818
00819 void staticSolve(int iterations);
00820
00821 static void solveCommonConstraints(btSoftBody** bodies,int count,int iterations);
00822
00823 static void solveClusters(const btAlignedObjectArray<btSoftBody*>& bodies);
00824
00825 void integrateMotion();
00826
00827 void defaultCollisionHandler(btCollisionObject* pco);
00828 void defaultCollisionHandler(btSoftBody* psb);
00829
00830
00831
00832
00833
00834 static const btSoftBody* upcast(const btCollisionObject* colObj)
00835 {
00836 if (colObj->getInternalType()==CO_SOFT_BODY)
00837 return (const btSoftBody*)colObj;
00838 return 0;
00839 }
00840 static btSoftBody* upcast(btCollisionObject* colObj)
00841 {
00842 if (colObj->getInternalType()==CO_SOFT_BODY)
00843 return (btSoftBody*)colObj;
00844 return 0;
00845 }
00846
00847
00848
00849
00850
00851 virtual void getAabb(btVector3& aabbMin,btVector3& aabbMax) const
00852 {
00853 aabbMin = m_bounds[0];
00854 aabbMax = m_bounds[1];
00855 }
00856
00857
00858
00859 void pointersToIndices();
00860 void indicesToPointers(const int* map=0);
00861
00862 int rayTest(const btVector3& rayFrom,const btVector3& rayTo,
00863 btScalar& mint,eFeature::_& feature,int& index,bool bcountonly) const;
00864 void initializeFaceTree();
00865 btVector3 evaluateCom() const;
00866 bool checkContact(btCollisionObject* colObj,const btVector3& x,btScalar margin,btSoftBody::sCti& cti) const;
00867 void updateNormals();
00868 void updateBounds();
00869 void updatePose();
00870 void updateConstants();
00871 void initializeClusters();
00872 void updateClusters();
00873 void cleanupClusters();
00874 void prepareClusters(int iterations);
00875 void solveClusters(btScalar sor);
00876 void applyClusters(bool drift);
00877 void dampClusters();
00878 void applyForces();
00879 static void PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti);
00880 static void PSolve_RContacts(btSoftBody* psb,btScalar kst,btScalar ti);
00881 static void PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti);
00882 static void PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti);
00883 static void VSolve_Links(btSoftBody* psb,btScalar kst);
00884 static psolver_t getSolver(ePSolver::_ solver);
00885 static vsolver_t getSolver(eVSolver::_ solver);
00886
00887 };
00888
00889
00890
00891 #endif //_BT_SOFT_BODY_H