Bullet Collision Detection & Physics Library
btSoftBody.h
Go to the documentation of this file.
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 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.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
16 
17 #ifndef _BT_SOFT_BODY_H
18 #define _BT_SOFT_BODY_H
19 
21 #include "LinearMath/btTransform.h"
24 
27 #include "btSparseSDF.h"
29 
30 //#ifdef BT_USE_DOUBLE_PRECISION
31 //#define btRigidBodyData btRigidBodyDoubleData
32 //#define btRigidBodyDataName "btRigidBodyDoubleData"
33 //#else
34 #define btSoftBodyData btSoftBodyFloatData
35 #define btSoftBodyDataName "btSoftBodyFloatData"
36 //#endif //BT_USE_DOUBLE_PRECISION
37 
39 class btDispatcher;
40 class btSoftBodySolver;
41 
42 /* btSoftBodyWorldInfo */
44 {
54 
56  :air_density((btScalar)1.2),
57  water_density(0),
58  water_offset(0),
59  m_maxDisplacement(1000.f),//avoid soft body from 'exploding' so use some upper threshold of maximum motion that a node can travel per frame
60  water_normal(0,0,0),
61  m_broadphase(0),
62  m_dispatcher(0),
63  m_gravity(0,-10,0)
64  {
65  }
66 };
67 
68 
72 {
73 public:
75 
76  // The solver object that handles this soft body
78 
79  //
80  // Enumerations
81  //
82 
84  struct eAeroModel { enum _ {
92  END
93  };};
94 
96  struct eVSolver { enum _ {
98  END
99  };};
100 
102  struct ePSolver { enum _ {
107  END
108  };};
109 
111  struct eSolverPresets { enum _ {
114  Default = Positions,
115  END
116  };};
117 
119  struct eFeature { enum _ {
125  END
126  };};
127 
130 
131  //
132  // Flags
133  //
134 
136  struct fCollision { enum _ {
137  RVSmask = 0x000f,
138  SDF_RS = 0x0001,
139  CL_RS = 0x0002,
140 
141  SVSmask = 0x0030,
142  VF_SS = 0x0010,
143  CL_SS = 0x0020,
144  CL_SELF = 0x0040,
145  /* presets */
146  Default = SDF_RS,
147  END
148  };};
149 
151  struct fMaterial { enum _ {
152  DebugDraw = 0x0001,
153  /* presets */
154  Default = DebugDraw,
155  END
156  };};
157 
158  //
159  // API Types
160  //
161 
162  /* sRayCast */
163  struct sRayCast
164  {
167  int index;
169  };
170 
171  /* ImplicitFn */
172  struct ImplicitFn
173  {
174  virtual ~ImplicitFn() {}
175  virtual btScalar Eval(const btVector3& x)=0;
176  };
177 
178  //
179  // Internal types
180  //
181 
184 
185  /* sCti is Softbody contact info */
186  struct sCti
187  {
188  const btCollisionObject* m_colObj; /* Rigid body */
189  btVector3 m_normal; /* Outward normal */
190  btScalar m_offset; /* Offset from origin */
191  };
192 
193  /* sMedium */
194  struct sMedium
195  {
196  btVector3 m_velocity; /* Velocity */
197  btScalar m_pressure; /* Pressure */
198  btScalar m_density; /* Density */
199  };
200 
201  /* Base type */
202  struct Element
203  {
204  void* m_tag; // User data
205  Element() : m_tag(0) {}
206  };
207  /* Material */
208  struct Material : Element
209  {
210  btScalar m_kLST; // Linear stiffness coefficient [0,1]
211  btScalar m_kAST; // Area/Angular stiffness coefficient [0,1]
212  btScalar m_kVST; // Volume stiffness coefficient [0,1]
213  int m_flags; // Flags
214  };
215 
216  /* Feature */
217  struct Feature : Element
218  {
219  Material* m_material; // Material
220  };
221  /* Node */
222  struct Node : Feature
223  {
224  btVector3 m_x; // Position
225  btVector3 m_q; // Previous step position
226  btVector3 m_v; // Velocity
227  btVector3 m_f; // Force accumulator
228  btVector3 m_n; // Normal
229  btScalar m_im; // 1/mass
230  btScalar m_area; // Area
231  btDbvtNode* m_leaf; // Leaf data
232  int m_battach:1; // Attached
233  };
234  /* Link */
236  {
237  btVector3 m_c3; // gradient
238  Node* m_n[2]; // Node pointers
239  btScalar m_rl; // Rest length
240  int m_bbending:1; // Bending link
241  btScalar m_c0; // (ima+imb)*kLST
242  btScalar m_c1; // rl^2
243  btScalar m_c2; // |gradient|^2/c0
244 
246 
247  };
248  /* Face */
249  struct Face : Feature
250  {
251  Node* m_n[3]; // Node pointers
252  btVector3 m_normal; // Normal
253  btScalar m_ra; // Rest area
254  btDbvtNode* m_leaf; // Leaf data
255  };
256  /* Tetra */
257  struct Tetra : Feature
258  {
259  Node* m_n[4]; // Node pointers
260  btScalar m_rv; // Rest volume
261  btDbvtNode* m_leaf; // Leaf data
262  btVector3 m_c0[4]; // gradients
263  btScalar m_c1; // (4*kVST)/(im0+im1+im2+im3)
264  btScalar m_c2; // m_c1/sum(|g0..3|^2)
265  };
266  /* RContact */
267  struct RContact
268  {
269  sCti m_cti; // Contact infos
270  Node* m_node; // Owner node
271  btMatrix3x3 m_c0; // Impulse matrix
272  btVector3 m_c1; // Relative anchor
273  btScalar m_c2; // ima*dt
274  btScalar m_c3; // Friction
275  btScalar m_c4; // Hardness
276  };
277  /* SContact */
278  struct SContact
279  {
280  Node* m_node; // Node
281  Face* m_face; // Face
282  btVector3 m_weights; // Weigths
283  btVector3 m_normal; // Normal
284  btScalar m_margin; // Margin
285  btScalar m_friction; // Friction
286  btScalar m_cfm[2]; // Constraint force mixing
287  };
288  /* Anchor */
289  struct Anchor
290  {
291  Node* m_node; // Node pointer
292  btVector3 m_local; // Anchor position in body space
293  btRigidBody* m_body; // Body
295  btMatrix3x3 m_c0; // Impulse matrix
296  btVector3 m_c1; // Relative anchor
297  btScalar m_c2; // ima*dt
298  };
299  /* Note */
300  struct Note : Element
301  {
302  const char* m_text; // Text
303  btVector3 m_offset; // Offset
304  int m_rank; // Rank
305  Node* m_nodes[4]; // Nodes
306  btScalar m_coords[4]; // Coordinates
307  };
308  /* Pose */
309  struct Pose
310  {
311  bool m_bvolume; // Is valid
312  bool m_bframe; // Is frame
313  btScalar m_volume; // Rest volume
314  tVector3Array m_pos; // Reference positions
315  tScalarArray m_wgh; // Weights
316  btVector3 m_com; // COM
317  btMatrix3x3 m_rot; // Rotation
318  btMatrix3x3 m_scl; // Scale
319  btMatrix3x3 m_aqq; // Base scaling
320  };
321  /* Cluster */
322  struct Cluster
323  {
324  tScalarArray m_masses;
326  tVector3Array m_framerefs;
333  btVector3 m_vimpulses[2];
334  btVector3 m_dimpulses[2];
340  btScalar m_ndamping; /* Node damping */
341  btScalar m_ldamping; /* Linear damping */
342  btScalar m_adamping; /* Angular damping */
347  bool m_collide;
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)
353  {}
354  };
355  /* Impulse */
356  struct Impulse
357  {
360  int m_asVelocity:1;
361  int m_asDrift:1;
362  Impulse() : m_velocity(0,0,0),m_drift(0,0,0),m_asVelocity(0),m_asDrift(0) {}
364  {
365  Impulse i=*this;
366  i.m_velocity=-i.m_velocity;
367  i.m_drift=-i.m_drift;
368  return(i);
369  }
371  {
372  Impulse i=*this;
373  i.m_velocity*=x;
374  i.m_drift*=x;
375  return(i);
376  }
377  };
378  /* Body */
379  struct Body
380  {
384 
385  Body() : m_soft(0),m_rigid(0),m_collisionObject(0) {}
386  Body(Cluster* p) : m_soft(p),m_rigid(0),m_collisionObject(0) {}
387  Body(const btCollisionObject* colObj) : m_soft(0),m_collisionObject(colObj)
388  {
389  m_rigid = (btRigidBody*)btRigidBody::upcast(m_collisionObject);
390  }
391 
392  void activate() const
393  {
394  if(m_rigid)
395  m_rigid->activate();
396  if (m_collisionObject)
397  m_collisionObject->activate();
398 
399  }
401  {
402  static const btMatrix3x3 iwi(0,0,0,0,0,0,0,0,0);
403  if(m_rigid) return(m_rigid->getInvInertiaTensorWorld());
404  if(m_soft) return(m_soft->m_invwi);
405  return(iwi);
406  }
408  {
409  if(m_rigid) return(m_rigid->getInvMass());
410  if(m_soft) return(m_soft->m_imass);
411  return(0);
412  }
413  const btTransform& xform() const
414  {
415  static const btTransform identity=btTransform::getIdentity();
416  if(m_collisionObject) return(m_collisionObject->getWorldTransform());
417  if(m_soft) return(m_soft->m_framexform);
418  return(identity);
419  }
421  {
422  if(m_rigid) return(m_rigid->getLinearVelocity());
423  if(m_soft) return(m_soft->m_lv);
424  return(btVector3(0,0,0));
425  }
427  {
428  if(m_rigid) return(btCross(m_rigid->getAngularVelocity(),rpos));
429  if(m_soft) return(btCross(m_soft->m_av,rpos));
430  return(btVector3(0,0,0));
431  }
433  {
434  if(m_rigid) return(m_rigid->getAngularVelocity());
435  if(m_soft) return(m_soft->m_av);
436  return(btVector3(0,0,0));
437  }
438  btVector3 velocity(const btVector3& rpos) const
439  {
440  return(linearVelocity()+angularVelocity(rpos));
441  }
442  void applyVImpulse(const btVector3& impulse,const btVector3& rpos) const
443  {
444  if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
445  if(m_soft) btSoftBody::clusterVImpulse(m_soft,rpos,impulse);
446  }
447  void applyDImpulse(const btVector3& impulse,const btVector3& rpos) const
448  {
449  if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
450  if(m_soft) btSoftBody::clusterDImpulse(m_soft,rpos,impulse);
451  }
452  void applyImpulse(const Impulse& impulse,const btVector3& rpos) const
453  {
454  if(impulse.m_asVelocity)
455  {
456 // printf("impulse.m_velocity = %f,%f,%f\n",impulse.m_velocity.getX(),impulse.m_velocity.getY(),impulse.m_velocity.getZ());
457  applyVImpulse(impulse.m_velocity,rpos);
458  }
459  if(impulse.m_asDrift)
460  {
461 // printf("impulse.m_drift = %f,%f,%f\n",impulse.m_drift.getX(),impulse.m_drift.getY(),impulse.m_drift.getZ());
462  applyDImpulse(impulse.m_drift,rpos);
463  }
464  }
465  void applyVAImpulse(const btVector3& impulse) const
466  {
467  if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
468  if(m_soft) btSoftBody::clusterVAImpulse(m_soft,impulse);
469  }
470  void applyDAImpulse(const btVector3& impulse) const
471  {
472  if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
473  if(m_soft) btSoftBody::clusterDAImpulse(m_soft,impulse);
474  }
475  void applyAImpulse(const Impulse& impulse) const
476  {
477  if(impulse.m_asVelocity) applyVAImpulse(impulse.m_velocity);
478  if(impulse.m_asDrift) applyDAImpulse(impulse.m_drift);
479  }
480  void applyDCImpulse(const btVector3& impulse) const
481  {
482  if(m_rigid) m_rigid->applyCentralImpulse(impulse);
483  if(m_soft) btSoftBody::clusterDCImpulse(m_soft,impulse);
484  }
485  };
486  /* Joint */
487  struct Joint
488  {
489  struct eType { enum _ {
490  Linear=0,
492  Contact
493  };};
494  struct Specs
495  {
496  Specs() : erp(1),cfm(1),split(1) {}
500  };
501  Body m_bodies[2];
502  btVector3 m_refs[2];
509  bool m_delete;
510  virtual ~Joint() {}
511  Joint() : m_delete(false) {}
512  virtual void Prepare(btScalar dt,int iterations);
513  virtual void Solve(btScalar dt,btScalar sor)=0;
514  virtual void Terminate(btScalar dt)=0;
515  virtual eType::_ Type() const=0;
516  };
517  /* LJoint */
518  struct LJoint : Joint
519  {
521  {
523  };
524  btVector3 m_rpos[2];
525  void Prepare(btScalar dt,int iterations);
526  void Solve(btScalar dt,btScalar sor);
527  void Terminate(btScalar dt);
528  eType::_ Type() const { return(eType::Linear); }
529  };
530  /* AJoint */
531  struct AJoint : Joint
532  {
533  struct IControl
534  {
535  virtual ~IControl() {}
536  virtual void Prepare(AJoint*) {}
537  virtual btScalar Speed(AJoint*,btScalar current) { return(current); }
538  static IControl* Default() { static IControl def;return(&def); }
539  };
541  {
542  Specs() : icontrol(IControl::Default()) {}
545  };
546  btVector3 m_axis[2];
548  void Prepare(btScalar dt,int iterations);
549  void Solve(btScalar dt,btScalar sor);
550  void Terminate(btScalar dt);
551  eType::_ Type() const { return(eType::Angular); }
552  };
553  /* CJoint */
554  struct CJoint : Joint
555  {
556  int m_life;
558  btVector3 m_rpos[2];
561  void Prepare(btScalar dt,int iterations);
562  void Solve(btScalar dt,btScalar sor);
563  void Terminate(btScalar dt);
564  eType::_ Type() const { return(eType::Contact); }
565  };
566  /* Config */
567  struct Config
568  {
569  eAeroModel::_ aeromodel; // Aerodynamic model (default: V_Point)
570  btScalar kVCF; // Velocities correction factor (Baumgarte)
571  btScalar kDP; // Damping coefficient [0,1]
572  btScalar kDG; // Drag coefficient [0,+inf]
573  btScalar kLF; // Lift coefficient [0,+inf]
574  btScalar kPR; // Pressure coefficient [-inf,+inf]
575  btScalar kVC; // Volume conversation coefficient [0,+inf]
576  btScalar kDF; // Dynamic friction coefficient [0,1]
577  btScalar kMT; // Pose matching coefficient [0,1]
578  btScalar kCHR; // Rigid contacts hardness [0,1]
579  btScalar kKHR; // Kinetic contacts hardness [0,1]
580  btScalar kSHR; // Soft contacts hardness [0,1]
581  btScalar kAHR; // Anchors hardness [0,1]
582  btScalar kSRHR_CL; // Soft vs rigid hardness [0,1] (cluster only)
583  btScalar kSKHR_CL; // Soft vs kinetic hardness [0,1] (cluster only)
584  btScalar kSSHR_CL; // Soft vs soft hardness [0,1] (cluster only)
585  btScalar kSR_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
586  btScalar kSK_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
587  btScalar kSS_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
588  btScalar maxvolume; // Maximum volume ratio for pose
589  btScalar timescale; // Time scale
590  int viterations; // Velocities solver iterations
591  int piterations; // Positions solver iterations
592  int diterations; // Drift solver iterations
593  int citerations; // Cluster solver iterations
594  int collisions; // Collisions flags
595  tVSolverArray m_vsequence; // Velocity solvers sequence
596  tPSolverArray m_psequence; // Position solvers sequence
597  tPSolverArray m_dsequence; // Drift solvers sequence
598  };
599  /* SolverState */
600  struct SolverState
601  {
602  btScalar sdt; // dt*timescale
603  btScalar isdt; // 1/sdt
604  btScalar velmrg; // velocity margin
605  btScalar radmrg; // radial margin
606  btScalar updmrg; // Update margin
607  };
610  {
616  int m_tests;
617  RayFromToCaster(const btVector3& rayFrom,const btVector3& rayTo,btScalar mxt);
618  void Process(const btDbvtNode* leaf);
619 
620  static /*inline*/ btScalar rayFromToTriangle(const btVector3& rayFrom,
621  const btVector3& rayTo,
622  const btVector3& rayNormalizedDirection,
623  const btVector3& a,
624  const btVector3& b,
625  const btVector3& c,
626  btScalar maxt=SIMD_INFINITY);
627  };
628 
629  //
630  // Typedefs
631  //
632 
633  typedef void (*psolver_t)(btSoftBody*,btScalar,btScalar);
634  typedef void (*vsolver_t)(btSoftBody*,btScalar);
648 
649  //
650  // Fields
651  //
652 
653  Config m_cfg; // Configuration
654  SolverState m_sst; // Solver state
655  Pose m_pose; // Pose
656  void* m_tag; // User data
658  tNoteArray m_notes; // Notes
659  tNodeArray m_nodes; // Nodes
660  tLinkArray m_links; // Links
661  tFaceArray m_faces; // Faces
662  tTetraArray m_tetras; // Tetras
663  tAnchorArray m_anchors; // Anchors
664  tRContactArray m_rcontacts; // Rigid contacts
665  tSContactArray m_scontacts; // Soft contacts
666  tJointArray m_joints; // Joints
667  tMaterialArray m_materials; // Materials
668  btScalar m_timeacc; // Time accumulator
669  btVector3 m_bounds[2]; // Spatial bounds
670  bool m_bUpdateRtCst; // Update runtime constants
671  btDbvt m_ndbvt; // Nodes tree
672  btDbvt m_fdbvt; // Faces tree
673  btDbvt m_cdbvt; // Clusters tree
674  tClusterArray m_clusters; // Clusters
675 
676  btAlignedObjectArray<bool>m_clusterConnectivity;//cluster connectivity, for self-collision
677 
679 
681 
683 
684  //
685  // Api
686  //
687 
688  /* ctor */
689  btSoftBody( btSoftBodyWorldInfo* worldInfo,int node_count, const btVector3* x, const btScalar* m);
690 
691  /* ctor */
692  btSoftBody( btSoftBodyWorldInfo* worldInfo);
693 
694  void initDefaults();
695 
696  /* dtor */
697  virtual ~btSoftBody();
698  /* Check for existing link */
699 
701 
703  {
704  return m_worldInfo;
705  }
706 
708  virtual void setCollisionShape(btCollisionShape* collisionShape)
709  {
710 
711  }
712 
713  bool checkLink( int node0,
714  int node1) const;
715  bool checkLink( const Node* node0,
716  const Node* node1) const;
717  /* Check for existring face */
718  bool checkFace( int node0,
719  int node1,
720  int node2) const;
721  /* Append material */
722  Material* appendMaterial();
723  /* Append note */
724  void appendNote( const char* text,
725  const btVector3& o,
726  const btVector4& c=btVector4(1,0,0,0),
727  Node* n0=0,
728  Node* n1=0,
729  Node* n2=0,
730  Node* n3=0);
731  void appendNote( const char* text,
732  const btVector3& o,
733  Node* feature);
734  void appendNote( const char* text,
735  const btVector3& o,
736  Link* feature);
737  void appendNote( const char* text,
738  const btVector3& o,
739  Face* feature);
740  /* Append node */
741  void appendNode( const btVector3& x,btScalar m);
742  /* Append link */
743  void appendLink(int model=-1,Material* mat=0);
744  void appendLink( int node0,
745  int node1,
746  Material* mat=0,
747  bool bcheckexist=false);
748  void appendLink( Node* node0,
749  Node* node1,
750  Material* mat=0,
751  bool bcheckexist=false);
752  /* Append face */
753  void appendFace(int model=-1,Material* mat=0);
754  void appendFace( int node0,
755  int node1,
756  int node2,
757  Material* mat=0);
758  void appendTetra(int model,Material* mat);
759  //
760  void appendTetra(int node0,
761  int node1,
762  int node2,
763  int node3,
764  Material* mat=0);
765 
766 
767  /* Append anchor */
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);
771  /* Append linear joint */
772  void appendLinearJoint(const LJoint::Specs& specs,Cluster* body0,Body body1);
773  void appendLinearJoint(const LJoint::Specs& specs,Body body=Body());
774  void appendLinearJoint(const LJoint::Specs& specs,btSoftBody* body);
775  /* Append linear joint */
776  void appendAngularJoint(const AJoint::Specs& specs,Cluster* body0,Body body1);
777  void appendAngularJoint(const AJoint::Specs& specs,Body body=Body());
778  void appendAngularJoint(const AJoint::Specs& specs,btSoftBody* body);
779  /* Add force (or gravity) to the entire body */
780  void addForce( const btVector3& force);
781  /* Add force (or gravity) to a node of the body */
782  void addForce( const btVector3& force,
783  int node);
784  /* Add aero force to a node of the body */
785  void addAeroForceToNode(const btVector3& windVelocity,int nodeIndex);
786 
787  /* Add aero force to a face of the body */
788  void addAeroForceToFace(const btVector3& windVelocity,int faceIndex);
789 
790  /* Add velocity to the entire body */
791  void addVelocity( const btVector3& velocity);
792 
793  /* Set velocity for the entire body */
794  void setVelocity( const btVector3& velocity);
795 
796  /* Add velocity to a node of the body */
797  void addVelocity( const btVector3& velocity,
798  int node);
799  /* Set mass */
800  void setMass( int node,
801  btScalar mass);
802  /* Get mass */
803  btScalar getMass( int node) const;
804  /* Get total mass */
805  btScalar getTotalMass() const;
806  /* Set total mass (weighted by previous masses) */
807  void setTotalMass( btScalar mass,
808  bool fromfaces=false);
809  /* Set total density */
810  void setTotalDensity(btScalar density);
811  /* Set volume mass (using tetrahedrons) */
812  void setVolumeMass( btScalar mass);
813  /* Set volume density (using tetrahedrons) */
814  void setVolumeDensity( btScalar density);
815  /* Transform */
816  void transform( const btTransform& trs);
817  /* Translate */
818  void translate( const btVector3& trs);
819  /* Rotate */
820  void rotate( const btQuaternion& rot);
821  /* Scale */
822  void scale( const btVector3& scl);
823  /* Get link resting lengths scale */
824  btScalar getRestLengthScale();
825  /* Scale resting length of all springs */
826  void setRestLengthScale(btScalar restLength);
827  /* Set current state as pose */
828  void setPose( bool bvolume,
829  bool bframe);
830  /* Set current link lengths as resting lengths */
831  void resetLinkRestLengths();
832  /* Return the volume */
833  btScalar getVolume() const;
834  /* Cluster count */
835  int clusterCount() const;
836  /* Cluster center of mass */
837  static btVector3 clusterCom(const Cluster* cluster);
838  btVector3 clusterCom(int cluster) const;
839  /* Cluster velocity at rpos */
840  static btVector3 clusterVelocity(const Cluster* cluster,const btVector3& rpos);
841  /* Cluster impulse */
842  static void clusterVImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
843  static void clusterDImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
844  static void clusterImpulse(Cluster* cluster,const btVector3& rpos,const Impulse& impulse);
845  static void clusterVAImpulse(Cluster* cluster,const btVector3& impulse);
846  static void clusterDAImpulse(Cluster* cluster,const btVector3& impulse);
847  static void clusterAImpulse(Cluster* cluster,const Impulse& impulse);
848  static void clusterDCImpulse(Cluster* cluster,const btVector3& impulse);
849  /* Generate bending constraints based on distance in the adjency graph */
850  int generateBendingConstraints( int distance,
851  Material* mat=0);
852  /* Randomize constraints to reduce solver bias */
853  void randomizeConstraints();
854  /* Release clusters */
855  void releaseCluster(int index);
856  void releaseClusters();
857  /* Generate clusters (K-mean) */
860  int generateClusters(int k,int maxiterations=8192);
861  /* Refine */
862  void refine(ImplicitFn* ifn,btScalar accurary,bool cut);
863  /* CutLink */
864  bool cutLink(int node0,int node1,btScalar position);
865  bool cutLink(const Node* node0,const Node* node1,btScalar position);
866 
868  bool rayTest(const btVector3& rayFrom,
869  const btVector3& rayTo,
870  sRayCast& results);
871  /* Solver presets */
872  void setSolver(eSolverPresets::_ preset);
873  /* predictMotion */
874  void predictMotion(btScalar dt);
875  /* solveConstraints */
876  void solveConstraints();
877  /* staticSolve */
878  void staticSolve(int iterations);
879  /* solveCommonConstraints */
880  static void solveCommonConstraints(btSoftBody** bodies,int count,int iterations);
881  /* solveClusters */
882  static void solveClusters(const btAlignedObjectArray<btSoftBody*>& bodies);
883  /* integrateMotion */
884  void integrateMotion();
885  /* defaultCollisionHandlers */
886  void defaultCollisionHandler(const btCollisionObjectWrapper* pcoWrap);
887  void defaultCollisionHandler(btSoftBody* psb);
888 
889 
890 
891  //
892  // Functionality to deal with new accelerated solvers.
893  //
894 
898  void setWindVelocity( const btVector3 &velocity );
899 
900 
904  const btVector3& getWindVelocity();
905 
906  //
907  // Set the solver that handles this soft body
908  // Should not be allowed to get out of sync with reality
909  // Currently called internally on addition to the world
910  void setSoftBodySolver( btSoftBodySolver *softBodySolver )
911  {
912  m_softBodySolver = softBodySolver;
913  }
914 
915  //
916  // Return the solver that handles this soft body
917  //
919  {
920  return m_softBodySolver;
921  }
922 
923  //
924  // Return the solver that handles this soft body
925  //
927  {
928  return m_softBodySolver;
929  }
930 
931 
932  //
933  // Cast
934  //
935 
936  static const btSoftBody* upcast(const btCollisionObject* colObj)
937  {
938  if (colObj->getInternalType()==CO_SOFT_BODY)
939  return (const btSoftBody*)colObj;
940  return 0;
941  }
942  static btSoftBody* upcast(btCollisionObject* colObj)
943  {
944  if (colObj->getInternalType()==CO_SOFT_BODY)
945  return (btSoftBody*)colObj;
946  return 0;
947  }
948 
949  //
950  // ::btCollisionObject
951  //
952 
953  virtual void getAabb(btVector3& aabbMin,btVector3& aabbMax) const
954  {
955  aabbMin = m_bounds[0];
956  aabbMax = m_bounds[1];
957  }
958  //
959  // Private
960  //
961  void pointersToIndices();
962  void indicesToPointers(const int* map=0);
963 
964  int rayTest(const btVector3& rayFrom,const btVector3& rayTo,
965  btScalar& mint,eFeature::_& feature,int& index,bool bcountonly) const;
966  void initializeFaceTree();
967  btVector3 evaluateCom() const;
968  bool checkContact(const btCollisionObjectWrapper* colObjWrap,const btVector3& x,btScalar margin,btSoftBody::sCti& cti) const;
969  void updateNormals();
970  void updateBounds();
971  void updatePose();
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);
981  void dampClusters();
982  void applyForces();
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);
988  static psolver_t getSolver(ePSolver::_ solver);
989  static vsolver_t getSolver(eVSolver::_ solver);
990 
991 
992  virtual int calculateSerializeBufferSize() const;
993 
995  virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
996 
997  //virtual void serializeSingleObject(class btSerializer* serializer) const;
998 
999 
1000 };
1001 
1002 
1003 
1004 
1005 #endif //_BT_SOFT_BODY_H
btScalar getInvMass() const
Definition: btRigidBody.h:273
const btCollisionObject * m_colObj
Definition: btSoftBody.h:188
btVector3 m_velocity
Definition: btSoftBody.h:358
static const btRigidBody * upcast(const btCollisionObject *colObj)
to keep collision detection and dynamics separate we don&#39;t store a rigidbody pointer but a rigidbody ...
Definition: btRigidBody.h:203
btMatrix3x3 m_scl
Definition: btSoftBody.h:318
Impulse operator*(btScalar x) const
Definition: btSoftBody.h:370
eFeature::_ feature
soft body
Definition: btSoftBody.h:166
Rigid contacts solver.
Definition: btSoftBody.h:106
btScalar kSS_SPLT_CL
Definition: btSoftBody.h:587
btAlignedObjectArray< Link > tLinkArray
Definition: btSoftBody.h:639
int index
feature type
Definition: btSoftBody.h:167
Vertex normals are oriented toward velocity.
Definition: btSoftBody.h:86
btScalar m_maxDisplacement
Definition: btSoftBody.h:48
Config m_cfg
Definition: btSoftBody.h:653
btMatrix3x3 m_c0
Definition: btSoftBody.h:271
btVector3 linearVelocity() const
Definition: btSoftBody.h:420
btVector3 m_normal
Definition: btSoftBody.h:189
Body(Cluster *p)
Definition: btSoftBody.h:386
btScalar water_offset
Definition: btSoftBody.h:47
void applyTorqueImpulse(const btVector3 &torque)
Definition: btRigidBody.h:329
btMatrix3x3 m_locii
Definition: btSoftBody.h:330
btAlignedObjectArray< ePSolver::_ > tPSolverArray
Definition: btSoftBody.h:129
btVector3 angularVelocity() const
Definition: btSoftBody.h:432
Vertex normals are flipped to match velocity.
Definition: btSoftBody.h:87
btScalar m_restLengthScale
Definition: btSoftBody.h:682
Cluster * m_soft
Definition: btSoftBody.h:381
tVector3Array m_framerefs
Definition: btSoftBody.h:326
btAlignedObjectArray< btVector3 > tVector3Array
Definition: btSoftBody.h:183
Body(const btCollisionObject *colObj)
Definition: btSoftBody.h:387
btScalar kSK_SPLT_CL
Definition: btSoftBody.h:586
int getInternalType() const
reserved for Bullet internal usage
btMatrix3x3 m_c0
Definition: btSoftBody.h:295
tJointArray m_joints
Definition: btSoftBody.h:666
btAlignedObjectArray< bool > m_clusterConnectivity
Definition: btSoftBody.h:676
static int split(btDbvtNode **leaves, int count, const btVector3 &org, const btVector3 &axis)
Definition: btDbvt.cpp:243
btScalar m_split
Definition: btSoftBody.h:505
btAlignedObjectArray< Cluster * > tClusterArray
Definition: btSoftBody.h:635
btVector3 angularVelocity(const btVector3 &rpos) const
Definition: btSoftBody.h:426
btAlignedObjectArray< Node * > m_nodes
Definition: btSoftBody.h:325
btAlignedObjectArray< btScalar > tScalarArray
Definition: btSoftBody.h:182
static void clusterVImpulse(Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse)
Definition: btSoftBody.cpp:976
btDispatcher * m_dispatcher
Definition: btSoftBody.h:51
The btDbvt class implements a fast dynamic bounding volume tree based on axis aligned bounding boxes ...
Definition: btDbvt.h:198
The btCollisionShape class provides an interface for collision shapes that can be shared among btColl...
void * m_tag
Definition: btSoftBody.h:656
btScalar fraction
feature index
Definition: btSoftBody.h:168
btVector3 m_windVelocity
Definition: btSoftBody.h:680
virtual btScalar Speed(AJoint *, btScalar current)
Definition: btSoftBody.h:537
const btMatrix3x3 & invWorldInertia() const
Definition: btSoftBody.h:400
tSContactArray m_scontacts
Definition: btSoftBody.h:665
btAlignedObjectArray< Face > tFaceArray
Definition: btSoftBody.h:640
btAlignedObjectArray< RContact > tRContactArray
Definition: btSoftBody.h:643
btDbvt m_fdbvt
Definition: btSoftBody.h:672
btAlignedObjectArray< int > m_userIndexMapping
Definition: btSoftBody.h:700
static IControl * Default()
Definition: btSoftBody.h:538
btAlignedObjectArray< Tetra > tTetraArray
Definition: btSoftBody.h:641
btVector3 water_normal
Definition: btSoftBody.h:49
const btTransform & xform() const
Definition: btSoftBody.h:413
btMatrix3x3 m_aqq
Definition: btSoftBody.h:319
Vertex normals are taken as it is.
Definition: btSoftBody.h:89
btTransform m_initialWorldTransform
Definition: btSoftBody.h:678
btDbvtNode * m_leaf
Definition: btSoftBody.h:254
static btSoftBody * upcast(btCollisionObject *colObj)
Definition: btSoftBody.h:942
tNodeArray m_nodes
Definition: btSoftBody.h:659
tLinkArray m_links
Definition: btSoftBody.h:660
btVector3 m_normal
Definition: btSoftBody.h:252
btAlignedObjectArray< btDbvtNode * > tLeafArray
Definition: btSoftBody.h:638
btSoftBodyWorldInfo * m_worldInfo
Definition: btSoftBody.h:657
tTetraArray m_tetras
Definition: btSoftBody.h:662
virtual void getAabb(btVector3 &aabbMin, btVector3 &aabbMax) const
Definition: btSoftBody.h:953
btSparseSdf< 3 > m_sparsesdf
Definition: btSoftBody.h:53
const char * m_text
Definition: btSoftBody.h:302
btVector3 btCross(const btVector3 &v1, const btVector3 &v2)
Return the cross product of two vectors.
Definition: btVector3.h:933
virtual void setCollisionShape(btCollisionShape *collisionShape)
Definition: btSoftBody.h:708
#define SIMD_INFINITY
Definition: btScalar.h:522
btTransform & getWorldTransform()
Material * m_material
Definition: btSoftBody.h:219
void applyDImpulse(const btVector3 &impulse, const btVector3 &rpos) const
Definition: btSoftBody.h:447
btVector3 m_offset
Definition: btSoftBody.h:303
btScalar kSR_SPLT_CL
Definition: btSoftBody.h:585
btSoftBodyWorldInfo * getWorldInfo()
Definition: btSoftBody.h:702
virtual ~Joint()
Definition: btSoftBody.h:510
btVector3 m_sdrift
Definition: btSoftBody.h:507
btVector3 m_normal
Definition: btSoftBody.h:559
btVector3 m_velocity
Definition: btSoftBody.h:196
Vertex normals are flipped to match velocity and lift and drag forces are applied.
Definition: btSoftBody.h:88
btAlignedObjectArray< Material * > tMaterialArray
Definition: btSoftBody.h:645
tMaterialArray m_materials
Definition: btSoftBody.h:667
static void clusterDImpulse(Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse)
Definition: btSoftBody.cpp:986
btSoftBodySolver * getSoftBodySolver() const
Definition: btSoftBody.h:926
static const btSoftBody * upcast(const btCollisionObject *colObj)
Definition: btSoftBody.h:936
const btCollisionObject * m_collisionObject
Definition: btSoftBody.h:383
btMatrix3x3 m_invwi
Definition: btSoftBody.h:331
RayFromToCaster takes a ray from, ray to (instead of direction!)
Definition: btSoftBody.h:609
eVSolver : velocities solvers
Definition: btSoftBody.h:96
btSoftBodySolver * getSoftBodySolver()
Definition: btSoftBody.h:918
const btVector3 & getAngularVelocity() const
Definition: btRigidBody.h:365
btCollisionObject can be used to manage collision detection objects.
static void clusterVAImpulse(Cluster *cluster, const btVector3 &impulse)
tAnchorArray m_anchors
Definition: btSoftBody.h:663
btDbvtNode * m_leaf
Definition: btSoftBody.h:261
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:62
btScalar m_influence
Definition: btSoftBody.h:294
Pose m_pose
Definition: btSoftBody.h:655
tPSolverArray m_dsequence
Definition: btSoftBody.h:597
btScalar invMass() const
Definition: btSoftBody.h:407
The btBroadphaseInterface class provides an interface to detect aabb-overlapping object pairs...
btScalar m_maxSelfCollisionImpulse
Definition: btSoftBody.h:344
void activate(bool forceActivation=false) const
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:83
#define ATTRIBUTE_ALIGNED16(a)
Definition: btScalar.h:82
btAlignedObjectArray< Note > tNoteArray
Definition: btSoftBody.h:636
void activate() const
Definition: btSoftBody.h:392
btScalar m_offset
Definition: btSoftBody.h:190
void applyVImpulse(const btVector3 &impulse, const btVector3 &rpos) const
Definition: btSoftBody.h:442
btVector3 m_com
Definition: btSoftBody.h:316
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:34
btAlignedObjectArray< btSoftBody * > tSoftBodyArray
Definition: btSoftBody.h:647
eType::_ Type() const
Definition: btSoftBody.h:564
btAlignedObjectArray< SContact > tSContactArray
Definition: btSoftBody.h:644
ePSolver : positions solvers
Definition: btSoftBody.h:102
btMatrix3x3 operator-(const btMatrix3x3 &m1, const btMatrix3x3 &m2)
Definition: btMatrix3x3.h:954
btDbvt m_cdbvt
Definition: btSoftBody.h:673
btAlignedObjectArray< Joint * > tJointArray
Definition: btSoftBody.h:646
tNoteArray m_notes
Definition: btSoftBody.h:658
virtual void Prepare(AJoint *)
Definition: btSoftBody.h:536
static const btTransform & getIdentity()
Return an identity transform.
Definition: btTransform.h:203
Face normals are flipped to match velocity.
Definition: btSoftBody.h:90
void applyDCImpulse(const btVector3 &impulse) const
Definition: btSoftBody.h:480
btDbvt m_ndbvt
Definition: btSoftBody.h:671
btVector3 m_n
Definition: btSoftBody.h:228
btVector3 m_local
Definition: btSoftBody.h:292
btDbvtNode * m_leaf
Definition: btSoftBody.h:339
btScalar timescale
Definition: btSoftBody.h:589
SolverState m_sst
Definition: btSoftBody.h:654
Face normals are flipped to match velocity and lift and drag forces are applied.
Definition: btSoftBody.h:91
tClusterArray m_clusters
Definition: btSoftBody.h:674
btSoftBody * body
Definition: btSoftBody.h:165
#define BT_DECLARE_ALIGNED_ALLOCATOR()
Definition: btScalar.h:403
btMatrix3x3 m_rot
Definition: btSoftBody.h:317
void setSoftBodySolver(btSoftBodySolver *softBodySolver)
Definition: btSoftBody.h:910
void applyVAImpulse(const btVector3 &impulse) const
Definition: btSoftBody.h:465
const btMatrix3x3 & getInvInertiaTensorWorld() const
Definition: btRigidBody.h:274
void applyCentralImpulse(const btVector3 &impulse)
Definition: btRigidBody.h:324
btMatrix3x3 m_massmatrix
Definition: btSoftBody.h:508
btScalar water_density
Definition: btSoftBody.h:46
btScalar m_volume
Definition: btSoftBody.h:313
btVector3 m_v
Definition: btSoftBody.h:226
tVSolverArray m_vsequence
Definition: btSoftBody.h:595
void applyImpulse(const Impulse &impulse, const btVector3 &rpos) const
Definition: btSoftBody.h:452
btScalar m_timeacc
Definition: btSoftBody.h:668
tPSolverArray m_psequence
Definition: btSoftBody.h:596
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:48
eType::_ Type() const
Definition: btSoftBody.h:551
tScalarArray m_wgh
Definition: btSoftBody.h:315
const btVector3 & getLinearVelocity() const
Definition: btRigidBody.h:362
IControl * m_icontrol
Definition: btSoftBody.h:547
btBroadphaseInterface * m_broadphase
Definition: btSoftBody.h:50
eAeroModel::_ aeromodel
Definition: btSoftBody.h:569
btScalar air_density
Definition: btSoftBody.h:45
void applyImpulse(const btVector3 &impulse, const btVector3 &rel_pos)
Definition: btRigidBody.h:334
btSoftBodySolver * m_softBodySolver
Definition: btSoftBody.h:77
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
Definition: btQuaternion.h:55
btVector3 m_q
Definition: btSoftBody.h:225
btAlignedObjectArray< const class btCollisionObject * > m_collisionDisabledObjects
Definition: btSoftBody.h:74
btScalar m_selfCollisionImpulseFactor
Definition: btSoftBody.h:345
btVector3 m_f
Definition: btSoftBody.h:227
btVector3 m_gravity
Definition: btSoftBody.h:52
bool m_bUpdateRtCst
Definition: btSoftBody.h:670
tScalarArray m_masses
Definition: btSoftBody.h:324
The btSoftBody is an class to simulate cloth and volumetric soft bodies.
Definition: btSoftBody.h:71
btAlignedObjectArray< Node > tNodeArray
Definition: btSoftBody.h:637
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
Definition: btDispatcher.h:77
static void clusterDCImpulse(Cluster *cluster, const btVector3 &impulse)
btRigidBody * m_body
Definition: btSoftBody.h:293
btVector3 m_drift
Definition: btSoftBody.h:506
btRigidBody * m_rigid
Definition: btSoftBody.h:382
void applyAImpulse(const Impulse &impulse) const
Definition: btSoftBody.h:475
void applyDAImpulse(const btVector3 &impulse) const
Definition: btSoftBody.h:470
btVector3 m_x
Definition: btSoftBody.h:224
tRContactArray m_rcontacts
Definition: btSoftBody.h:664
btAlignedObjectArray< Anchor > tAnchorArray
Definition: btSoftBody.h:642
btScalar maxvolume
Definition: btSoftBody.h:588
btScalar m_area
Definition: btSoftBody.h:230
btVector3 m_rayNormalizedDirection
Definition: btSoftBody.h:613
btAlignedObjectArray< eVSolver::_ > tVSolverArray
Definition: btSoftBody.h:128
btVector3 velocity(const btVector3 &rpos) const
Definition: btSoftBody.h:438
static void clusterDAImpulse(Cluster *cluster, const btVector3 &impulse)
btDbvtNode * m_leaf
Definition: btSoftBody.h:231
btTransform m_framexform
Definition: btSoftBody.h:327
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:292
btScalar m_friction
Definition: btSoftBody.h:560
tVector3Array m_pos
Definition: btSoftBody.h:314
eType::_ Type() const
Definition: btSoftBody.h:528
tFaceArray m_faces
Definition: btSoftBody.h:661