btSoftBody.h
Go to the documentation of this file.
00001 /*
00002 Bullet Continuous Collision Detection and Physics Library
00003 Copyright (c) 2003-2006 Erwin Coumans  http://continuousphysics.com/Bullet/
00004 
00005 This software is provided 'as-is', without any express or implied warranty.
00006 In no event will the authors be held liable for any damages arising from the use of this software.
00007 Permission is granted to anyone to use this software for any purpose,
00008 including commercial applications, and to alter it and redistribute it freely,
00009 subject to the following restrictions:
00010 
00011 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.
00012 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00013 3. This notice may not be removed or altered from any source distribution.
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 //#ifdef BT_USE_DOUBLE_PRECISION
00031 //#define btRigidBodyData       btRigidBodyDoubleData
00032 //#define btRigidBodyDataName   "btRigidBodyDoubleData"
00033 //#else
00034 #define btSoftBodyData  btSoftBodyFloatData
00035 #define btSoftBodyDataName      "btSoftBodyFloatData"
00036 //#endif //BT_USE_DOUBLE_PRECISION
00037 
00038 class btBroadphaseInterface;
00039 class btDispatcher;
00040 class btSoftBodySolver;
00041 
00042 /* btSoftBodyWorldInfo  */ 
00043 struct  btSoftBodyWorldInfo
00044 {
00045         btScalar                                air_density;
00046         btScalar                                water_density;
00047         btScalar                                water_offset;
00048         btVector3                               water_normal;
00049         btBroadphaseInterface*  m_broadphase;
00050         btDispatcher*   m_dispatcher;
00051         btVector3                               m_gravity;
00052         btSparseSdf<3>                  m_sparsesdf;
00053 
00054         btSoftBodyWorldInfo()
00055                 :air_density((btScalar)1.2),
00056                 water_density(0),
00057                 water_offset(0),
00058                 water_normal(0,0,0),
00059                 m_broadphase(0),
00060                 m_dispatcher(0),
00061                 m_gravity(0,-10,0)
00062         {
00063         }
00064 };      
00065 
00066 
00069 class   btSoftBody : public btCollisionObject
00070 {
00071 public:
00072         btAlignedObjectArray<class btCollisionObject*> m_collisionDisabledObjects;
00073 
00074         // The solver object that handles this soft body
00075         btSoftBodySolver *m_softBodySolver;
00076 
00077         //
00078         // Enumerations
00079         //
00080 
00082         struct eAeroModel { enum _ {
00083                 V_Point,                        
00084                 V_TwoSided,                     
00085                 V_TwoSidedLiftDrag, 
00086                 V_OneSided,                     
00087                 F_TwoSided,                     
00088                 F_TwoSidedLiftDrag,     
00089                 F_OneSided,                     
00090                 END
00091         };};
00092 
00094         struct  eVSolver { enum _ {
00095                 Linear,         
00096                 END
00097         };};
00098 
00100         struct  ePSolver { enum _ {
00101                 Linear,         
00102                 Anchors,        
00103                 RContacts,      
00104                 SContacts,      
00105                 END
00106         };};
00107 
00109         struct  eSolverPresets { enum _ {
00110                 Positions,
00111                 Velocities,
00112                 Default =       Positions,
00113                 END
00114         };};
00115 
00117         struct  eFeature { enum _ {
00118                 None,
00119                 Node,
00120                 Link,
00121                 Face,
00122                 Tetra,
00123                 END
00124         };};
00125 
00126         typedef btAlignedObjectArray<eVSolver::_>       tVSolverArray;
00127         typedef btAlignedObjectArray<ePSolver::_>       tPSolverArray;
00128 
00129         //
00130         // Flags
00131         //
00132 
00134         struct fCollision { enum _ {
00135                 RVSmask =       0x000f, 
00136                 SDF_RS  =       0x0001, 
00137                 CL_RS   =       0x0002, 
00138 
00139                 SVSmask =       0x0030, 
00140                 VF_SS   =       0x0010, 
00141                 CL_SS   =       0x0020, 
00142                 CL_SELF =       0x0040, 
00143                 /* presets      */ 
00144                 Default =       SDF_RS,
00145                 END
00146         };};
00147 
00149         struct fMaterial { enum _ {
00150                 DebugDraw       =       0x0001, 
00151                 /* presets      */ 
00152                 Default         =       DebugDraw,
00153                 END
00154         };};
00155 
00156         //
00157         // API Types
00158         //
00159 
00160         /* sRayCast             */ 
00161         struct sRayCast
00162         {
00163                 btSoftBody*     body;           
00164                 eFeature::_     feature;        
00165                 int                     index;          
00166                 btScalar        fraction;               
00167         };
00168 
00169         /* ImplicitFn   */ 
00170         struct  ImplicitFn
00171         {
00172                 virtual btScalar        Eval(const btVector3& x)=0;
00173         };
00174 
00175         //
00176         // Internal types
00177         //
00178 
00179         typedef btAlignedObjectArray<btScalar>  tScalarArray;
00180         typedef btAlignedObjectArray<btVector3> tVector3Array;
00181 
00182         /* sCti is Softbody contact info        */ 
00183         struct  sCti
00184         {
00185                 btCollisionObject*      m_colObj;               /* Rigid body                   */ 
00186                 btVector3               m_normal;       /* Outward normal               */ 
00187                 btScalar                m_offset;       /* Offset from origin   */ 
00188         };      
00189 
00190         /* sMedium              */ 
00191         struct  sMedium
00192         {
00193                 btVector3               m_velocity;     /* Velocity                             */ 
00194                 btScalar                m_pressure;     /* Pressure                             */ 
00195                 btScalar                m_density;      /* Density                              */ 
00196         };
00197 
00198         /* Base type    */ 
00199         struct  Element
00200         {
00201                 void*                   m_tag;                  // User data
00202                 Element() : m_tag(0) {}
00203         };
00204         /* Material             */ 
00205         struct  Material : Element
00206         {
00207                 btScalar                                m_kLST;                 // Linear stiffness coefficient [0,1]
00208                 btScalar                                m_kAST;                 // Area/Angular stiffness coefficient [0,1]
00209                 btScalar                                m_kVST;                 // Volume stiffness coefficient [0,1]
00210                 int                                             m_flags;                // Flags
00211         };
00212 
00213         /* Feature              */ 
00214         struct  Feature : Element
00215         {
00216                 Material*                               m_material;             // Material
00217         };
00218         /* Node                 */ 
00219         struct  Node : Feature
00220         {
00221                 btVector3                               m_x;                    // Position
00222                 btVector3                               m_q;                    // Previous step position
00223                 btVector3                               m_v;                    // Velocity
00224                 btVector3                               m_f;                    // Force accumulator
00225                 btVector3                               m_n;                    // Normal
00226                 btScalar                                m_im;                   // 1/mass
00227                 btScalar                                m_area;                 // Area
00228                 btDbvtNode*                             m_leaf;                 // Leaf data
00229                 int                                             m_battach:1;    // Attached
00230         };
00231         /* Link                 */ 
00232         struct  Link : Feature
00233         {
00234                 Node*                                   m_n[2];                 // Node pointers
00235                 btScalar                                m_rl;                   // Rest length          
00236                 int                                             m_bbending:1;   // Bending link
00237                 btScalar                                m_c0;                   // (ima+imb)*kLST
00238                 btScalar                                m_c1;                   // rl^2
00239                 btScalar                                m_c2;                   // |gradient|^2/c0
00240                 btVector3                               m_c3;                   // gradient
00241         };
00242         /* Face                 */ 
00243         struct  Face : Feature
00244         {
00245                 Node*                                   m_n[3];                 // Node pointers
00246                 btVector3                               m_normal;               // Normal
00247                 btScalar                                m_ra;                   // Rest area
00248                 btDbvtNode*                             m_leaf;                 // Leaf data
00249         };
00250         /* Tetra                */ 
00251         struct  Tetra : Feature
00252         {
00253                 Node*                                   m_n[4];                 // Node pointers                
00254                 btScalar                                m_rv;                   // Rest volume
00255                 btDbvtNode*                             m_leaf;                 // Leaf data
00256                 btVector3                               m_c0[4];                // gradients
00257                 btScalar                                m_c1;                   // (4*kVST)/(im0+im1+im2+im3)
00258                 btScalar                                m_c2;                   // m_c1/sum(|g0..3|^2)
00259         };
00260         /* RContact             */ 
00261         struct  RContact
00262         {
00263                 sCti            m_cti;                  // Contact infos
00264                 Node*                                   m_node;                 // Owner node
00265                 btMatrix3x3                             m_c0;                   // Impulse matrix
00266                 btVector3                               m_c1;                   // Relative anchor
00267                 btScalar                                m_c2;                   // ima*dt
00268                 btScalar                                m_c3;                   // Friction
00269                 btScalar                                m_c4;                   // Hardness
00270         };
00271         /* SContact             */ 
00272         struct  SContact
00273         {
00274                 Node*                                   m_node;                 // Node
00275                 Face*                                   m_face;                 // Face
00276                 btVector3                               m_weights;              // Weigths
00277                 btVector3                               m_normal;               // Normal
00278                 btScalar                                m_margin;               // Margin
00279                 btScalar                                m_friction;             // Friction
00280                 btScalar                                m_cfm[2];               // Constraint force mixing
00281         };
00282         /* Anchor               */ 
00283         struct  Anchor
00284         {
00285                 Node*                                   m_node;                 // Node pointer
00286                 btVector3                               m_local;                // Anchor position in body space
00287                 btRigidBody*                    m_body;                 // Body
00288                 btScalar                                m_influence;
00289                 btMatrix3x3                             m_c0;                   // Impulse matrix
00290                 btVector3                               m_c1;                   // Relative anchor
00291                 btScalar                                m_c2;                   // ima*dt
00292         };
00293         /* Note                 */ 
00294         struct  Note : Element
00295         {
00296                 const char*                             m_text;                 // Text
00297                 btVector3                               m_offset;               // Offset
00298                 int                                             m_rank;                 // Rank
00299                 Node*                                   m_nodes[4];             // Nodes
00300                 btScalar                                m_coords[4];    // Coordinates
00301         };      
00302         /* Pose                 */ 
00303         struct  Pose
00304         {
00305                 bool                                    m_bvolume;              // Is valid
00306                 bool                                    m_bframe;               // Is frame
00307                 btScalar                                m_volume;               // Rest volume
00308                 tVector3Array                   m_pos;                  // Reference positions
00309                 tScalarArray                    m_wgh;                  // Weights
00310                 btVector3                               m_com;                  // COM
00311                 btMatrix3x3                             m_rot;                  // Rotation
00312                 btMatrix3x3                             m_scl;                  // Scale
00313                 btMatrix3x3                             m_aqq;                  // Base scaling
00314         };
00315         /* Cluster              */ 
00316         struct  Cluster
00317         {
00318                 tScalarArray                            m_masses;
00319                 btAlignedObjectArray<Node*>     m_nodes;                
00320                 tVector3Array                           m_framerefs;
00321                 btTransform                                     m_framexform;
00322                 btScalar                                        m_idmass;
00323                 btScalar                                        m_imass;
00324                 btMatrix3x3                                     m_locii;
00325                 btMatrix3x3                                     m_invwi;
00326                 btVector3                                       m_com;
00327                 btVector3                                       m_vimpulses[2];
00328                 btVector3                                       m_dimpulses[2];
00329                 int                                                     m_nvimpulses;
00330                 int                                                     m_ndimpulses;
00331                 btVector3                                       m_lv;
00332                 btVector3                                       m_av;
00333                 btDbvtNode*                                     m_leaf;
00334                 btScalar                                        m_ndamping;     /* Node damping         */ 
00335                 btScalar                                        m_ldamping;     /* Linear damping       */ 
00336                 btScalar                                        m_adamping;     /* Angular damping      */ 
00337                 btScalar                                        m_matching;
00338                 btScalar                                        m_maxSelfCollisionImpulse;
00339                 btScalar                                        m_selfCollisionImpulseFactor;
00340                 bool                                            m_containsAnchor;
00341                 bool                                            m_collide;
00342                 int                                                     m_clusterIndex;
00343                 Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0) 
00344                 ,m_maxSelfCollisionImpulse(100.f),
00345                 m_selfCollisionImpulseFactor(0.01f),
00346                 m_containsAnchor(false)
00347                 {}
00348         };
00349         /* Impulse              */ 
00350         struct  Impulse
00351         {
00352                 btVector3                                       m_velocity;
00353                 btVector3                                       m_drift;
00354                 int                                                     m_asVelocity:1;
00355                 int                                                     m_asDrift:1;
00356                 Impulse() : m_velocity(0,0,0),m_drift(0,0,0),m_asVelocity(0),m_asDrift(0)       {}
00357                 Impulse                                         operator -() const
00358                 {
00359                         Impulse i=*this;
00360                         i.m_velocity=-i.m_velocity;
00361                         i.m_drift=-i.m_drift;
00362                         return(i);
00363                 }
00364                 Impulse                                         operator*(btScalar x) const
00365                 {
00366                         Impulse i=*this;
00367                         i.m_velocity*=x;
00368                         i.m_drift*=x;
00369                         return(i);
00370                 }
00371         };
00372         /* Body                 */ 
00373         struct  Body
00374         {
00375                 Cluster*                        m_soft;
00376                 btRigidBody*            m_rigid;
00377                 btCollisionObject*      m_collisionObject;
00378 
00379                 Body() : m_soft(0),m_rigid(0),m_collisionObject(0)                              {}
00380                 Body(Cluster* p) : m_soft(p),m_rigid(0),m_collisionObject(0)    {}
00381                 Body(btCollisionObject* colObj) : m_soft(0),m_collisionObject(colObj)
00382                 {
00383                         m_rigid = btRigidBody::upcast(m_collisionObject);
00384                 }
00385 
00386                 void                                            activate() const
00387                 {
00388                         if(m_rigid) 
00389                                 m_rigid->activate();
00390                         if (m_collisionObject)
00391                                 m_collisionObject->activate();
00392 
00393                 }
00394                 const btMatrix3x3&                      invWorldInertia() const
00395                 {
00396                         static const btMatrix3x3        iwi(0,0,0,0,0,0,0,0,0);
00397                         if(m_rigid) return(m_rigid->getInvInertiaTensorWorld());
00398                         if(m_soft)      return(m_soft->m_invwi);
00399                         return(iwi);
00400                 }
00401                 btScalar                                        invMass() const
00402                 {
00403                         if(m_rigid) return(m_rigid->getInvMass());
00404                         if(m_soft)      return(m_soft->m_imass);
00405                         return(0);
00406                 }
00407                 const btTransform&                      xform() const
00408                 {
00409                         static const btTransform        identity=btTransform::getIdentity();            
00410                         if(m_collisionObject) return(m_collisionObject->getWorldTransform());
00411                         if(m_soft)      return(m_soft->m_framexform);
00412                         return(identity);
00413                 }
00414                 btVector3                                       linearVelocity() const
00415                 {
00416                         if(m_rigid) return(m_rigid->getLinearVelocity());
00417                         if(m_soft)      return(m_soft->m_lv);
00418                         return(btVector3(0,0,0));
00419                 }
00420                 btVector3                                       angularVelocity(const btVector3& rpos) const
00421                 {                       
00422                         if(m_rigid) return(btCross(m_rigid->getAngularVelocity(),rpos));
00423                         if(m_soft)      return(btCross(m_soft->m_av,rpos));
00424                         return(btVector3(0,0,0));
00425                 }
00426                 btVector3                                       angularVelocity() const
00427                 {                       
00428                         if(m_rigid) return(m_rigid->getAngularVelocity());
00429                         if(m_soft)      return(m_soft->m_av);
00430                         return(btVector3(0,0,0));
00431                 }
00432                 btVector3                                       velocity(const btVector3& rpos) const
00433                 {
00434                         return(linearVelocity()+angularVelocity(rpos));
00435                 }
00436                 void                                            applyVImpulse(const btVector3& impulse,const btVector3& rpos) const
00437                 {
00438                         if(m_rigid)     m_rigid->applyImpulse(impulse,rpos);
00439                         if(m_soft)      btSoftBody::clusterVImpulse(m_soft,rpos,impulse);
00440                 }
00441                 void                                            applyDImpulse(const btVector3& impulse,const btVector3& rpos) const
00442                 {
00443                         if(m_rigid)     m_rigid->applyImpulse(impulse,rpos);
00444                         if(m_soft)      btSoftBody::clusterDImpulse(m_soft,rpos,impulse);
00445                 }               
00446                 void                                            applyImpulse(const Impulse& impulse,const btVector3& rpos) const
00447                 {
00448                         if(impulse.m_asVelocity)        
00449                         {
00450 //                              printf("impulse.m_velocity = %f,%f,%f\n",impulse.m_velocity.getX(),impulse.m_velocity.getY(),impulse.m_velocity.getZ());
00451                                 applyVImpulse(impulse.m_velocity,rpos);
00452                         }
00453                         if(impulse.m_asDrift)           
00454                         {
00455 //                              printf("impulse.m_drift = %f,%f,%f\n",impulse.m_drift.getX(),impulse.m_drift.getY(),impulse.m_drift.getZ());
00456                                 applyDImpulse(impulse.m_drift,rpos);
00457                         }
00458                 }
00459                 void                                            applyVAImpulse(const btVector3& impulse) const
00460                 {
00461                         if(m_rigid)     m_rigid->applyTorqueImpulse(impulse);
00462                         if(m_soft)      btSoftBody::clusterVAImpulse(m_soft,impulse);
00463                 }
00464                 void                                            applyDAImpulse(const btVector3& impulse) const
00465                 {
00466                         if(m_rigid)     m_rigid->applyTorqueImpulse(impulse);
00467                         if(m_soft)      btSoftBody::clusterDAImpulse(m_soft,impulse);
00468                 }
00469                 void                                            applyAImpulse(const Impulse& impulse) const
00470                 {
00471                         if(impulse.m_asVelocity)        applyVAImpulse(impulse.m_velocity);
00472                         if(impulse.m_asDrift)           applyDAImpulse(impulse.m_drift);
00473                 }
00474                 void                                            applyDCImpulse(const btVector3& impulse) const
00475                 {
00476                         if(m_rigid)     m_rigid->applyCentralImpulse(impulse);
00477                         if(m_soft)      btSoftBody::clusterDCImpulse(m_soft,impulse);
00478                 }
00479         };
00480         /* Joint                */ 
00481         struct  Joint
00482         {
00483                 struct eType { enum _ {
00484                         Linear=0,
00485                         Angular,
00486                         Contact
00487                 };};
00488                 struct Specs
00489                 {
00490                         Specs() : erp(1),cfm(1),split(1) {}
00491                         btScalar        erp;
00492                         btScalar        cfm;
00493                         btScalar        split;
00494                 };
00495                 Body                                            m_bodies[2];
00496                 btVector3                                       m_refs[2];
00497                 btScalar                                        m_cfm;
00498                 btScalar                                        m_erp;
00499                 btScalar                                        m_split;
00500                 btVector3                                       m_drift;
00501                 btVector3                                       m_sdrift;
00502                 btMatrix3x3                                     m_massmatrix;
00503                 bool                                            m_delete;
00504                 virtual                                         ~Joint() {}
00505                 Joint() : m_delete(false) {}
00506                 virtual void                            Prepare(btScalar dt,int iterations);
00507                 virtual void                            Solve(btScalar dt,btScalar sor)=0;
00508                 virtual void                            Terminate(btScalar dt)=0;
00509                 virtual eType::_                        Type() const=0;
00510         };
00511         /* LJoint               */ 
00512         struct  LJoint : Joint
00513         {
00514                 struct Specs : Joint::Specs
00515                 {
00516                         btVector3       position;
00517                 };              
00518                 btVector3                                       m_rpos[2];
00519                 void                                            Prepare(btScalar dt,int iterations);
00520                 void                                            Solve(btScalar dt,btScalar sor);
00521                 void                                            Terminate(btScalar dt);
00522                 eType::_                                        Type() const { return(eType::Linear); }
00523         };
00524         /* AJoint               */ 
00525         struct  AJoint : Joint
00526         {
00527                 struct IControl
00528                 {
00529                         virtual void                    Prepare(AJoint*)                                {}
00530                         virtual btScalar                Speed(AJoint*,btScalar current) { return(current); }
00531                         static IControl*                Default()                                               { static IControl def;return(&def); }
00532                 };
00533                 struct Specs : Joint::Specs
00534                 {
00535                         Specs() : icontrol(IControl::Default()) {}
00536                         btVector3       axis;
00537                         IControl*       icontrol;
00538                 };              
00539                 btVector3                                       m_axis[2];
00540                 IControl*                                       m_icontrol;
00541                 void                                            Prepare(btScalar dt,int iterations);
00542                 void                                            Solve(btScalar dt,btScalar sor);
00543                 void                                            Terminate(btScalar dt);
00544                 eType::_                                        Type() const { return(eType::Angular); }
00545         };
00546         /* CJoint               */ 
00547         struct  CJoint : Joint
00548         {               
00549                 int                                                     m_life;
00550                 int                                                     m_maxlife;
00551                 btVector3                                       m_rpos[2];
00552                 btVector3                                       m_normal;
00553                 btScalar                                        m_friction;
00554                 void                                            Prepare(btScalar dt,int iterations);
00555                 void                                            Solve(btScalar dt,btScalar sor);
00556                 void                                            Terminate(btScalar dt);
00557                 eType::_                                        Type() const { return(eType::Contact); }
00558         };
00559         /* Config               */ 
00560         struct  Config
00561         {
00562                 eAeroModel::_                   aeromodel;              // Aerodynamic model (default: V_Point)
00563                 btScalar                                kVCF;                   // Velocities correction factor (Baumgarte)
00564                 btScalar                                kDP;                    // Damping coefficient [0,1]
00565                 btScalar                                kDG;                    // Drag coefficient [0,+inf]
00566                 btScalar                                kLF;                    // Lift coefficient [0,+inf]
00567                 btScalar                                kPR;                    // Pressure coefficient [-inf,+inf]
00568                 btScalar                                kVC;                    // Volume conversation coefficient [0,+inf]
00569                 btScalar                                kDF;                    // Dynamic friction coefficient [0,1]
00570                 btScalar                                kMT;                    // Pose matching coefficient [0,1]              
00571                 btScalar                                kCHR;                   // Rigid contacts hardness [0,1]
00572                 btScalar                                kKHR;                   // Kinetic contacts hardness [0,1]
00573                 btScalar                                kSHR;                   // Soft contacts hardness [0,1]
00574                 btScalar                                kAHR;                   // Anchors hardness [0,1]
00575                 btScalar                                kSRHR_CL;               // Soft vs rigid hardness [0,1] (cluster only)
00576                 btScalar                                kSKHR_CL;               // Soft vs kinetic hardness [0,1] (cluster only)
00577                 btScalar                                kSSHR_CL;               // Soft vs soft hardness [0,1] (cluster only)
00578                 btScalar                                kSR_SPLT_CL;    // Soft vs rigid impulse split [0,1] (cluster only)
00579                 btScalar                                kSK_SPLT_CL;    // Soft vs rigid impulse split [0,1] (cluster only)
00580                 btScalar                                kSS_SPLT_CL;    // Soft vs rigid impulse split [0,1] (cluster only)
00581                 btScalar                                maxvolume;              // Maximum volume ratio for pose
00582                 btScalar                                timescale;              // Time scale
00583                 int                                             viterations;    // Velocities solver iterations
00584                 int                                             piterations;    // Positions solver iterations
00585                 int                                             diterations;    // Drift solver iterations
00586                 int                                             citerations;    // Cluster solver iterations
00587                 int                                             collisions;             // Collisions flags
00588                 tVSolverArray                   m_vsequence;    // Velocity solvers sequence
00589                 tPSolverArray                   m_psequence;    // Position solvers sequence
00590                 tPSolverArray                   m_dsequence;    // Drift solvers sequence
00591         };
00592         /* SolverState  */ 
00593         struct  SolverState
00594         {
00595                 btScalar                                sdt;                    // dt*timescale
00596                 btScalar                                isdt;                   // 1/sdt
00597                 btScalar                                velmrg;                 // velocity margin
00598                 btScalar                                radmrg;                 // radial margin
00599                 btScalar                                updmrg;                 // Update margin
00600         };      
00602         struct  RayFromToCaster : btDbvt::ICollide
00603         {
00604                 btVector3                       m_rayFrom;
00605                 btVector3                       m_rayTo;
00606                 btVector3                       m_rayNormalizedDirection;
00607                 btScalar                        m_mint;
00608                 Face*                           m_face;
00609                 int                                     m_tests;
00610                 RayFromToCaster(const btVector3& rayFrom,const btVector3& rayTo,btScalar mxt);
00611                 void                                    Process(const btDbvtNode* leaf);
00612 
00613                 static inline btScalar  rayFromToTriangle(const btVector3& rayFrom,
00614                         const btVector3& rayTo,
00615                         const btVector3& rayNormalizedDirection,
00616                         const btVector3& a,
00617                         const btVector3& b,
00618                         const btVector3& c,
00619                         btScalar maxt=SIMD_INFINITY);
00620         };
00621 
00622         //
00623         // Typedefs
00624         //
00625 
00626         typedef void                                                            (*psolver_t)(btSoftBody*,btScalar,btScalar);
00627         typedef void                                                            (*vsolver_t)(btSoftBody*,btScalar);
00628         typedef btAlignedObjectArray<Cluster*>          tClusterArray;
00629         typedef btAlignedObjectArray<Note>                      tNoteArray;
00630         typedef btAlignedObjectArray<Node>                      tNodeArray;
00631         typedef btAlignedObjectArray<btDbvtNode*>       tLeafArray;
00632         typedef btAlignedObjectArray<Link>                      tLinkArray;
00633         typedef btAlignedObjectArray<Face>                      tFaceArray;
00634         typedef btAlignedObjectArray<Tetra>                     tTetraArray;
00635         typedef btAlignedObjectArray<Anchor>            tAnchorArray;
00636         typedef btAlignedObjectArray<RContact>          tRContactArray;
00637         typedef btAlignedObjectArray<SContact>          tSContactArray;
00638         typedef btAlignedObjectArray<Material*>         tMaterialArray;
00639         typedef btAlignedObjectArray<Joint*>            tJointArray;
00640         typedef btAlignedObjectArray<btSoftBody*>       tSoftBodyArray; 
00641 
00642         //
00643         // Fields
00644         //
00645 
00646         Config                                  m_cfg;                  // Configuration
00647         SolverState                             m_sst;                  // Solver state
00648         Pose                                    m_pose;                 // Pose
00649         void*                                   m_tag;                  // User data
00650         btSoftBodyWorldInfo*    m_worldInfo;    // World info
00651         tNoteArray                              m_notes;                // Notes
00652         tNodeArray                              m_nodes;                // Nodes
00653         tLinkArray                              m_links;                // Links
00654         tFaceArray                              m_faces;                // Faces
00655         tTetraArray                             m_tetras;               // Tetras
00656         tAnchorArray                    m_anchors;              // Anchors
00657         tRContactArray                  m_rcontacts;    // Rigid contacts
00658         tSContactArray                  m_scontacts;    // Soft contacts
00659         tJointArray                             m_joints;               // Joints
00660         tMaterialArray                  m_materials;    // Materials
00661         btScalar                                m_timeacc;              // Time accumulator
00662         btVector3                               m_bounds[2];    // Spatial bounds       
00663         bool                                    m_bUpdateRtCst; // Update runtime constants
00664         btDbvt                                  m_ndbvt;                // Nodes tree
00665         btDbvt                                  m_fdbvt;                // Faces tree
00666         btDbvt                                  m_cdbvt;                // Clusters tree
00667         tClusterArray                   m_clusters;             // Clusters
00668 
00669         btAlignedObjectArray<bool>m_clusterConnectivity;//cluster connectivity, for self-collision
00670 
00671         btTransform                     m_initialWorldTransform;
00672 
00673         btVector3                       m_windVelocity;
00674         //
00675         // Api
00676         //
00677 
00678         /* ctor                                                                                                                                 */ 
00679         btSoftBody(     btSoftBodyWorldInfo* worldInfo,int node_count,          const btVector3* x,             const btScalar* m);
00680 
00681         /* ctor                                                                                                                                 */ 
00682         btSoftBody(     btSoftBodyWorldInfo* worldInfo);
00683 
00684         void    initDefaults();
00685 
00686         /* dtor                                                                                                                                 */ 
00687         virtual ~btSoftBody();
00688         /* Check for existing link                                                                                              */ 
00689 
00690         btAlignedObjectArray<int>       m_userIndexMapping;
00691 
00692         btSoftBodyWorldInfo*    getWorldInfo()
00693         {
00694                 return m_worldInfo;
00695         }
00696 
00698         virtual void    setCollisionShape(btCollisionShape* collisionShape)
00699         {
00700                 
00701         }
00702 
00703         bool                            checkLink(      int node0,
00704                 int node1) const;
00705         bool                            checkLink(      const Node* node0,
00706                 const Node* node1) const;
00707         /* Check for existring face                                                                                             */ 
00708         bool                            checkFace(      int node0,
00709                 int node1,
00710                 int node2) const;
00711         /* Append material                                                                                                              */ 
00712         Material*                       appendMaterial();
00713         /* Append note                                                                                                                  */ 
00714         void                            appendNote(     const char* text,
00715                 const btVector3& o,
00716                 const btVector4& c=btVector4(1,0,0,0),
00717                 Node* n0=0,
00718                 Node* n1=0,
00719                 Node* n2=0,
00720                 Node* n3=0);
00721         void                            appendNote(     const char* text,
00722                 const btVector3& o,
00723                 Node* feature);
00724         void                            appendNote(     const char* text,
00725                 const btVector3& o,
00726                 Link* feature);
00727         void                            appendNote(     const char* text,
00728                 const btVector3& o,
00729                 Face* feature);
00730         /* Append node                                                                                                                  */ 
00731         void                            appendNode(     const btVector3& x,btScalar m);
00732         /* Append link                                                                                                                  */ 
00733         void                            appendLink(int model=-1,Material* mat=0);
00734         void                            appendLink(     int node0,
00735                 int node1,
00736                 Material* mat=0,
00737                 bool bcheckexist=false);
00738         void                            appendLink(     Node* node0,
00739                 Node* node1,
00740                 Material* mat=0,
00741                 bool bcheckexist=false);
00742         /* Append face                                                                                                                  */ 
00743         void                            appendFace(int model=-1,Material* mat=0);
00744         void                            appendFace(     int node0,
00745                 int node1,
00746                 int node2,
00747                 Material* mat=0);
00748         void                    appendTetra(int model,Material* mat);
00749         //
00750         void                    appendTetra(int node0,
00751                                                                                 int node1,
00752                                                                                 int node2,
00753                                                                                 int node3,
00754                                                                                 Material* mat=0);
00755 
00756 
00757         /* Append anchor                                                                                                                */ 
00758         void                            appendAnchor(   int node,
00759                 btRigidBody* body, bool disableCollisionBetweenLinkedBodies=false,btScalar influence = 1);
00760         void                    appendAnchor(int node,btRigidBody* body, const btVector3& localPivot,bool disableCollisionBetweenLinkedBodies=false,btScalar influence = 1);
00761         /* Append linear joint                                                                                                  */ 
00762         void                            appendLinearJoint(const LJoint::Specs& specs,Cluster* body0,Body body1);
00763         void                            appendLinearJoint(const LJoint::Specs& specs,Body body=Body());
00764         void                            appendLinearJoint(const LJoint::Specs& specs,btSoftBody* body);
00765         /* Append linear joint                                                                                                  */ 
00766         void                            appendAngularJoint(const AJoint::Specs& specs,Cluster* body0,Body body1);
00767         void                            appendAngularJoint(const AJoint::Specs& specs,Body body=Body());
00768         void                            appendAngularJoint(const AJoint::Specs& specs,btSoftBody* body);
00769         /* Add force (or gravity) to the entire body                                                    */ 
00770         void                            addForce(               const btVector3& force);
00771         /* Add force (or gravity) to a node of the body                                                 */ 
00772         void                            addForce(               const btVector3& force,
00773                 int node);
00774         /* Add velocity to the entire body                                                                              */ 
00775         void                            addVelocity(    const btVector3& velocity);
00776 
00777         /* Set velocity for the entire body                                                                             */ 
00778         void                            setVelocity(    const btVector3& velocity);
00779 
00780         /* Add velocity to a node of the body                                                                   */ 
00781         void                            addVelocity(    const btVector3& velocity,
00782                 int node);
00783         /* Set mass                                                                                                                             */ 
00784         void                            setMass(                int node,
00785                 btScalar mass);
00786         /* Get mass                                                                                                                             */ 
00787         btScalar                        getMass(                int node) const;
00788         /* Get total mass                                                                                                               */ 
00789         btScalar                        getTotalMass() const;
00790         /* Set total mass (weighted by previous masses)                                                 */ 
00791         void                            setTotalMass(   btScalar mass,
00792                 bool fromfaces=false);
00793         /* Set total density                                                                                                    */ 
00794         void                            setTotalDensity(btScalar density);
00795         /* Set volume mass (using tetrahedrons)                                                                 */
00796         void                            setVolumeMass(          btScalar mass);
00797         /* Set volume density (using tetrahedrons)                                                              */
00798         void                            setVolumeDensity(       btScalar density);
00799         /* Transform                                                                                                                    */ 
00800         void                            transform(              const btTransform& trs);
00801         /* Translate                                                                                                                    */ 
00802         void                            translate(              const btVector3& trs);
00803         /* Rotate                                                                                                                       */ 
00804         void                            rotate( const btQuaternion& rot);
00805         /* Scale                                                                                                                                */ 
00806         void                            scale(  const btVector3& scl);
00807         /* Set current state as pose                                                                                    */ 
00808         void                            setPose(                bool bvolume,
00809                 bool bframe);
00810         /* Return the volume                                                                                                    */ 
00811         btScalar                        getVolume() const;
00812         /* Cluster count                                                                                                                */ 
00813         int                                     clusterCount() const;
00814         /* Cluster center of mass                                                                                               */ 
00815         static btVector3        clusterCom(const Cluster* cluster);
00816         btVector3                       clusterCom(int cluster) const;
00817         /* Cluster velocity at rpos                                                                                             */ 
00818         static btVector3        clusterVelocity(const Cluster* cluster,const btVector3& rpos);
00819         /* Cluster impulse                                                                                                              */ 
00820         static void                     clusterVImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
00821         static void                     clusterDImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
00822         static void                     clusterImpulse(Cluster* cluster,const btVector3& rpos,const Impulse& impulse);
00823         static void                     clusterVAImpulse(Cluster* cluster,const btVector3& impulse);
00824         static void                     clusterDAImpulse(Cluster* cluster,const btVector3& impulse);
00825         static void                     clusterAImpulse(Cluster* cluster,const Impulse& impulse);
00826         static void                     clusterDCImpulse(Cluster* cluster,const btVector3& impulse);
00827         /* Generate bending constraints based on distance in the adjency graph  */ 
00828         int                                     generateBendingConstraints(     int distance,
00829                 Material* mat=0);
00830         /* Randomize constraints to reduce solver bias                                                  */ 
00831         void                            randomizeConstraints();
00832         /* Release clusters                                                                                                             */ 
00833         void                            releaseCluster(int index);
00834         void                            releaseClusters();
00835         /* Generate clusters (K-mean)                                                                                   */ 
00838         int                                     generateClusters(int k,int maxiterations=8192);
00839         /* Refine                                                                                                                               */ 
00840         void                            refine(ImplicitFn* ifn,btScalar accurary,bool cut);
00841         /* CutLink                                                                                                                              */ 
00842         bool                            cutLink(int node0,int node1,btScalar position);
00843         bool                            cutLink(const Node* node0,const Node* node1,btScalar position);
00844 
00846         bool                            rayTest(const btVector3& rayFrom,
00847                 const btVector3& rayTo,
00848                 sRayCast& results);
00849         /* Solver presets                                                                                                               */ 
00850         void                            setSolver(eSolverPresets::_ preset);
00851         /* predictMotion                                                                                                                */ 
00852         void                            predictMotion(btScalar dt);
00853         /* solveConstraints                                                                                                             */ 
00854         void                            solveConstraints();
00855         /* staticSolve                                                                                                                  */ 
00856         void                            staticSolve(int iterations);
00857         /* solveCommonConstraints                                                                                               */ 
00858         static void                     solveCommonConstraints(btSoftBody** bodies,int count,int iterations);
00859         /* solveClusters                                                                                                                */ 
00860         static void                     solveClusters(const btAlignedObjectArray<btSoftBody*>& bodies);
00861         /* integrateMotion                                                                                                              */ 
00862         void                            integrateMotion();
00863         /* defaultCollisionHandlers                                                                                             */ 
00864         void                            defaultCollisionHandler(btCollisionObject* pco);
00865         void                            defaultCollisionHandler(btSoftBody* psb);
00866 
00867 
00868 
00869         //
00870         // Functionality to deal with new accelerated solvers.
00871         //
00872 
00876         void setWindVelocity( const btVector3 &velocity );
00877 
00878 
00882         const btVector3& getWindVelocity();
00883 
00884         //
00885         // Set the solver that handles this soft body
00886         // Should not be allowed to get out of sync with reality
00887         // Currently called internally on addition to the world
00888         void setSoftBodySolver( btSoftBodySolver *softBodySolver )
00889         {
00890                 m_softBodySolver = softBodySolver;
00891         }
00892 
00893         //
00894         // Return the solver that handles this soft body
00895         // 
00896         btSoftBodySolver *getSoftBodySolver()
00897         {
00898                 return m_softBodySolver;
00899         }
00900 
00901         //
00902         // Return the solver that handles this soft body
00903         // 
00904         btSoftBodySolver *getSoftBodySolver() const
00905         {
00906                 return m_softBodySolver;
00907         }
00908 
00909 
00910         //
00911         // Cast
00912         //
00913 
00914         static const btSoftBody*        upcast(const btCollisionObject* colObj)
00915         {
00916                 if (colObj->getInternalType()==CO_SOFT_BODY)
00917                         return (const btSoftBody*)colObj;
00918                 return 0;
00919         }
00920         static btSoftBody*                      upcast(btCollisionObject* colObj)
00921         {
00922                 if (colObj->getInternalType()==CO_SOFT_BODY)
00923                         return (btSoftBody*)colObj;
00924                 return 0;
00925         }
00926 
00927         //
00928         // ::btCollisionObject
00929         //
00930 
00931         virtual void getAabb(btVector3& aabbMin,btVector3& aabbMax) const
00932         {
00933                 aabbMin = m_bounds[0];
00934                 aabbMax = m_bounds[1];
00935         }
00936         //
00937         // Private
00938         //
00939         void                            pointersToIndices();
00940         void                            indicesToPointers(const int* map=0);
00941 
00942         int                                     rayTest(const btVector3& rayFrom,const btVector3& rayTo,
00943                 btScalar& mint,eFeature::_& feature,int& index,bool bcountonly) const;
00944         void                            initializeFaceTree();
00945         btVector3                       evaluateCom() const;
00946         bool                            checkContact(btCollisionObject* colObj,const btVector3& x,btScalar margin,btSoftBody::sCti& cti) const;
00947         void                            updateNormals();
00948         void                            updateBounds();
00949         void                            updatePose();
00950         void                            updateConstants();
00951         void                            initializeClusters();
00952         void                            updateClusters();
00953         void                            cleanupClusters();
00954         void                            prepareClusters(int iterations);
00955         void                            solveClusters(btScalar sor);
00956         void                            applyClusters(bool drift);
00957         void                            dampClusters();
00958         void                            applyForces();  
00959         static void                     PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti);
00960         static void                     PSolve_RContacts(btSoftBody* psb,btScalar kst,btScalar ti);
00961         static void                     PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti);
00962         static void                     PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti);
00963         static void                     VSolve_Links(btSoftBody* psb,btScalar kst);
00964         static psolver_t        getSolver(ePSolver::_ solver);
00965         static vsolver_t        getSolver(eVSolver::_ solver);
00966 
00967 
00968         virtual int     calculateSerializeBufferSize()  const;
00969 
00971         virtual const char*     serialize(void* dataBuffer,  class btSerializer* serializer) const;
00972 
00973         //virtual void serializeSingleObject(class btSerializer* serializer) const;
00974 
00975 
00976 };
00977 
00978 
00979 
00980 
00981 #endif //_BT_SOFT_BODY_H
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


bullet
Author(s): Erwin Coumans, ROS package maintained by Tully Foote
autogenerated on Wed Oct 31 2012 07:54:31