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