Bullet 2.85 update
[Torque-3d.git] / Engine / lib / bullet / src / BulletSoftBody / btSoftBody.h
blobbd5846bfb67b2c765cea0d00bc996b36b260c6d5
1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
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:
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.
15 ///btSoftBody implementation by Nathanael Presson
17 #ifndef _BT_SOFT_BODY_H
18 #define _BT_SOFT_BODY_H
20 #include "LinearMath/btAlignedObjectArray.h"
21 #include "LinearMath/btTransform.h"
22 #include "LinearMath/btIDebugDraw.h"
23 #include "BulletDynamics/Dynamics/btRigidBody.h"
25 #include "BulletCollision/CollisionShapes/btConcaveShape.h"
26 #include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
27 #include "btSparseSDF.h"
28 #include "BulletCollision/BroadphaseCollision/btDbvt.h"
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
38 class btBroadphaseInterface;
39 class btDispatcher;
40 class btSoftBodySolver;
42 /* btSoftBodyWorldInfo */
43 struct btSoftBodyWorldInfo
45 btScalar air_density;
46 btScalar water_density;
47 btScalar water_offset;
48 btScalar m_maxDisplacement;
49 btVector3 water_normal;
50 btBroadphaseInterface* m_broadphase;
51 btDispatcher* m_dispatcher;
52 btVector3 m_gravity;
53 btSparseSdf<3> m_sparsesdf;
55 btSoftBodyWorldInfo()
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)
66 };
69 ///The btSoftBody is an class to simulate cloth and volumetric soft bodies.
70 ///There is two-way interaction between btSoftBody and btRigidBody/btCollisionObject.
71 class btSoftBody : public btCollisionObject
73 public:
74 btAlignedObjectArray<const class btCollisionObject*> m_collisionDisabledObjects;
76 // The solver object that handles this soft body
77 btSoftBodySolver *m_softBodySolver;
80 // Enumerations
83 ///eAeroModel
84 struct eAeroModel { enum _ {
85 V_Point, ///Vertex normals are oriented toward velocity
86 V_TwoSided, ///Vertex normals are flipped to match velocity
87 V_TwoSidedLiftDrag, ///Vertex normals are flipped to match velocity and lift and drag forces are applied
88 V_OneSided, ///Vertex normals are taken as it is
89 F_TwoSided, ///Face normals are flipped to match velocity
90 F_TwoSidedLiftDrag, ///Face normals are flipped to match velocity and lift and drag forces are applied
91 F_OneSided, ///Face normals are taken as it is
92 END
93 };};
95 ///eVSolver : velocities solvers
96 struct eVSolver { enum _ {
97 Linear, ///Linear solver
98 END
99 };};
101 ///ePSolver : positions solvers
102 struct ePSolver { enum _ {
103 Linear, ///Linear solver
104 Anchors, ///Anchor solver
105 RContacts, ///Rigid contacts solver
106 SContacts, ///Soft contacts solver
108 };};
110 ///eSolverPresets
111 struct eSolverPresets { enum _ {
112 Positions,
113 Velocities,
114 Default = Positions,
116 };};
118 ///eFeature
119 struct eFeature { enum _ {
120 None,
121 Node,
122 Link,
123 Face,
124 Tetra,
126 };};
128 typedef btAlignedObjectArray<eVSolver::_> tVSolverArray;
129 typedef btAlignedObjectArray<ePSolver::_> tPSolverArray;
132 // Flags
135 ///fCollision
136 struct fCollision { enum _ {
137 RVSmask = 0x000f, ///Rigid versus soft mask
138 SDF_RS = 0x0001, ///SDF based rigid vs soft
139 CL_RS = 0x0002, ///Cluster vs convex rigid vs soft
141 SVSmask = 0x0030, ///Rigid versus soft mask
142 VF_SS = 0x0010, ///Vertex vs face soft vs soft handling
143 CL_SS = 0x0020, ///Cluster vs cluster soft vs soft handling
144 CL_SELF = 0x0040, ///Cluster soft body self collision
145 /* presets */
146 Default = SDF_RS,
148 };};
150 ///fMaterial
151 struct fMaterial { enum _ {
152 DebugDraw = 0x0001, /// Enable debug draw
153 /* presets */
154 Default = DebugDraw,
156 };};
159 // API Types
162 /* sRayCast */
163 struct sRayCast
165 btSoftBody* body; /// soft body
166 eFeature::_ feature; /// feature type
167 int index; /// feature index
168 btScalar fraction; /// time of impact fraction (rayorg+(rayto-rayfrom)*fraction)
171 /* ImplicitFn */
172 struct ImplicitFn
174 virtual ~ImplicitFn() {}
175 virtual btScalar Eval(const btVector3& x)=0;
179 // Internal types
182 typedef btAlignedObjectArray<btScalar> tScalarArray;
183 typedef btAlignedObjectArray<btVector3> tVector3Array;
185 /* sCti is Softbody contact info */
186 struct sCti
188 const btCollisionObject* m_colObj; /* Rigid body */
189 btVector3 m_normal; /* Outward normal */
190 btScalar m_offset; /* Offset from origin */
193 /* sMedium */
194 struct sMedium
196 btVector3 m_velocity; /* Velocity */
197 btScalar m_pressure; /* Pressure */
198 btScalar m_density; /* Density */
201 /* Base type */
202 struct Element
204 void* m_tag; // User data
205 Element() : m_tag(0) {}
207 /* Material */
208 struct Material : Element
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
216 /* Feature */
217 struct Feature : Element
219 Material* m_material; // Material
221 /* Node */
222 struct Node : Feature
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
234 /* Link */
235 struct Link : Feature
237 Node* m_n[2]; // Node pointers
238 btScalar m_rl; // Rest length
239 int m_bbending:1; // Bending link
240 btScalar m_c0; // (ima+imb)*kLST
241 btScalar m_c1; // rl^2
242 btScalar m_c2; // |gradient|^2/c0
243 btVector3 m_c3; // gradient
245 /* Face */
246 struct Face : Feature
248 Node* m_n[3]; // Node pointers
249 btVector3 m_normal; // Normal
250 btScalar m_ra; // Rest area
251 btDbvtNode* m_leaf; // Leaf data
253 /* Tetra */
254 struct Tetra : Feature
256 Node* m_n[4]; // Node pointers
257 btScalar m_rv; // Rest volume
258 btDbvtNode* m_leaf; // Leaf data
259 btVector3 m_c0[4]; // gradients
260 btScalar m_c1; // (4*kVST)/(im0+im1+im2+im3)
261 btScalar m_c2; // m_c1/sum(|g0..3|^2)
263 /* RContact */
264 struct RContact
266 sCti m_cti; // Contact infos
267 Node* m_node; // Owner node
268 btMatrix3x3 m_c0; // Impulse matrix
269 btVector3 m_c1; // Relative anchor
270 btScalar m_c2; // ima*dt
271 btScalar m_c3; // Friction
272 btScalar m_c4; // Hardness
274 /* SContact */
275 struct SContact
277 Node* m_node; // Node
278 Face* m_face; // Face
279 btVector3 m_weights; // Weigths
280 btVector3 m_normal; // Normal
281 btScalar m_margin; // Margin
282 btScalar m_friction; // Friction
283 btScalar m_cfm[2]; // Constraint force mixing
285 /* Anchor */
286 struct Anchor
288 Node* m_node; // Node pointer
289 btVector3 m_local; // Anchor position in body space
290 btRigidBody* m_body; // Body
291 btScalar m_influence;
292 btMatrix3x3 m_c0; // Impulse matrix
293 btVector3 m_c1; // Relative anchor
294 btScalar m_c2; // ima*dt
296 /* Note */
297 struct Note : Element
299 const char* m_text; // Text
300 btVector3 m_offset; // Offset
301 int m_rank; // Rank
302 Node* m_nodes[4]; // Nodes
303 btScalar m_coords[4]; // Coordinates
305 /* Pose */
306 struct Pose
308 bool m_bvolume; // Is valid
309 bool m_bframe; // Is frame
310 btScalar m_volume; // Rest volume
311 tVector3Array m_pos; // Reference positions
312 tScalarArray m_wgh; // Weights
313 btVector3 m_com; // COM
314 btMatrix3x3 m_rot; // Rotation
315 btMatrix3x3 m_scl; // Scale
316 btMatrix3x3 m_aqq; // Base scaling
318 /* Cluster */
319 struct Cluster
321 tScalarArray m_masses;
322 btAlignedObjectArray<Node*> m_nodes;
323 tVector3Array m_framerefs;
324 btTransform m_framexform;
325 btScalar m_idmass;
326 btScalar m_imass;
327 btMatrix3x3 m_locii;
328 btMatrix3x3 m_invwi;
329 btVector3 m_com;
330 btVector3 m_vimpulses[2];
331 btVector3 m_dimpulses[2];
332 int m_nvimpulses;
333 int m_ndimpulses;
334 btVector3 m_lv;
335 btVector3 m_av;
336 btDbvtNode* m_leaf;
337 btScalar m_ndamping; /* Node damping */
338 btScalar m_ldamping; /* Linear damping */
339 btScalar m_adamping; /* Angular damping */
340 btScalar m_matching;
341 btScalar m_maxSelfCollisionImpulse;
342 btScalar m_selfCollisionImpulseFactor;
343 bool m_containsAnchor;
344 bool m_collide;
345 int m_clusterIndex;
346 Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0)
347 ,m_maxSelfCollisionImpulse(100.f),
348 m_selfCollisionImpulseFactor(0.01f),
349 m_containsAnchor(false)
352 /* Impulse */
353 struct Impulse
355 btVector3 m_velocity;
356 btVector3 m_drift;
357 int m_asVelocity:1;
358 int m_asDrift:1;
359 Impulse() : m_velocity(0,0,0),m_drift(0,0,0),m_asVelocity(0),m_asDrift(0) {}
360 Impulse operator -() const
362 Impulse i=*this;
363 i.m_velocity=-i.m_velocity;
364 i.m_drift=-i.m_drift;
365 return(i);
367 Impulse operator*(btScalar x) const
369 Impulse i=*this;
370 i.m_velocity*=x;
371 i.m_drift*=x;
372 return(i);
375 /* Body */
376 struct Body
378 Cluster* m_soft;
379 btRigidBody* m_rigid;
380 const btCollisionObject* m_collisionObject;
382 Body() : m_soft(0),m_rigid(0),m_collisionObject(0) {}
383 Body(Cluster* p) : m_soft(p),m_rigid(0),m_collisionObject(0) {}
384 Body(const btCollisionObject* colObj) : m_soft(0),m_collisionObject(colObj)
386 m_rigid = (btRigidBody*)btRigidBody::upcast(m_collisionObject);
389 void activate() const
391 if(m_rigid)
392 m_rigid->activate();
393 if (m_collisionObject)
394 m_collisionObject->activate();
397 const btMatrix3x3& invWorldInertia() const
399 static const btMatrix3x3 iwi(0,0,0,0,0,0,0,0,0);
400 if(m_rigid) return(m_rigid->getInvInertiaTensorWorld());
401 if(m_soft) return(m_soft->m_invwi);
402 return(iwi);
404 btScalar invMass() const
406 if(m_rigid) return(m_rigid->getInvMass());
407 if(m_soft) return(m_soft->m_imass);
408 return(0);
410 const btTransform& xform() const
412 static const btTransform identity=btTransform::getIdentity();
413 if(m_collisionObject) return(m_collisionObject->getWorldTransform());
414 if(m_soft) return(m_soft->m_framexform);
415 return(identity);
417 btVector3 linearVelocity() const
419 if(m_rigid) return(m_rigid->getLinearVelocity());
420 if(m_soft) return(m_soft->m_lv);
421 return(btVector3(0,0,0));
423 btVector3 angularVelocity(const btVector3& rpos) const
425 if(m_rigid) return(btCross(m_rigid->getAngularVelocity(),rpos));
426 if(m_soft) return(btCross(m_soft->m_av,rpos));
427 return(btVector3(0,0,0));
429 btVector3 angularVelocity() const
431 if(m_rigid) return(m_rigid->getAngularVelocity());
432 if(m_soft) return(m_soft->m_av);
433 return(btVector3(0,0,0));
435 btVector3 velocity(const btVector3& rpos) const
437 return(linearVelocity()+angularVelocity(rpos));
439 void applyVImpulse(const btVector3& impulse,const btVector3& rpos) const
441 if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
442 if(m_soft) btSoftBody::clusterVImpulse(m_soft,rpos,impulse);
444 void applyDImpulse(const btVector3& impulse,const btVector3& rpos) const
446 if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
447 if(m_soft) btSoftBody::clusterDImpulse(m_soft,rpos,impulse);
449 void applyImpulse(const Impulse& impulse,const btVector3& rpos) const
451 if(impulse.m_asVelocity)
453 // printf("impulse.m_velocity = %f,%f,%f\n",impulse.m_velocity.getX(),impulse.m_velocity.getY(),impulse.m_velocity.getZ());
454 applyVImpulse(impulse.m_velocity,rpos);
456 if(impulse.m_asDrift)
458 // printf("impulse.m_drift = %f,%f,%f\n",impulse.m_drift.getX(),impulse.m_drift.getY(),impulse.m_drift.getZ());
459 applyDImpulse(impulse.m_drift,rpos);
462 void applyVAImpulse(const btVector3& impulse) const
464 if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
465 if(m_soft) btSoftBody::clusterVAImpulse(m_soft,impulse);
467 void applyDAImpulse(const btVector3& impulse) const
469 if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
470 if(m_soft) btSoftBody::clusterDAImpulse(m_soft,impulse);
472 void applyAImpulse(const Impulse& impulse) const
474 if(impulse.m_asVelocity) applyVAImpulse(impulse.m_velocity);
475 if(impulse.m_asDrift) applyDAImpulse(impulse.m_drift);
477 void applyDCImpulse(const btVector3& impulse) const
479 if(m_rigid) m_rigid->applyCentralImpulse(impulse);
480 if(m_soft) btSoftBody::clusterDCImpulse(m_soft,impulse);
483 /* Joint */
484 struct Joint
486 struct eType { enum _ {
487 Linear=0,
488 Angular,
489 Contact
490 };};
491 struct Specs
493 Specs() : erp(1),cfm(1),split(1) {}
494 btScalar erp;
495 btScalar cfm;
496 btScalar split;
498 Body m_bodies[2];
499 btVector3 m_refs[2];
500 btScalar m_cfm;
501 btScalar m_erp;
502 btScalar m_split;
503 btVector3 m_drift;
504 btVector3 m_sdrift;
505 btMatrix3x3 m_massmatrix;
506 bool m_delete;
507 virtual ~Joint() {}
508 Joint() : m_delete(false) {}
509 virtual void Prepare(btScalar dt,int iterations);
510 virtual void Solve(btScalar dt,btScalar sor)=0;
511 virtual void Terminate(btScalar dt)=0;
512 virtual eType::_ Type() const=0;
514 /* LJoint */
515 struct LJoint : Joint
517 struct Specs : Joint::Specs
519 btVector3 position;
521 btVector3 m_rpos[2];
522 void Prepare(btScalar dt,int iterations);
523 void Solve(btScalar dt,btScalar sor);
524 void Terminate(btScalar dt);
525 eType::_ Type() const { return(eType::Linear); }
527 /* AJoint */
528 struct AJoint : Joint
530 struct IControl
532 virtual ~IControl() {}
533 virtual void Prepare(AJoint*) {}
534 virtual btScalar Speed(AJoint*,btScalar current) { return(current); }
535 static IControl* Default() { static IControl def;return(&def); }
537 struct Specs : Joint::Specs
539 Specs() : icontrol(IControl::Default()) {}
540 btVector3 axis;
541 IControl* icontrol;
543 btVector3 m_axis[2];
544 IControl* m_icontrol;
545 void Prepare(btScalar dt,int iterations);
546 void Solve(btScalar dt,btScalar sor);
547 void Terminate(btScalar dt);
548 eType::_ Type() const { return(eType::Angular); }
550 /* CJoint */
551 struct CJoint : Joint
553 int m_life;
554 int m_maxlife;
555 btVector3 m_rpos[2];
556 btVector3 m_normal;
557 btScalar m_friction;
558 void Prepare(btScalar dt,int iterations);
559 void Solve(btScalar dt,btScalar sor);
560 void Terminate(btScalar dt);
561 eType::_ Type() const { return(eType::Contact); }
563 /* Config */
564 struct Config
566 eAeroModel::_ aeromodel; // Aerodynamic model (default: V_Point)
567 btScalar kVCF; // Velocities correction factor (Baumgarte)
568 btScalar kDP; // Damping coefficient [0,1]
569 btScalar kDG; // Drag coefficient [0,+inf]
570 btScalar kLF; // Lift coefficient [0,+inf]
571 btScalar kPR; // Pressure coefficient [-inf,+inf]
572 btScalar kVC; // Volume conversation coefficient [0,+inf]
573 btScalar kDF; // Dynamic friction coefficient [0,1]
574 btScalar kMT; // Pose matching coefficient [0,1]
575 btScalar kCHR; // Rigid contacts hardness [0,1]
576 btScalar kKHR; // Kinetic contacts hardness [0,1]
577 btScalar kSHR; // Soft contacts hardness [0,1]
578 btScalar kAHR; // Anchors hardness [0,1]
579 btScalar kSRHR_CL; // Soft vs rigid hardness [0,1] (cluster only)
580 btScalar kSKHR_CL; // Soft vs kinetic hardness [0,1] (cluster only)
581 btScalar kSSHR_CL; // Soft vs soft hardness [0,1] (cluster only)
582 btScalar kSR_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
583 btScalar kSK_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
584 btScalar kSS_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
585 btScalar maxvolume; // Maximum volume ratio for pose
586 btScalar timescale; // Time scale
587 int viterations; // Velocities solver iterations
588 int piterations; // Positions solver iterations
589 int diterations; // Drift solver iterations
590 int citerations; // Cluster solver iterations
591 int collisions; // Collisions flags
592 tVSolverArray m_vsequence; // Velocity solvers sequence
593 tPSolverArray m_psequence; // Position solvers sequence
594 tPSolverArray m_dsequence; // Drift solvers sequence
596 /* SolverState */
597 struct SolverState
599 btScalar sdt; // dt*timescale
600 btScalar isdt; // 1/sdt
601 btScalar velmrg; // velocity margin
602 btScalar radmrg; // radial margin
603 btScalar updmrg; // Update margin
605 /// RayFromToCaster takes a ray from, ray to (instead of direction!)
606 struct RayFromToCaster : btDbvt::ICollide
608 btVector3 m_rayFrom;
609 btVector3 m_rayTo;
610 btVector3 m_rayNormalizedDirection;
611 btScalar m_mint;
612 Face* m_face;
613 int m_tests;
614 RayFromToCaster(const btVector3& rayFrom,const btVector3& rayTo,btScalar mxt);
615 void Process(const btDbvtNode* leaf);
617 static inline btScalar rayFromToTriangle(const btVector3& rayFrom,
618 const btVector3& rayTo,
619 const btVector3& rayNormalizedDirection,
620 const btVector3& a,
621 const btVector3& b,
622 const btVector3& c,
623 btScalar maxt=SIMD_INFINITY);
627 // Typedefs
630 typedef void (*psolver_t)(btSoftBody*,btScalar,btScalar);
631 typedef void (*vsolver_t)(btSoftBody*,btScalar);
632 typedef btAlignedObjectArray<Cluster*> tClusterArray;
633 typedef btAlignedObjectArray<Note> tNoteArray;
634 typedef btAlignedObjectArray<Node> tNodeArray;
635 typedef btAlignedObjectArray<btDbvtNode*> tLeafArray;
636 typedef btAlignedObjectArray<Link> tLinkArray;
637 typedef btAlignedObjectArray<Face> tFaceArray;
638 typedef btAlignedObjectArray<Tetra> tTetraArray;
639 typedef btAlignedObjectArray<Anchor> tAnchorArray;
640 typedef btAlignedObjectArray<RContact> tRContactArray;
641 typedef btAlignedObjectArray<SContact> tSContactArray;
642 typedef btAlignedObjectArray<Material*> tMaterialArray;
643 typedef btAlignedObjectArray<Joint*> tJointArray;
644 typedef btAlignedObjectArray<btSoftBody*> tSoftBodyArray;
647 // Fields
650 Config m_cfg; // Configuration
651 SolverState m_sst; // Solver state
652 Pose m_pose; // Pose
653 void* m_tag; // User data
654 btSoftBodyWorldInfo* m_worldInfo; // World info
655 tNoteArray m_notes; // Notes
656 tNodeArray m_nodes; // Nodes
657 tLinkArray m_links; // Links
658 tFaceArray m_faces; // Faces
659 tTetraArray m_tetras; // Tetras
660 tAnchorArray m_anchors; // Anchors
661 tRContactArray m_rcontacts; // Rigid contacts
662 tSContactArray m_scontacts; // Soft contacts
663 tJointArray m_joints; // Joints
664 tMaterialArray m_materials; // Materials
665 btScalar m_timeacc; // Time accumulator
666 btVector3 m_bounds[2]; // Spatial bounds
667 bool m_bUpdateRtCst; // Update runtime constants
668 btDbvt m_ndbvt; // Nodes tree
669 btDbvt m_fdbvt; // Faces tree
670 btDbvt m_cdbvt; // Clusters tree
671 tClusterArray m_clusters; // Clusters
673 btAlignedObjectArray<bool>m_clusterConnectivity;//cluster connectivity, for self-collision
675 btTransform m_initialWorldTransform;
677 btVector3 m_windVelocity;
679 btScalar m_restLengthScale;
682 // Api
685 /* ctor */
686 btSoftBody( btSoftBodyWorldInfo* worldInfo,int node_count, const btVector3* x, const btScalar* m);
688 /* ctor */
689 btSoftBody( btSoftBodyWorldInfo* worldInfo);
691 void initDefaults();
693 /* dtor */
694 virtual ~btSoftBody();
695 /* Check for existing link */
697 btAlignedObjectArray<int> m_userIndexMapping;
699 btSoftBodyWorldInfo* getWorldInfo()
701 return m_worldInfo;
704 ///@todo: avoid internal softbody shape hack and move collision code to collision library
705 virtual void setCollisionShape(btCollisionShape* collisionShape)
710 bool checkLink( int node0,
711 int node1) const;
712 bool checkLink( const Node* node0,
713 const Node* node1) const;
714 /* Check for existring face */
715 bool checkFace( int node0,
716 int node1,
717 int node2) const;
718 /* Append material */
719 Material* appendMaterial();
720 /* Append note */
721 void appendNote( const char* text,
722 const btVector3& o,
723 const btVector4& c=btVector4(1,0,0,0),
724 Node* n0=0,
725 Node* n1=0,
726 Node* n2=0,
727 Node* n3=0);
728 void appendNote( const char* text,
729 const btVector3& o,
730 Node* feature);
731 void appendNote( const char* text,
732 const btVector3& o,
733 Link* feature);
734 void appendNote( const char* text,
735 const btVector3& o,
736 Face* feature);
737 /* Append node */
738 void appendNode( const btVector3& x,btScalar m);
739 /* Append link */
740 void appendLink(int model=-1,Material* mat=0);
741 void appendLink( int node0,
742 int node1,
743 Material* mat=0,
744 bool bcheckexist=false);
745 void appendLink( Node* node0,
746 Node* node1,
747 Material* mat=0,
748 bool bcheckexist=false);
749 /* Append face */
750 void appendFace(int model=-1,Material* mat=0);
751 void appendFace( int node0,
752 int node1,
753 int node2,
754 Material* mat=0);
755 void appendTetra(int model,Material* mat);
757 void appendTetra(int node0,
758 int node1,
759 int node2,
760 int node3,
761 Material* mat=0);
764 /* Append anchor */
765 void appendAnchor( int node,
766 btRigidBody* body, bool disableCollisionBetweenLinkedBodies=false,btScalar influence = 1);
767 void appendAnchor(int node,btRigidBody* body, const btVector3& localPivot,bool disableCollisionBetweenLinkedBodies=false,btScalar influence = 1);
768 /* Append linear joint */
769 void appendLinearJoint(const LJoint::Specs& specs,Cluster* body0,Body body1);
770 void appendLinearJoint(const LJoint::Specs& specs,Body body=Body());
771 void appendLinearJoint(const LJoint::Specs& specs,btSoftBody* body);
772 /* Append linear joint */
773 void appendAngularJoint(const AJoint::Specs& specs,Cluster* body0,Body body1);
774 void appendAngularJoint(const AJoint::Specs& specs,Body body=Body());
775 void appendAngularJoint(const AJoint::Specs& specs,btSoftBody* body);
776 /* Add force (or gravity) to the entire body */
777 void addForce( const btVector3& force);
778 /* Add force (or gravity) to a node of the body */
779 void addForce( const btVector3& force,
780 int node);
781 /* Add aero force to a node of the body */
782 void addAeroForceToNode(const btVector3& windVelocity,int nodeIndex);
784 /* Add aero force to a face of the body */
785 void addAeroForceToFace(const btVector3& windVelocity,int faceIndex);
787 /* Add velocity to the entire body */
788 void addVelocity( const btVector3& velocity);
790 /* Set velocity for the entire body */
791 void setVelocity( const btVector3& velocity);
793 /* Add velocity to a node of the body */
794 void addVelocity( const btVector3& velocity,
795 int node);
796 /* Set mass */
797 void setMass( int node,
798 btScalar mass);
799 /* Get mass */
800 btScalar getMass( int node) const;
801 /* Get total mass */
802 btScalar getTotalMass() const;
803 /* Set total mass (weighted by previous masses) */
804 void setTotalMass( btScalar mass,
805 bool fromfaces=false);
806 /* Set total density */
807 void setTotalDensity(btScalar density);
808 /* Set volume mass (using tetrahedrons) */
809 void setVolumeMass( btScalar mass);
810 /* Set volume density (using tetrahedrons) */
811 void setVolumeDensity( btScalar density);
812 /* Transform */
813 void transform( const btTransform& trs);
814 /* Translate */
815 void translate( const btVector3& trs);
816 /* Rotate */
817 void rotate( const btQuaternion& rot);
818 /* Scale */
819 void scale( const btVector3& scl);
820 /* Get link resting lengths scale */
821 btScalar getRestLengthScale();
822 /* Scale resting length of all springs */
823 void setRestLengthScale(btScalar restLength);
824 /* Set current state as pose */
825 void setPose( bool bvolume,
826 bool bframe);
827 /* Set current link lengths as resting lengths */
828 void resetLinkRestLengths();
829 /* Return the volume */
830 btScalar getVolume() const;
831 /* Cluster count */
832 int clusterCount() const;
833 /* Cluster center of mass */
834 static btVector3 clusterCom(const Cluster* cluster);
835 btVector3 clusterCom(int cluster) const;
836 /* Cluster velocity at rpos */
837 static btVector3 clusterVelocity(const Cluster* cluster,const btVector3& rpos);
838 /* Cluster impulse */
839 static void clusterVImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
840 static void clusterDImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
841 static void clusterImpulse(Cluster* cluster,const btVector3& rpos,const Impulse& impulse);
842 static void clusterVAImpulse(Cluster* cluster,const btVector3& impulse);
843 static void clusterDAImpulse(Cluster* cluster,const btVector3& impulse);
844 static void clusterAImpulse(Cluster* cluster,const Impulse& impulse);
845 static void clusterDCImpulse(Cluster* cluster,const btVector3& impulse);
846 /* Generate bending constraints based on distance in the adjency graph */
847 int generateBendingConstraints( int distance,
848 Material* mat=0);
849 /* Randomize constraints to reduce solver bias */
850 void randomizeConstraints();
851 /* Release clusters */
852 void releaseCluster(int index);
853 void releaseClusters();
854 /* Generate clusters (K-mean) */
855 ///generateClusters with k=0 will create a convex cluster for each tetrahedron or triangle
856 ///otherwise an approximation will be used (better performance)
857 int generateClusters(int k,int maxiterations=8192);
858 /* Refine */
859 void refine(ImplicitFn* ifn,btScalar accurary,bool cut);
860 /* CutLink */
861 bool cutLink(int node0,int node1,btScalar position);
862 bool cutLink(const Node* node0,const Node* node1,btScalar position);
864 ///Ray casting using rayFrom and rayTo in worldspace, (not direction!)
865 bool rayTest(const btVector3& rayFrom,
866 const btVector3& rayTo,
867 sRayCast& results);
868 /* Solver presets */
869 void setSolver(eSolverPresets::_ preset);
870 /* predictMotion */
871 void predictMotion(btScalar dt);
872 /* solveConstraints */
873 void solveConstraints();
874 /* staticSolve */
875 void staticSolve(int iterations);
876 /* solveCommonConstraints */
877 static void solveCommonConstraints(btSoftBody** bodies,int count,int iterations);
878 /* solveClusters */
879 static void solveClusters(const btAlignedObjectArray<btSoftBody*>& bodies);
880 /* integrateMotion */
881 void integrateMotion();
882 /* defaultCollisionHandlers */
883 void defaultCollisionHandler(const btCollisionObjectWrapper* pcoWrap);
884 void defaultCollisionHandler(btSoftBody* psb);
889 // Functionality to deal with new accelerated solvers.
893 * Set a wind velocity for interaction with the air.
895 void setWindVelocity( const btVector3 &velocity );
899 * Return the wind velocity for interaction with the air.
901 const btVector3& getWindVelocity();
904 // Set the solver that handles this soft body
905 // Should not be allowed to get out of sync with reality
906 // Currently called internally on addition to the world
907 void setSoftBodySolver( btSoftBodySolver *softBodySolver )
909 m_softBodySolver = softBodySolver;
913 // Return the solver that handles this soft body
915 btSoftBodySolver *getSoftBodySolver()
917 return m_softBodySolver;
921 // Return the solver that handles this soft body
923 btSoftBodySolver *getSoftBodySolver() const
925 return m_softBodySolver;
930 // Cast
933 static const btSoftBody* upcast(const btCollisionObject* colObj)
935 if (colObj->getInternalType()==CO_SOFT_BODY)
936 return (const btSoftBody*)colObj;
937 return 0;
939 static btSoftBody* upcast(btCollisionObject* colObj)
941 if (colObj->getInternalType()==CO_SOFT_BODY)
942 return (btSoftBody*)colObj;
943 return 0;
947 // ::btCollisionObject
950 virtual void getAabb(btVector3& aabbMin,btVector3& aabbMax) const
952 aabbMin = m_bounds[0];
953 aabbMax = m_bounds[1];
956 // Private
958 void pointersToIndices();
959 void indicesToPointers(const int* map=0);
961 int rayTest(const btVector3& rayFrom,const btVector3& rayTo,
962 btScalar& mint,eFeature::_& feature,int& index,bool bcountonly) const;
963 void initializeFaceTree();
964 btVector3 evaluateCom() const;
965 bool checkContact(const btCollisionObjectWrapper* colObjWrap,const btVector3& x,btScalar margin,btSoftBody::sCti& cti) const;
966 void updateNormals();
967 void updateBounds();
968 void updatePose();
969 void updateConstants();
970 void updateLinkConstants();
971 void updateArea(bool averageArea = true);
972 void initializeClusters();
973 void updateClusters();
974 void cleanupClusters();
975 void prepareClusters(int iterations);
976 void solveClusters(btScalar sor);
977 void applyClusters(bool drift);
978 void dampClusters();
979 void applyForces();
980 static void PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti);
981 static void PSolve_RContacts(btSoftBody* psb,btScalar kst,btScalar ti);
982 static void PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti);
983 static void PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti);
984 static void VSolve_Links(btSoftBody* psb,btScalar kst);
985 static psolver_t getSolver(ePSolver::_ solver);
986 static vsolver_t getSolver(eVSolver::_ solver);
989 virtual int calculateSerializeBufferSize() const;
991 ///fills the dataBuffer and returns the struct name (and 0 on failure)
992 virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
994 //virtual void serializeSingleObject(class btSerializer* serializer) const;
1002 #endif //_BT_SOFT_BODY_H