Bullet Collision Detection & Physics Library
btSoftBody.h
Go to the documentation of this file.
1/*
2Bullet Continuous Collision Detection and Physics Library
3Copyright (c) 2003-2006 Erwin Coumans https://bulletphysics.org
4
5This software is provided 'as-is', without any express or implied warranty.
6In no event will the authors be held liable for any damages arising from the use of this software.
7Permission is granted to anyone to use this software for any purpose,
8including commercial applications, and to alter it and redistribute it freely,
9subject to the following restrictions:
10
111. 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.
122. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
133. 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
25
28#include "btSparseSDF.h"
32//#ifdef BT_USE_DOUBLE_PRECISION
33//#define btRigidBodyData btRigidBodyDoubleData
34//#define btRigidBodyDataName "btRigidBodyDoubleData"
35//#else
36#define btSoftBodyData btSoftBodyFloatData
37#define btSoftBodyDataName "btSoftBodyFloatData"
39static unsigned long seed = 243703;
40//#endif //BT_USE_DOUBLE_PRECISION
41
43class btDispatcher;
45
46/* btSoftBodyWorldInfo */
48{
58
60 : air_density((btScalar)1.2),
62 water_offset(0),
63 m_maxDisplacement(1000.f), //avoid soft body from 'exploding' so use some upper threshold of maximum motion that a node can travel per frame
64 water_normal(0, 0, 0),
65 m_broadphase(0),
66 m_dispatcher(0),
67 m_gravity(0, -10, 0)
68 {
69 }
70};
71
75{
76public:
78
79 // The solver object that handles this soft body
81
82 //
83 // Enumerations
84 //
85
88 {
89 enum _
90 {
98 END
99 };
100 };
101
103 struct eVSolver
104 {
105 enum _
106 {
108 END
109 };
110 };
111
113 struct ePSolver
114 {
115 enum _
116 {
121 END
122 };
123 };
124
127 {
128 enum _
129 {
133 END
134 };
135 };
136
138 struct eFeature
139 {
140 enum _
141 {
147 END
148 };
149 };
150
153
154 //
155 // Flags
156 //
157
160 {
161 enum _
162 {
163 RVSmask = 0x000f,
164 SDF_RS = 0x0001,
165 CL_RS = 0x0002,
166 SDF_RD = 0x0004,
167
168 SVSmask = 0x00f0,
169 VF_SS = 0x0010,
170 CL_SS = 0x0020,
171 CL_SELF = 0x0040,
172 VF_DD = 0x0080,
173
174 RVDFmask = 0x0f00,
175 SDF_RDF = 0x0100,
176 SDF_MDF = 0x0200,
177 SDF_RDN = 0x0400,
178 /* presets */
180 END
181 };
182 };
183
186 {
187 enum _
188 {
189 DebugDraw = 0x0001,
190 /* presets */
192 END
193 };
194 };
195
196 //
197 // API Types
198 //
199
200 /* sRayCast */
201 struct sRayCast
202 {
205 int index;
207 };
208
209 /* ImplicitFn */
211 {
212 virtual ~ImplicitFn() {}
213 virtual btScalar Eval(const btVector3& x) = 0;
214 };
215
216 //
217 // Internal types
218 //
219
222
223 /* sCti is Softbody contact info */
224 struct sCti
225 {
226 const btCollisionObject* m_colObj; /* Rigid body */
227 btVector3 m_normal; /* Outward normal */
228 btScalar m_offset; /* Offset from origin */
229 btVector3 m_bary; /* Barycentric weights for faces */
230 };
231
232 /* sMedium */
233 struct sMedium
234 {
235 btVector3 m_velocity; /* Velocity */
236 btScalar m_pressure; /* Pressure */
237 btScalar m_density; /* Density */
238 };
239
240 /* Base type */
241 struct Element
242 {
243 void* m_tag; // User data
244 Element() : m_tag(0) {}
245 };
246 /* Material */
248 {
249 btScalar m_kLST; // Linear stiffness coefficient [0,1]
250 btScalar m_kAST; // Area/Angular stiffness coefficient [0,1]
251 btScalar m_kVST; // Volume stiffness coefficient [0,1]
252 int m_flags; // Flags
253 };
254
255 /* Feature */
257 {
258 Material* m_material; // Material
259 };
260 /* Node */
262 {
266 };
267 struct Node : Feature
268 {
269 btVector3 m_x; // Position
270 btVector3 m_q; // Previous step position/Test position
271 btVector3 m_v; // Velocity
272 btVector3 m_vn; // Previous step velocity
273 btVector3 m_f; // Force accumulator
274 btVector3 m_n; // Normal
275 btScalar m_im; // 1/mass
277 btDbvtNode* m_leaf; // Leaf data
278 int m_constrained; // depth of penetration
279 int m_battach : 1; // Attached
280 int index;
281 btVector3 m_splitv; // velocity associated with split impulse
282 btMatrix3x3 m_effectiveMass; // effective mass in contact
283 btMatrix3x3 m_effectiveMass_inv; // inverse of effective mass
284 };
285 /* Link */
287 Link : Feature
288 {
289 btVector3 m_c3; // gradient
290 Node* m_n[2]; // Node pointers
291 btScalar m_rl; // Rest length
292 int m_bbending : 1; // Bending link
293 btScalar m_c0; // (ima+imb)*kLST
294 btScalar m_c1; // rl^2
295 btScalar m_c2; // |gradient|^2/c0
296
298 };
300 {
301 RenderNode* m_n[3]; // Node pointers
302 };
303
304 /* Face */
305 struct Face : Feature
306 {
307 Node* m_n[3]; // Node pointers
309 btScalar m_ra; // Rest area
310 btDbvtNode* m_leaf; // Leaf data
311 btVector4 m_pcontact; // barycentric weights of the persistent contact
314 };
315 /* Tetra */
316 struct Tetra : Feature
317 {
318 Node* m_n[4]; // Node pointers
319 btScalar m_rv; // Rest volume
320 btDbvtNode* m_leaf; // Leaf data
321 btVector3 m_c0[4]; // gradients
322 btScalar m_c1; // (4*kVST)/(im0+im1+im2+im3)
323 btScalar m_c2; // m_c1/sum(|g0..3|^2)
327 btVector4 m_P_inv[3]; // first three columns of P_inv matrix
328 };
329
330 /* TetraScratch */
332 {
333 btMatrix3x3 m_F; // deformation gradient F
334 btScalar m_trace; // trace of F^T * F
335 btScalar m_J; // det(F)
336 btMatrix3x3 m_cofF; // cofactor of F
337 btMatrix3x3 m_corotation; // corotatio of the tetra
338 };
339
340 /* RContact */
341 struct RContact
342 {
343 sCti m_cti; // Contact infos
344 Node* m_node; // Owner node
345 btMatrix3x3 m_c0; // Impulse matrix
346 btVector3 m_c1; // Relative anchor
347 btScalar m_c2; // ima*dt
348 btScalar m_c3; // Friction
349 btScalar m_c4; // Hardness
350
351 // jacobians and unit impulse responses for multibody
357 };
358
360 {
361 public:
362 sCti m_cti; // Contact infos
363 btMatrix3x3 m_c0; // Impulse matrix
364 btVector3 m_c1; // Relative anchor
365 btScalar m_c2; // inverse mass of node/face
366 btScalar m_c3; // Friction
367 btScalar m_c4; // Hardness
368 btMatrix3x3 m_c5; // inverse effective mass
369
370 // jacobians and unit impulse responses for multibody
376 };
377
379 {
380 public:
381 Node* m_node; // Owner node
382 };
383
385 {
386 public:
387 btVector3 m_local; // Anchor position in body space
388 };
389
391 {
392 public:
393 Face* m_face; // Owner face
394 btVector3 m_contactPoint; // Contact point
395 btVector3 m_bary; // Barycentric weights
396 btVector3 m_weights; // v_contactPoint * m_weights[i] = m_face->m_node[i]->m_v;
397 };
398
400 {
401 Node* m_node; // Node
402 Face* m_face; // Face
403 btVector3 m_bary; // Barycentric weights
404 btVector3 m_weights; // v_contactPoint * m_weights[i] = m_face->m_node[i]->m_v;
407 btScalar m_friction; // Friction
408 btScalar m_imf; // inverse mass of the face at contact point
409 btScalar m_c0; // scale of the impulse matrix;
410 const btCollisionObject* m_colObj; // Collision object to collide with.
411 };
412
413 /* SContact */
414 struct SContact
415 {
416 Node* m_node; // Node
417 Face* m_face; // Face
421 btScalar m_friction; // Friction
422 btScalar m_cfm[2]; // Constraint force mixing
423 };
424 /* Anchor */
425 struct Anchor
426 {
427 Node* m_node; // Node pointer
428 btVector3 m_local; // Anchor position in body space
431 btMatrix3x3 m_c0; // Impulse matrix
432 btVector3 m_c1; // Relative anchor
433 btScalar m_c2; // ima*dt
434 };
435 /* Note */
436 struct Note : Element
437 {
438 const char* m_text; // Text
440 int m_rank; // Rank
441 Node* m_nodes[4]; // Nodes
442 btScalar m_coords[4]; // Coordinates
443 };
444 /* Pose */
445 struct Pose
446 {
447 bool m_bvolume; // Is valid
448 bool m_bframe; // Is frame
449 btScalar m_volume; // Rest volume
450 tVector3Array m_pos; // Reference positions
451 tScalarArray m_wgh; // Weights
453 btMatrix3x3 m_rot; // Rotation
455 btMatrix3x3 m_aqq; // Base scaling
456 };
457 /* Cluster */
458 struct Cluster
459 {
476 btScalar m_ndamping; /* Node damping */
477 btScalar m_ldamping; /* Linear damping */
478 btScalar m_adamping; /* Angular damping */
486 {
487 }
488 };
489 /* Impulse */
490 struct Impulse
491 {
495 int m_asDrift : 1;
496 Impulse() : m_velocity(0, 0, 0), m_drift(0, 0, 0), m_asVelocity(0), m_asDrift(0) {}
498 {
499 Impulse i = *this;
500 i.m_velocity = -i.m_velocity;
501 i.m_drift = -i.m_drift;
502 return (i);
503 }
505 {
506 Impulse i = *this;
507 i.m_velocity *= x;
508 i.m_drift *= x;
509 return (i);
510 }
511 };
512 /* Body */
513 struct Body
514 {
518
521 Body(const btCollisionObject* colObj) : m_soft(0), m_collisionObject(colObj)
522 {
524 }
525
526 void activate() const
527 {
528 if (m_rigid)
529 m_rigid->activate();
532 }
534 {
535 static const btMatrix3x3 iwi(0, 0, 0, 0, 0, 0, 0, 0, 0);
537 if (m_soft) return (m_soft->m_invwi);
538 return (iwi);
539 }
541 {
542 if (m_rigid) return (m_rigid->getInvMass());
543 if (m_soft) return (m_soft->m_imass);
544 return (0);
545 }
546 const btTransform& xform() const
547 {
548 static const btTransform identity = btTransform::getIdentity();
550 if (m_soft) return (m_soft->m_framexform);
551 return (identity);
552 }
554 {
555 if (m_rigid) return (m_rigid->getLinearVelocity());
556 if (m_soft) return (m_soft->m_lv);
557 return (btVector3(0, 0, 0));
558 }
560 {
561 if (m_rigid) return (btCross(m_rigid->getAngularVelocity(), rpos));
562 if (m_soft) return (btCross(m_soft->m_av, rpos));
563 return (btVector3(0, 0, 0));
564 }
566 {
567 if (m_rigid) return (m_rigid->getAngularVelocity());
568 if (m_soft) return (m_soft->m_av);
569 return (btVector3(0, 0, 0));
570 }
571 btVector3 velocity(const btVector3& rpos) const
572 {
573 return (linearVelocity() + angularVelocity(rpos));
574 }
575 void applyVImpulse(const btVector3& impulse, const btVector3& rpos) const
576 {
577 if (m_rigid) m_rigid->applyImpulse(impulse, rpos);
578 if (m_soft) btSoftBody::clusterVImpulse(m_soft, rpos, impulse);
579 }
580 void applyDImpulse(const btVector3& impulse, const btVector3& rpos) const
581 {
582 if (m_rigid) m_rigid->applyImpulse(impulse, rpos);
583 if (m_soft) btSoftBody::clusterDImpulse(m_soft, rpos, impulse);
584 }
585 void applyImpulse(const Impulse& impulse, const btVector3& rpos) const
586 {
587 if (impulse.m_asVelocity)
588 {
589 // printf("impulse.m_velocity = %f,%f,%f\n",impulse.m_velocity.getX(),impulse.m_velocity.getY(),impulse.m_velocity.getZ());
590 applyVImpulse(impulse.m_velocity, rpos);
591 }
592 if (impulse.m_asDrift)
593 {
594 // printf("impulse.m_drift = %f,%f,%f\n",impulse.m_drift.getX(),impulse.m_drift.getY(),impulse.m_drift.getZ());
595 applyDImpulse(impulse.m_drift, rpos);
596 }
597 }
598 void applyVAImpulse(const btVector3& impulse) const
599 {
600 if (m_rigid) m_rigid->applyTorqueImpulse(impulse);
602 }
603 void applyDAImpulse(const btVector3& impulse) const
604 {
605 if (m_rigid) m_rigid->applyTorqueImpulse(impulse);
607 }
608 void applyAImpulse(const Impulse& impulse) const
609 {
610 if (impulse.m_asVelocity) applyVAImpulse(impulse.m_velocity);
611 if (impulse.m_asDrift) applyDAImpulse(impulse.m_drift);
612 }
613 void applyDCImpulse(const btVector3& impulse) const
614 {
615 if (m_rigid) m_rigid->applyCentralImpulse(impulse);
617 }
618 };
619 /* Joint */
620 struct Joint
621 {
622 struct eType
623 {
624 enum _
625 {
628 Contact
629 };
630 };
631 struct Specs
632 {
633 Specs() : erp(1), cfm(1), split(1) {}
637 };
647 virtual ~Joint() {}
648 Joint() : m_delete(false) {}
649 virtual void Prepare(btScalar dt, int iterations);
650 virtual void Solve(btScalar dt, btScalar sor) = 0;
651 virtual void Terminate(btScalar dt) = 0;
652 virtual eType::_ Type() const = 0;
653 };
654 /* LJoint */
655 struct LJoint : Joint
656 {
658 {
660 };
662 void Prepare(btScalar dt, int iterations);
663 void Solve(btScalar dt, btScalar sor);
664 void Terminate(btScalar dt);
665 eType::_ Type() const { return (eType::Linear); }
666 };
667 /* AJoint */
668 struct AJoint : Joint
669 {
670 struct IControl
671 {
672 virtual ~IControl() {}
673 virtual void Prepare(AJoint*) {}
674 virtual btScalar Speed(AJoint*, btScalar current) { return (current); }
676 {
677 static IControl def;
678 return (&def);
679 }
680 };
682 {
683 Specs() : icontrol(IControl::Default()) {}
686 };
689 void Prepare(btScalar dt, int iterations);
690 void Solve(btScalar dt, btScalar sor);
691 void Terminate(btScalar dt);
692 eType::_ Type() const { return (eType::Angular); }
693 };
694 /* CJoint */
695 struct CJoint : Joint
696 {
702 void Prepare(btScalar dt, int iterations);
703 void Solve(btScalar dt, btScalar sor);
704 void Terminate(btScalar dt);
705 eType::_ Type() const { return (eType::Contact); }
706 };
707 /* Config */
708 struct Config
709 {
710 eAeroModel::_ aeromodel; // Aerodynamic model (default: V_Point)
711 btScalar kVCF; // Velocities correction factor (Baumgarte)
712 btScalar kDP; // Damping coefficient [0,1]
713 btScalar kDG; // Drag coefficient [0,+inf]
714 btScalar kLF; // Lift coefficient [0,+inf]
715 btScalar kPR; // Pressure coefficient [-inf,+inf]
716 btScalar kVC; // Volume conversation coefficient [0,+inf]
717 btScalar kDF; // Dynamic friction coefficient [0,1]
718 btScalar kMT; // Pose matching coefficient [0,1]
719 btScalar kCHR; // Rigid contacts hardness [0,1]
720 btScalar kKHR; // Kinetic contacts hardness [0,1]
721 btScalar kSHR; // Soft contacts hardness [0,1]
722 btScalar kAHR; // Anchors hardness [0,1]
723 btScalar kSRHR_CL; // Soft vs rigid hardness [0,1] (cluster only)
724 btScalar kSKHR_CL; // Soft vs kinetic hardness [0,1] (cluster only)
725 btScalar kSSHR_CL; // Soft vs soft hardness [0,1] (cluster only)
726 btScalar kSR_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
727 btScalar kSK_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
728 btScalar kSS_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
729 btScalar maxvolume; // Maximum volume ratio for pose
730 btScalar timescale; // Time scale
731 int viterations; // Velocities solver iterations
732 int piterations; // Positions solver iterations
733 int diterations; // Drift solver iterations
734 int citerations; // Cluster solver iterations
735 int collisions; // Collisions flags
736 tVSolverArray m_vsequence; // Velocity solvers sequence
737 tPSolverArray m_psequence; // Position solvers sequence
738 tPSolverArray m_dsequence; // Drift solvers sequence
739 btScalar drag; // deformable air drag
740 btScalar m_maxStress; // Maximum principle first Piola stress
741 };
742 /* SolverState */
744 {
745 //if you add new variables, always initialize them!
747 : sdt(0),
748 isdt(0),
749 velmrg(0),
750 radmrg(0),
751 updmrg(0)
752 {
753 }
754 btScalar sdt; // dt*timescale
755 btScalar isdt; // 1/sdt
756 btScalar velmrg; // velocity margin
757 btScalar radmrg; // radial margin
758 btScalar updmrg; // Update margin
759 };
762 {
769 RayFromToCaster(const btVector3& rayFrom, const btVector3& rayTo, btScalar mxt);
770 void Process(const btDbvtNode* leaf);
771
772 static /*inline*/ btScalar rayFromToTriangle(const btVector3& rayFrom,
773 const btVector3& rayTo,
774 const btVector3& rayNormalizedDirection,
775 const btVector3& a,
776 const btVector3& b,
777 const btVector3& c,
778 btScalar maxt = SIMD_INFINITY);
779 };
780
781 //
782 // Typedefs
783 //
784
786 typedef void (*vsolver_t)(btSoftBody*, btScalar);
803
804 //
805 // Fields
806 //
807
808 Config m_cfg; // Configuration
809 SolverState m_sst; // Solver state
810 Pose m_pose; // Pose
811 void* m_tag; // User data
824 tRContactArray m_rcontacts; // Rigid contacts
829 tSContactArray m_scontacts; // Soft contacts
832 btScalar m_timeacc; // Time accumulator
833 btVector3 m_bounds[2]; // Spatial bounds
834 bool m_bUpdateRtCst; // Update runtime constants
835 btDbvt m_ndbvt; // Nodes tree
836 btDbvt m_fdbvt; // Faces tree
837 btDbvntNode* m_fdbvnt; // Faces tree with normals
838 btDbvt m_cdbvt; // Clusters tree
840 btScalar m_dampingCoefficient; // Damping Coefficient
843 btAlignedObjectArray<btVector3> m_quads; // quadrature points for collision detection
848
851 btAlignedObjectArray<btScalar> m_z; // vertical distance used in extrapolation
854
855 btAlignedObjectArray<bool> m_clusterConnectivity; //cluster connectivity, for self-collision
856
858
860
861 bool m_reducedModel; // Reduced deformable model flag
862
863 //
864 // Api
865 //
866
867 /* ctor */
868 btSoftBody(btSoftBodyWorldInfo* worldInfo, int node_count, const btVector3* x, const btScalar* m);
869
870 /* ctor */
872
873 void initDefaults();
874
875 /* dtor */
876 virtual ~btSoftBody();
877 /* Check for existing link */
878
880
882 {
883 return m_worldInfo;
884 }
885
886 void setDampingCoefficient(btScalar damping_coeff)
887 {
888 m_dampingCoefficient = damping_coeff;
889 }
890
892 virtual void setCollisionShape(btCollisionShape* collisionShape)
893 {
894 }
895
896 bool checkLink(int node0,
897 int node1) const;
898 bool checkLink(const Node* node0,
899 const Node* node1) const;
900 /* Check for existring face */
901 bool checkFace(int node0,
902 int node1,
903 int node2) const;
904 /* Append material */
905 Material* appendMaterial();
906 /* Append note */
907 void appendNote(const char* text,
908 const btVector3& o,
909 const btVector4& c = btVector4(1, 0, 0, 0),
910 Node* n0 = 0,
911 Node* n1 = 0,
912 Node* n2 = 0,
913 Node* n3 = 0);
914 void appendNote(const char* text,
915 const btVector3& o,
916 Node* feature);
917 void appendNote(const char* text,
918 const btVector3& o,
919 Link* feature);
920 void appendNote(const char* text,
921 const btVector3& o,
922 Face* feature);
923 /* Append node */
924 void appendNode(const btVector3& x, btScalar m);
925 /* Append link */
926 void appendLink(int model = -1, Material* mat = 0);
927 void appendLink(int node0,
928 int node1,
929 Material* mat = 0,
930 bool bcheckexist = false);
931 void appendLink(Node* node0,
932 Node* node1,
933 Material* mat = 0,
934 bool bcheckexist = false);
935 /* Append face */
936 void appendFace(int model = -1, Material* mat = 0);
937 void appendFace(int node0,
938 int node1,
939 int node2,
940 Material* mat = 0);
941 void appendTetra(int model, Material* mat);
942 //
943 void appendTetra(int node0,
944 int node1,
945 int node2,
946 int node3,
947 Material* mat = 0);
948
949 /* Append anchor */
950 void appendDeformableAnchor(int node, btRigidBody* body);
952 void appendAnchor(int node,
953 btRigidBody* body, bool disableCollisionBetweenLinkedBodies = false, btScalar influence = 1);
954 void appendAnchor(int node, btRigidBody* body, const btVector3& localPivot, bool disableCollisionBetweenLinkedBodies = false, btScalar influence = 1);
955 void removeAnchor(int node);
956 /* Append linear joint */
957 void appendLinearJoint(const LJoint::Specs& specs, Cluster* body0, Body body1);
958 void appendLinearJoint(const LJoint::Specs& specs, Body body = Body());
959 void appendLinearJoint(const LJoint::Specs& specs, btSoftBody* body);
960 /* Append linear joint */
961 void appendAngularJoint(const AJoint::Specs& specs, Cluster* body0, Body body1);
962 void appendAngularJoint(const AJoint::Specs& specs, Body body = Body());
963 void appendAngularJoint(const AJoint::Specs& specs, btSoftBody* body);
964 /* Add force (or gravity) to the entire body */
965 void addForce(const btVector3& force);
966 /* Add force (or gravity) to a node of the body */
967 void addForce(const btVector3& force,
968 int node);
969 /* Add aero force to a node of the body */
970 void addAeroForceToNode(const btVector3& windVelocity, int nodeIndex);
971
972 /* Add aero force to a face of the body */
973 void addAeroForceToFace(const btVector3& windVelocity, int faceIndex);
974
975 /* Add velocity to the entire body */
976 void addVelocity(const btVector3& velocity);
977
978 /* Set velocity for the entire body */
979 void setVelocity(const btVector3& velocity);
980
981 /* Add velocity to a node of the body */
982 void addVelocity(const btVector3& velocity,
983 int node);
984 /* Set mass */
985 void setMass(int node,
986 btScalar mass);
987 /* Get mass */
988 btScalar getMass(int node) const;
989 /* Get total mass */
990 btScalar getTotalMass() const;
991 /* Set total mass (weighted by previous masses) */
992 void setTotalMass(btScalar mass,
993 bool fromfaces = false);
994 /* Set total density */
995 void setTotalDensity(btScalar density);
996 /* Set volume mass (using tetrahedrons) */
997 void setVolumeMass(btScalar mass);
998 /* Set volume density (using tetrahedrons) */
999 void setVolumeDensity(btScalar density);
1000 /* Get the linear velocity of the center of mass */
1002 /* Set the linear velocity of the center of mass */
1003 void setLinearVelocity(const btVector3& linVel);
1004 /* Set the angular velocity of the center of mass */
1005 void setAngularVelocity(const btVector3& angVel);
1006 /* Get best fit rigid transform */
1008 /* Transform to given pose */
1009 virtual void transformTo(const btTransform& trs);
1010 /* Transform */
1011 virtual void transform(const btTransform& trs);
1012 /* Translate */
1013 virtual void translate(const btVector3& trs);
1014 /* Rotate */
1015 virtual void rotate(const btQuaternion& rot);
1016 /* Scale */
1017 virtual void scale(const btVector3& scl);
1018 /* Get link resting lengths scale */
1020 /* Scale resting length of all springs */
1021 void setRestLengthScale(btScalar restLength);
1022 /* Set current state as pose */
1023 void setPose(bool bvolume,
1024 bool bframe);
1025 /* Set current link lengths as resting lengths */
1026 void resetLinkRestLengths();
1027 /* Return the volume */
1028 btScalar getVolume() const;
1029 /* Cluster count */
1031 {
1032 btVector3 com(0, 0, 0);
1033 for (int i = 0; i < m_nodes.size(); i++)
1034 {
1035 com += (m_nodes[i].m_x * this->getMass(i));
1036 }
1037 com /= this->getTotalMass();
1038 return com;
1039 }
1040 int clusterCount() const;
1041 /* Cluster center of mass */
1042 static btVector3 clusterCom(const Cluster* cluster);
1043 btVector3 clusterCom(int cluster) const;
1044 /* Cluster velocity at rpos */
1045 static btVector3 clusterVelocity(const Cluster* cluster, const btVector3& rpos);
1046 /* Cluster impulse */
1047 static void clusterVImpulse(Cluster* cluster, const btVector3& rpos, const btVector3& impulse);
1048 static void clusterDImpulse(Cluster* cluster, const btVector3& rpos, const btVector3& impulse);
1049 static void clusterImpulse(Cluster* cluster, const btVector3& rpos, const Impulse& impulse);
1050 static void clusterVAImpulse(Cluster* cluster, const btVector3& impulse);
1051 static void clusterDAImpulse(Cluster* cluster, const btVector3& impulse);
1052 static void clusterAImpulse(Cluster* cluster, const Impulse& impulse);
1053 static void clusterDCImpulse(Cluster* cluster, const btVector3& impulse);
1054 /* Generate bending constraints based on distance in the adjency graph */
1055 int generateBendingConstraints(int distance,
1056 Material* mat = 0);
1057 /* Randomize constraints to reduce solver bias */
1058 void randomizeConstraints();
1059
1061
1062 /* Release clusters */
1063 void releaseCluster(int index);
1064 void releaseClusters();
1065 /* Generate clusters (K-mean) */
1068 int generateClusters(int k, int maxiterations = 8192);
1069 /* Refine */
1070 void refine(ImplicitFn* ifn, btScalar accurary, bool cut);
1071 /* CutLink */
1072 bool cutLink(int node0, int node1, btScalar position);
1073 bool cutLink(const Node* node0, const Node* node1, btScalar position);
1074
1076 bool rayTest(const btVector3& rayFrom,
1077 const btVector3& rayTo,
1078 sRayCast& results);
1079 bool rayFaceTest(const btVector3& rayFrom,
1080 const btVector3& rayTo,
1081 sRayCast& results);
1082 int rayFaceTest(const btVector3& rayFrom, const btVector3& rayTo,
1083 btScalar& mint, int& index) const;
1084 /* Solver presets */
1085 void setSolver(eSolverPresets::_ preset);
1086 /* predictMotion */
1087 void predictMotion(btScalar dt);
1088 /* solveConstraints */
1089 void solveConstraints();
1090 /* staticSolve */
1091 void staticSolve(int iterations);
1092 /* solveCommonConstraints */
1093 static void solveCommonConstraints(btSoftBody** bodies, int count, int iterations);
1094 /* solveClusters */
1095 static void solveClusters(const btAlignedObjectArray<btSoftBody*>& bodies);
1096 /* integrateMotion */
1097 void integrateMotion();
1098 /* defaultCollisionHandlers */
1102 bool useSelfCollision();
1103 void updateDeactivation(btScalar timeStep);
1104 void setZeroVelocity();
1105 bool wantsSleeping();
1106
1107 virtual btMatrix3x3 getImpulseFactor(int n_node)
1108 {
1109 btMatrix3x3 tmp;
1110 tmp.setIdentity();
1111 return tmp;
1112 }
1113
1114 //
1115 // Functionality to deal with new accelerated solvers.
1116 //
1117
1121 void setWindVelocity(const btVector3& velocity);
1122
1126 const btVector3& getWindVelocity();
1127
1128 //
1129 // Set the solver that handles this soft body
1130 // Should not be allowed to get out of sync with reality
1131 // Currently called internally on addition to the world
1133 {
1134 m_softBodySolver = softBodySolver;
1135 }
1136
1137 //
1138 // Return the solver that handles this soft body
1139 //
1141 {
1142 return m_softBodySolver;
1143 }
1144
1145 //
1146 // Return the solver that handles this soft body
1147 //
1149 {
1150 return m_softBodySolver;
1151 }
1152
1153 //
1154 // Cast
1155 //
1156
1157 static const btSoftBody* upcast(const btCollisionObject* colObj)
1158 {
1159 if (colObj->getInternalType() == CO_SOFT_BODY)
1160 return (const btSoftBody*)colObj;
1161 return 0;
1162 }
1164 {
1165 if (colObj->getInternalType() == CO_SOFT_BODY)
1166 return (btSoftBody*)colObj;
1167 return 0;
1168 }
1169
1170 //
1171 // ::btCollisionObject
1172 //
1173
1174 virtual void getAabb(btVector3& aabbMin, btVector3& aabbMax) const
1175 {
1176 aabbMin = m_bounds[0];
1177 aabbMax = m_bounds[1];
1178 }
1179 //
1180 // Private
1181 //
1182 void pointersToIndices();
1183 void indicesToPointers(const int* map = 0);
1184
1185 int rayTest(const btVector3& rayFrom, const btVector3& rayTo,
1186 btScalar& mint, eFeature::_& feature, int& index, bool bcountonly) const;
1187 void initializeFaceTree();
1188 void rebuildNodeTree();
1189 btVector3 evaluateCom() const;
1190 bool checkDeformableContact(const btCollisionObjectWrapper* colObjWrap, const btVector3& x, btScalar margin, btSoftBody::sCti& cti, bool predict = false) const;
1191 bool checkDeformableFaceContact(const btCollisionObjectWrapper* colObjWrap, Face& f, btVector3& contact_point, btVector3& bary, btScalar margin, btSoftBody::sCti& cti, bool predict = false) const;
1192 bool checkContact(const btCollisionObjectWrapper* colObjWrap, const btVector3& x, btScalar margin, btSoftBody::sCti& cti) const;
1193 void updateNormals();
1194 void updateBounds();
1195 void updatePose();
1196 void updateConstants();
1197 void updateLinkConstants();
1198 void updateArea(bool averageArea = true);
1199 void initializeClusters();
1200 void updateClusters();
1201 void cleanupClusters();
1202 void prepareClusters(int iterations);
1203 void solveClusters(btScalar sor);
1204 void applyClusters(bool drift);
1205 void dampClusters();
1207 void setGravityFactor(btScalar gravFactor);
1208 void setCacheBarycenter(bool cacheBarycenter);
1209 void initializeDmInverse();
1210 void updateDeformation();
1211 void advanceDeformation();
1212 void applyForces();
1213 void setMaxStress(btScalar maxStress);
1214 void interpolateRenderMesh();
1215 void setCollisionQuadrature(int N);
1216 static void PSolve_Anchors(btSoftBody* psb, btScalar kst, btScalar ti);
1217 static void PSolve_RContacts(btSoftBody* psb, btScalar kst, btScalar ti);
1218 static void PSolve_SContacts(btSoftBody* psb, btScalar, btScalar ti);
1219 static void PSolve_Links(btSoftBody* psb, btScalar kst, btScalar ti);
1220 static void VSolve_Links(btSoftBody* psb, btScalar kst);
1221 static psolver_t getSolver(ePSolver::_ solver);
1222 static vsolver_t getSolver(eVSolver::_ solver);
1224#define SAFE_EPSILON SIMD_EPSILON * 100.0
1225 void updateNode(btDbvtNode* node, bool use_velocity, bool margin)
1226 {
1227 if (node->isleaf())
1228 {
1229 btSoftBody::Node* n = (btSoftBody::Node*)(node->data);
1231 vol;
1232 btScalar pad = margin ? m_sst.radmrg : SAFE_EPSILON; // use user defined margin or margin for floating point precision
1233 if (use_velocity)
1234 {
1235 btVector3 points[2] = {n->m_x, n->m_x + m_sst.sdt * n->m_v};
1236 vol = btDbvtVolume::FromPoints(points, 2);
1237 vol.Expand(btVector3(pad, pad, pad));
1238 }
1239 else
1240 {
1241 vol = btDbvtVolume::FromCR(n->m_x, pad);
1242 }
1243 node->volume = vol;
1244 return;
1245 }
1246 else
1247 {
1248 updateNode(node->childs[0], use_velocity, margin);
1249 updateNode(node->childs[1], use_velocity, margin);
1251 vol;
1252 Merge(node->childs[0]->volume, node->childs[1]->volume, vol);
1253 node->volume = vol;
1254 }
1255 }
1256
1257 void updateNodeTree(bool use_velocity, bool margin)
1258 {
1259 if (m_ndbvt.m_root)
1260 updateNode(m_ndbvt.m_root, use_velocity, margin);
1261 }
1262
1263 template <class DBVTNODE> // btDbvtNode or btDbvntNode
1264 void updateFace(DBVTNODE* node, bool use_velocity, bool margin)
1265 {
1266 if (node->isleaf())
1267 {
1268 btSoftBody::Face* f = (btSoftBody::Face*)(node->data);
1269 btScalar pad = margin ? m_sst.radmrg : SAFE_EPSILON; // use user defined margin or margin for floating point precision
1271 vol;
1272 if (use_velocity)
1273 {
1274 btVector3 points[6] = {f->m_n[0]->m_x, f->m_n[0]->m_x + m_sst.sdt * f->m_n[0]->m_v,
1275 f->m_n[1]->m_x, f->m_n[1]->m_x + m_sst.sdt * f->m_n[1]->m_v,
1276 f->m_n[2]->m_x, f->m_n[2]->m_x + m_sst.sdt * f->m_n[2]->m_v};
1277 vol = btDbvtVolume::FromPoints(points, 6);
1278 }
1279 else
1280 {
1281 btVector3 points[3] = {f->m_n[0]->m_x,
1282 f->m_n[1]->m_x,
1283 f->m_n[2]->m_x};
1284 vol = btDbvtVolume::FromPoints(points, 3);
1285 }
1286 vol.Expand(btVector3(pad, pad, pad));
1287 node->volume = vol;
1288 return;
1289 }
1290 else
1291 {
1292 updateFace(node->childs[0], use_velocity, margin);
1293 updateFace(node->childs[1], use_velocity, margin);
1295 vol;
1296 Merge(node->childs[0]->volume, node->childs[1]->volume, vol);
1297 node->volume = vol;
1298 }
1299 }
1300 void updateFaceTree(bool use_velocity, bool margin)
1301 {
1302 if (m_fdbvt.m_root)
1303 updateFace(m_fdbvt.m_root, use_velocity, margin);
1304 if (m_fdbvnt)
1305 updateFace(m_fdbvnt, use_velocity, margin);
1306 }
1307
1308 template <typename T>
1309 static inline T BaryEval(const T& a,
1310 const T& b,
1311 const T& c,
1312 const btVector3& coord)
1313 {
1314 return (a * coord.x() + b * coord.y() + c * coord.z());
1315 }
1316
1317 void applyRepulsionForce(btScalar timeStep, bool applySpringForce)
1318 {
1320 {
1321 // randomize the order of repulsive force
1322 indices.resize(m_faceNodeContacts.size());
1323 for (int i = 0; i < m_faceNodeContacts.size(); ++i)
1324 indices[i] = i;
1325#define NEXTRAND (seed = (1664525L * seed + 1013904223L) & 0xffffffff)
1326 int i, ni;
1327
1328 for (i = 0, ni = indices.size(); i < ni; ++i)
1329 {
1330 btSwap(indices[i], indices[NEXTRAND % ni]);
1331 }
1332 }
1333 for (int k = 0; k < m_faceNodeContacts.size(); ++k)
1334 {
1335 int idx = indices[k];
1337 btSoftBody::Node* node = c.m_node;
1338 btSoftBody::Face* face = c.m_face;
1339 const btVector3& w = c.m_bary;
1340 const btVector3& n = c.m_normal;
1341 btVector3 l = node->m_x - BaryEval(face->m_n[0]->m_x, face->m_n[1]->m_x, face->m_n[2]->m_x, w);
1342 btScalar d = c.m_margin - n.dot(l);
1343 d = btMax(btScalar(0), d);
1344
1345 const btVector3& va = node->m_v;
1346 btVector3 vb = BaryEval(face->m_n[0]->m_v, face->m_n[1]->m_v, face->m_n[2]->m_v, w);
1347 btVector3 vr = va - vb;
1348 const btScalar vn = btDot(vr, n); // dn < 0 <==> opposing
1349 if (vn > OVERLAP_REDUCTION_FACTOR * d / timeStep)
1350 continue;
1351 btVector3 vt = vr - vn * n;
1352 btScalar I = 0;
1353 btScalar mass = node->m_im == 0 ? 0 : btScalar(1) / node->m_im;
1354 if (applySpringForce)
1355 I = -btMin(m_repulsionStiffness * timeStep * d, mass * (OVERLAP_REDUCTION_FACTOR * d / timeStep - vn));
1356 if (vn < 0)
1357 I += 0.5 * mass * vn;
1358 int face_penetration = 0, node_penetration = node->m_constrained;
1359 for (int i = 0; i < 3; ++i)
1360 face_penetration |= face->m_n[i]->m_constrained;
1361 btScalar I_tilde = 2.0 * I / (1.0 + w.length2());
1362
1363 // double the impulse if node or face is constrained.
1364 if (face_penetration > 0 || node_penetration > 0)
1365 {
1366 I_tilde *= 2.0;
1367 }
1368 if (face_penetration <= 0)
1369 {
1370 for (int j = 0; j < 3; ++j)
1371 face->m_n[j]->m_v += w[j] * n * I_tilde * node->m_im;
1372 }
1373 if (node_penetration <= 0)
1374 {
1375 node->m_v -= I_tilde * node->m_im * n;
1376 }
1377
1378 // apply frictional impulse
1379 btScalar vt_norm = vt.safeNorm();
1380 if (vt_norm > SIMD_EPSILON)
1381 {
1382 btScalar delta_vn = -2 * I * node->m_im;
1383 btScalar mu = c.m_friction;
1384 btScalar vt_new = btMax(btScalar(1) - mu * delta_vn / (vt_norm + SIMD_EPSILON), btScalar(0)) * vt_norm;
1385 I = 0.5 * mass * (vt_norm - vt_new);
1386 vt.safeNormalize();
1387 I_tilde = 2.0 * I / (1.0 + w.length2());
1388 // double the impulse if node or face is constrained.
1389 if (face_penetration > 0 || node_penetration > 0)
1390 I_tilde *= 2.0;
1391 if (face_penetration <= 0)
1392 {
1393 for (int j = 0; j < 3; ++j)
1394 face->m_n[j]->m_v += w[j] * vt * I_tilde * (face->m_n[j])->m_im;
1395 }
1396 if (node_penetration <= 0)
1397 {
1398 node->m_v -= I_tilde * node->m_im * vt;
1399 }
1400 }
1401 }
1402 }
1403 virtual int calculateSerializeBufferSize() const;
1404
1406 virtual const char* serialize(void* dataBuffer, class btSerializer* serializer) const;
1407};
1408
1409#endif //_BT_SOFT_BODY_H
DBVT_INLINE void Merge(const btDbvtAabbMm &a, const btDbvtAabbMm &b, btDbvtAabbMm &r)
Definition: btDbvt.h:745
const T & btMax(const T &a, const T &b)
Definition: btMinMax.h:27
const T & btMin(const T &a, const T &b)
Definition: btMinMax.h:21
float btScalar
The btScalar type abstracts floating point numbers, to easily switch between double and single floati...
Definition: btScalar.h:314
#define ATTRIBUTE_ALIGNED16(a)
Definition: btScalar.h:99
#define SIMD_INFINITY
Definition: btScalar.h:544
#define SIMD_EPSILON
Definition: btScalar.h:543
void btSwap(T &a, T &b)
Definition: btScalar.h:643
static unsigned long seed
Definition: btSoftBody.h:39
static const btScalar OVERLAP_REDUCTION_FACTOR
Definition: btSoftBody.h:38
#define NEXTRAND
#define SAFE_EPSILON
Definition: btSoftBody.h:1224
btScalar btDot(const btVector3 &v1, const btVector3 &v2)
Return the dot product between two vectors.
Definition: btVector3.h:890
btVector3 btCross(const btVector3 &v1, const btVector3 &v2)
Return the cross product of two vectors.
Definition: btVector3.h:918
int size() const
return the number of elements in the array
void resize(int newsize, const T &fillData=T())
The btBroadphaseInterface class provides an interface to detect aabb-overlapping object pairs.
btCollisionObject can be used to manage collision detection objects.
btTransform & getWorldTransform()
int getInternalType() const
reserved for Bullet internal usage
void activate(bool forceActivation=false) const
The btCollisionShape class provides an interface for collision shapes that can be shared among btColl...
The btDispatcher interface class can be used in combination with broadphase to dispatch calculations ...
Definition: btDispatcher.h:77
The btMatrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with...
Definition: btMatrix3x3.h:50
void setIdentity()
Set the matrix to the identity.
Definition: btMatrix3x3.h:323
The btQuaternion implements quaternion to perform linear algebra rotations in combination with btMatr...
Definition: btQuaternion.h:50
The btRigidBody is the main class for rigid body objects.
Definition: btRigidBody.h:60
void applyTorqueImpulse(const btVector3 &torque)
Definition: btRigidBody.h:327
btScalar getInvMass() const
Definition: btRigidBody.h:263
void applyImpulse(const btVector3 &impulse, const btVector3 &rel_pos)
Definition: btRigidBody.h:335
void applyCentralImpulse(const btVector3 &impulse)
Definition: btRigidBody.h:319
const btVector3 & getAngularVelocity() const
Definition: btRigidBody.h:437
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:189
const btMatrix3x3 & getInvInertiaTensorWorld() const
Definition: btRigidBody.h:265
const btVector3 & getLinearVelocity() const
Definition: btRigidBody.h:433
btMultiBodyJacobianData jacobianData_t1
Definition: btSoftBody.h:372
btMultiBodyJacobianData jacobianData_normal
Definition: btSoftBody.h:371
btMultiBodyJacobianData jacobianData_t2
Definition: btSoftBody.h:373
The btSoftBody is an class to simulate cloth and volumetric soft bodies.
Definition: btSoftBody.h:75
static void PSolve_Links(btSoftBody *psb, btScalar kst, btScalar ti)
static void PSolve_SContacts(btSoftBody *psb, btScalar, btScalar ti)
bool checkLink(int node0, int node1) const
Definition: btSoftBody.cpp:256
bool m_bUpdateRtCst
Definition: btSoftBody.h:834
btScalar m_sleepingThreshold
Definition: btSoftBody.h:841
virtual void transformTo(const btTransform &trs)
btVector3 getLinearVelocity()
bool checkFace(int node0, int node1, int node2) const
Definition: btSoftBody.cpp:278
void advanceDeformation()
btAlignedObjectArray< eVSolver::_ > tVSolverArray
Definition: btSoftBody.h:151
void setGravityFactor(btScalar gravFactor)
void updateClusters()
btDbvt m_cdbvt
Definition: btSoftBody.h:838
void setPose(bool bvolume, bool bframe)
bool cutLink(int node0, int node1, btScalar position)
void appendFace(int model=-1, Material *mat=0)
Definition: btSoftBody.cpp:432
void setMass(int node, btScalar mass)
Definition: btSoftBody.cpp:923
void interpolateRenderMesh()
tJointArray m_joints
Definition: btSoftBody.h:830
btScalar m_dampingCoefficient
Definition: btSoftBody.h:840
void updateNode(btDbvtNode *node, bool use_velocity, bool margin)
Definition: btSoftBody.h:1225
btAlignedObjectArray< TetraScratch > m_tetraScratchesTn
Definition: btSoftBody.h:821
void integrateMotion()
btAlignedObjectArray< Tetra > tTetraArray
Definition: btSoftBody.h:795
void rebuildNodeTree()
bool rayFaceTest(const btVector3 &rayFrom, const btVector3 &rayTo, sRayCast &results)
void appendLinearJoint(const LJoint::Specs &specs, Cluster *body0, Body body1)
Definition: btSoftBody.cpp:640
tRenderFaceArray m_renderFaces
Definition: btSoftBody.h:818
btAlignedObjectArray< SContact > tSContactArray
Definition: btSoftBody.h:798
virtual void scale(const btVector3 &scl)
btAlignedObjectArray< bool > m_clusterConnectivity
Definition: btSoftBody.h:855
void updateFaceTree(bool use_velocity, bool margin)
Definition: btSoftBody.h:1300
void defaultCollisionHandler(const btCollisionObjectWrapper *pcoWrap)
btScalar getVolume() const
bool rayTest(const btVector3 &rayFrom, const btVector3 &rayTo, sRayCast &results)
Ray casting using rayFrom and rayTo in worldspace, (not direction!)
SolverState m_sst
Definition: btSoftBody.h:809
void addVelocity(const btVector3 &velocity)
Definition: btSoftBody.cpp:893
btAlignedObjectArray< RContact > tRContactArray
Definition: btSoftBody.h:797
void setDampingCoefficient(btScalar damping_coeff)
Definition: btSoftBody.h:886
void predictMotion(btScalar dt)
void setSelfCollision(bool useSelfCollision)
void setLinearVelocity(const btVector3 &linVel)
btScalar m_timeacc
Definition: btSoftBody.h:832
Pose m_pose
Definition: btSoftBody.h:810
btAlignedObjectArray< int > m_userIndexMapping
Definition: btSoftBody.h:879
btAlignedObjectArray< Face > tFaceArray
Definition: btSoftBody.h:793
void appendTetra(int model, Material *mat)
Definition: btSoftBody.cpp:472
void setRestLengthScale(btScalar restLength)
btDbvntNode * m_fdbvnt
Definition: btSoftBody.h:837
void updateNodeTree(bool use_velocity, bool margin)
Definition: btSoftBody.h:1257
virtual void rotate(const btQuaternion &rot)
void updateFace(DBVTNODE *node, bool use_velocity, bool margin)
Definition: btSoftBody.h:1264
void applyClusters(bool drift)
void setZeroVelocity()
static void PSolve_Anchors(btSoftBody *psb, btScalar kst, btScalar ti)
btAlignedObjectArray< DeformableFaceNodeContact > m_faceNodeContactsCCD
Definition: btSoftBody.h:828
btSoftBodyWorldInfo * m_worldInfo
Definition: btSoftBody.h:812
void setSoftBodySolver(btSoftBodySolver *softBodySolver)
Definition: btSoftBody.h:1132
btAlignedObjectArray< btAlignedObjectArray< btScalar > > tDenseMatrix
Definition: btSoftBody.h:802
void updateArea(bool averageArea=true)
void addForce(const btVector3 &force)
Definition: btSoftBody.cpp:693
bool wantsSleeping()
void prepareClusters(int iterations)
void setCollisionQuadrature(int N)
static void clusterVImpulse(Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse)
virtual const char * serialize(void *dataBuffer, class btSerializer *serializer) const
fills the dataBuffer and returns the struct name (and 0 on failure)
btAlignedObjectArray< DeformableFaceNodeContact > m_faceNodeContacts
Definition: btSoftBody.h:826
static void VSolve_Links(btSoftBody *psb, btScalar kst)
tTetraArray m_tetras
Definition: btSoftBody.h:819
bool useSelfCollision()
btVector3 evaluateCom() const
void setTotalDensity(btScalar density)
Definition: btSoftBody.cpp:983
btAlignedObjectArray< const class btCollisionObject * > m_collisionDisabledObjects
Definition: btSoftBody.h:77
btAlignedObjectArray< Link > tLinkArray
Definition: btSoftBody.h:792
static void clusterDAImpulse(Cluster *cluster, const btVector3 &impulse)
void appendNode(const btVector3 &x, btScalar m)
Definition: btSoftBody.cpp:372
void staticSolve(int iterations)
void setVolumeMass(btScalar mass)
Definition: btSoftBody.cpp:989
btScalar m_restLengthScale
Definition: btSoftBody.h:859
bool checkDeformableContact(const btCollisionObjectWrapper *colObjWrap, const btVector3 &x, btScalar margin, btSoftBody::sCti &cti, bool predict=false) const
bool m_reducedModel
Definition: btSoftBody.h:861
void cleanupClusters()
Config m_cfg
Definition: btSoftBody.h:808
void updateDeactivation(btScalar timeStep)
btAlignedObjectArray< TetraScratch > m_tetraScratches
Definition: btSoftBody.h:820
const btVector3 & getWindVelocity()
Return the wind velocity for interaction with the air.
void addAeroForceToFace(const btVector3 &windVelocity, int faceIndex)
Definition: btSoftBody.cpp:797
btAlignedObjectArray< btVector4 > m_renderNodesInterpolationWeights
Definition: btSoftBody.h:849
void appendAngularJoint(const AJoint::Specs &specs, Cluster *body0, Body body1)
Definition: btSoftBody.cpp:666
tFaceArray m_faces
Definition: btSoftBody.h:817
void setAngularVelocity(const btVector3 &angVel)
void setVolumeDensity(btScalar density)
static void clusterDCImpulse(Cluster *cluster, const btVector3 &impulse)
virtual void transform(const btTransform &trs)
bool m_softSoftCollision
Definition: btSoftBody.h:853
static void clusterVAImpulse(Cluster *cluster, const btVector3 &impulse)
btScalar getMass(int node) const
Definition: btSoftBody.cpp:930
tMaterialArray m_materials
Definition: btSoftBody.h:831
void setMaxStress(btScalar maxStress)
void dampClusters()
btSoftBody(btSoftBodyWorldInfo *worldInfo, int node_count, const btVector3 *x, const btScalar *m)
Definition: btSoftBody.cpp:130
void updateDeformation()
btAlignedObjectArray< btScalar > m_z
Definition: btSoftBody.h:851
void addAeroForceToNode(const btVector3 &windVelocity, int nodeIndex)
Definition: btSoftBody.cpp:708
void applyRepulsionForce(btScalar timeStep, bool applySpringForce)
Definition: btSoftBody.h:1317
btAlignedObjectArray< btVector3 > tVector3Array
Definition: btSoftBody.h:221
static btVector3 clusterCom(const Cluster *cluster)
tRContactArray m_rcontacts
Definition: btSoftBody.h:824
void appendAnchor(int node, btRigidBody *body, bool disableCollisionBetweenLinkedBodies=false, btScalar influence=1)
Definition: btSoftBody.cpp:504
btAlignedObjectArray< Node > tNodeArray
Definition: btSoftBody.h:789
btVector3 m_bounds[2]
Definition: btSoftBody.h:833
btScalar m_maxSpeedSquared
Definition: btSoftBody.h:842
void releaseCluster(int index)
btAlignedObjectArray< RenderNode > tRenderNodeArray
Definition: btSoftBody.h:790
btScalar m_repulsionStiffness
Definition: btSoftBody.h:844
void setVelocity(const btVector3 &velocity)
Definition: btSoftBody.cpp:899
tClusterArray m_clusters
Definition: btSoftBody.h:839
btAlignedObjectArray< Joint * > tJointArray
Definition: btSoftBody.h:800
void solveConstraints()
btAlignedObjectArray< DeformableFaceRigidContact > m_faceRigidContacts
Definition: btSoftBody.h:827
int generateClusters(int k, int maxiterations=8192)
generateClusters with k=0 will create a convex cluster for each tetrahedron or triangle otherwise an ...
void geometricCollisionHandler(btSoftBody *psb)
void releaseClusters()
void refine(ImplicitFn *ifn, btScalar accurary, bool cut)
void setSolver(eSolverPresets::_ preset)
static T BaryEval(const T &a, const T &b, const T &c, const btVector3 &coord)
Definition: btSoftBody.h:1309
Material * appendMaterial()
Definition: btSoftBody.cpp:302
void removeAnchor(int node)
Definition: btSoftBody.cpp:566
btAlignedObjectArray< DeformableNodeRigidAnchor > m_deformableAnchors
Definition: btSoftBody.h:823
void setCacheBarycenter(bool cacheBarycenter)
btAlignedObjectArray< Material * > tMaterialArray
Definition: btSoftBody.h:799
btAlignedObjectArray< Anchor > tAnchorArray
Definition: btSoftBody.h:796
btScalar m_gravityFactor
Definition: btSoftBody.h:845
static void solveClusters(const btAlignedObjectArray< btSoftBody * > &bodies)
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:314
bool checkDeformableFaceContact(const btCollisionObjectWrapper *colObjWrap, Face &f, btVector3 &contact_point, btVector3 &bary, btScalar margin, btSoftBody::sCti &cti, bool predict=false) const
virtual int calculateSerializeBufferSize() const
btAlignedObjectArray< DeformableNodeRigidContact > m_nodeRigidContacts
Definition: btSoftBody.h:825
btAlignedObjectArray< btSoftBody * > tSoftBodyArray
Definition: btSoftBody.h:801
static void PSolve_RContacts(btSoftBody *psb, btScalar kst, btScalar ti)
virtual btMatrix3x3 getImpulseFactor(int n_node)
Definition: btSoftBody.h:1107
static void clusterImpulse(Cluster *cluster, const btVector3 &rpos, const Impulse &impulse)
btAlignedObjectArray< btAlignedObjectArray< const btSoftBody::Node * > > m_renderNodesParents
Definition: btSoftBody.h:850
tRenderNodeArray m_renderNodes
Definition: btSoftBody.h:815
void pointersToIndices()
tNoteArray m_notes
Definition: btSoftBody.h:813
void updateNormals()
static void clusterDImpulse(Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse)
btDbvt m_fdbvt
Definition: btSoftBody.h:836
tLinkArray m_links
Definition: btSoftBody.h:816
void applyForces()
static btVector3 clusterVelocity(const Cluster *cluster, const btVector3 &rpos)
btTransform getRigidTransform()
tSContactArray m_scontacts
Definition: btSoftBody.h:829
bool m_cacheBarycenter
Definition: btSoftBody.h:846
bool m_useSelfCollision
Definition: btSoftBody.h:852
void * m_tag
Definition: btSoftBody.h:811
void updatePose()
btAlignedObjectArray< btDbvtNode * > tLeafArray
Definition: btSoftBody.h:791
void(* psolver_t)(btSoftBody *, btScalar, btScalar)
Definition: btSoftBody.h:785
void initializeClusters()
btSoftBodyWorldInfo * getWorldInfo()
Definition: btSoftBody.h:881
tAnchorArray m_anchors
Definition: btSoftBody.h:822
btScalar getRestLengthScale()
btAlignedObjectArray< Note > tNoteArray
Definition: btSoftBody.h:788
void updateState(const btAlignedObjectArray< btVector3 > &qs, const btAlignedObjectArray< btVector3 > &vs)
void randomizeConstraints()
virtual void setCollisionShape(btCollisionShape *collisionShape)
Definition: btSoftBody.h:892
btVector3 m_windVelocity
Definition: btSoftBody.h:857
btScalar getTotalMass() const
Definition: btSoftBody.cpp:936
tNodeArray m_nodes
Definition: btSoftBody.h:814
btAlignedObjectArray< ePSolver::_ > tPSolverArray
Definition: btSoftBody.h:152
void appendLink(int model=-1, Material *mat=0)
Definition: btSoftBody.cpp:392
void setSpringStiffness(btScalar k)
void initializeDmInverse()
static const btSoftBody * upcast(const btCollisionObject *colObj)
Definition: btSoftBody.h:1157
void updateConstants()
void setTotalMass(btScalar mass, bool fromfaces=false)
Definition: btSoftBody.cpp:947
btSoftBodySolver * getSoftBodySolver()
Definition: btSoftBody.h:1140
virtual ~btSoftBody()
Definition: btSoftBody.cpp:240
void appendDeformableAnchor(int node, btRigidBody *body)
Definition: btSoftBody.cpp:531
btAlignedObjectArray< RenderFace > tRenderFaceArray
Definition: btSoftBody.h:794
void updateLinkConstants()
virtual void getAabb(btVector3 &aabbMin, btVector3 &aabbMax) const
Definition: btSoftBody.h:1174
void(* vsolver_t)(btSoftBody *, btScalar)
Definition: btSoftBody.h:786
void initDefaults()
Definition: btSoftBody.cpp:170
btAlignedObjectArray< btVector3 > m_quads
Definition: btSoftBody.h:843
static psolver_t getSolver(ePSolver::_ solver)
bool checkContact(const btCollisionObjectWrapper *colObjWrap, const btVector3 &x, btScalar margin, btSoftBody::sCti &cti) const
void indicesToPointers(const int *map=0)
static void solveCommonConstraints(btSoftBody **bodies, int count, int iterations)
btAlignedObjectArray< Cluster * > tClusterArray
Definition: btSoftBody.h:787
void updateBounds()
void setWindVelocity(const btVector3 &velocity)
Set a wind velocity for interaction with the air.
btSoftBodySolver * getSoftBodySolver() const
Definition: btSoftBody.h:1148
int generateBendingConstraints(int distance, Material *mat=0)
btAlignedObjectArray< btVector3 > m_X
Definition: btSoftBody.h:847
virtual void translate(const btVector3 &trs)
btVector3 getCenterOfMass() const
Definition: btSoftBody.h:1030
void initializeFaceTree()
btSoftBodySolver * m_softBodySolver
Definition: btSoftBody.h:80
void resetLinkRestLengths()
int clusterCount() const
btAlignedObjectArray< btScalar > tScalarArray
Definition: btSoftBody.h:220
btDbvt m_ndbvt
Definition: btSoftBody.h:835
static void clusterAImpulse(Cluster *cluster, const Impulse &impulse)
static btSoftBody * upcast(btCollisionObject *colObj)
Definition: btSoftBody.h:1163
The btTransform class supports rigid transforms with only translation and rotation and no scaling/she...
Definition: btTransform.h:30
static const btTransform & getIdentity()
Return an identity transform.
Definition: btTransform.h:198
btVector3 can be used to represent 3D points and vectors.
Definition: btVector3.h:82
btScalar safeNorm() const
Return the norm (length) of the vector.
Definition: btVector3.h:269
const btScalar & z() const
Return the z value.
Definition: btVector3.h:579
btVector3 & safeNormalize()
Definition: btVector3.h:286
btScalar dot(const btVector3 &v) const
Return the dot product.
Definition: btVector3.h:229
btScalar length2() const
Return the length of the vector squared.
Definition: btVector3.h:251
const btScalar & x() const
Return the x value.
Definition: btVector3.h:575
const btScalar & y() const
Return the y value.
Definition: btVector3.h:577
static btDbvtAabbMm FromCR(const btVector3 &c, btScalar r)
Definition: btDbvt.h:473
static btDbvtAabbMm FromPoints(const btVector3 *pts, int n)
Definition: btDbvt.h:488
btDbvtNode * childs[2]
Definition: btDbvt.h:187
void * data
Definition: btDbvt.h:188
btDbvtVolume volume
Definition: btDbvt.h:182
DBVT_INLINE bool isleaf() const
Definition: btDbvt.h:184
The btDbvt class implements a fast dynamic bounding volume tree based on axis aligned bounding boxes ...
Definition: btDbvt.h:229
btDbvtNode * m_root
Definition: btDbvt.h:302
btScalar air_density
Definition: btSoftBody.h:49
btDispatcher * m_dispatcher
Definition: btSoftBody.h:55
btScalar water_density
Definition: btSoftBody.h:50
btSparseSdf< 3 > m_sparsesdf
Definition: btSoftBody.h:57
btVector3 m_gravity
Definition: btSoftBody.h:56
btVector3 water_normal
Definition: btSoftBody.h:53
btScalar m_maxDisplacement
Definition: btSoftBody.h:52
btScalar water_offset
Definition: btSoftBody.h:51
btBroadphaseInterface * m_broadphase
Definition: btSoftBody.h:54
static IControl * Default()
Definition: btSoftBody.h:675
virtual btScalar Speed(AJoint *, btScalar current)
Definition: btSoftBody.h:674
virtual void Prepare(AJoint *)
Definition: btSoftBody.h:673
btVector3 m_axis[2]
Definition: btSoftBody.h:687
void Prepare(btScalar dt, int iterations)
void Solve(btScalar dt, btScalar sor)
IControl * m_icontrol
Definition: btSoftBody.h:688
void Terminate(btScalar dt)
eType::_ Type() const
Definition: btSoftBody.h:692
btScalar m_influence
Definition: btSoftBody.h:430
btVector3 m_local
Definition: btSoftBody.h:428
btRigidBody * m_body
Definition: btSoftBody.h:429
btMatrix3x3 m_c0
Definition: btSoftBody.h:431
btScalar invMass() const
Definition: btSoftBody.h:540
Body(Cluster *p)
Definition: btSoftBody.h:520
const btMatrix3x3 & invWorldInertia() const
Definition: btSoftBody.h:533
void applyVImpulse(const btVector3 &impulse, const btVector3 &rpos) const
Definition: btSoftBody.h:575
btVector3 angularVelocity() const
Definition: btSoftBody.h:565
btRigidBody * m_rigid
Definition: btSoftBody.h:516
btVector3 linearVelocity() const
Definition: btSoftBody.h:553
btVector3 angularVelocity(const btVector3 &rpos) const
Definition: btSoftBody.h:559
void applyDImpulse(const btVector3 &impulse, const btVector3 &rpos) const
Definition: btSoftBody.h:580
Body(const btCollisionObject *colObj)
Definition: btSoftBody.h:521
btVector3 velocity(const btVector3 &rpos) const
Definition: btSoftBody.h:571
void applyDCImpulse(const btVector3 &impulse) const
Definition: btSoftBody.h:613
void applyDAImpulse(const btVector3 &impulse) const
Definition: btSoftBody.h:603
const btTransform & xform() const
Definition: btSoftBody.h:546
void activate() const
Definition: btSoftBody.h:526
void applyVAImpulse(const btVector3 &impulse) const
Definition: btSoftBody.h:598
Cluster * m_soft
Definition: btSoftBody.h:515
void applyAImpulse(const Impulse &impulse) const
Definition: btSoftBody.h:608
void applyImpulse(const Impulse &impulse, const btVector3 &rpos) const
Definition: btSoftBody.h:585
const btCollisionObject * m_collisionObject
Definition: btSoftBody.h:517
void Terminate(btScalar dt)
eType::_ Type() const
Definition: btSoftBody.h:705
btVector3 m_rpos[2]
Definition: btSoftBody.h:699
void Prepare(btScalar dt, int iterations)
btVector3 m_normal
Definition: btSoftBody.h:700
btScalar m_friction
Definition: btSoftBody.h:701
void Solve(btScalar dt, btScalar sor)
btVector3 m_dimpulses[2]
Definition: btSoftBody.h:470
tVector3Array m_framerefs
Definition: btSoftBody.h:462
btMatrix3x3 m_invwi
Definition: btSoftBody.h:467
btScalar m_maxSelfCollisionImpulse
Definition: btSoftBody.h:480
btMatrix3x3 m_locii
Definition: btSoftBody.h:466
btAlignedObjectArray< Node * > m_nodes
Definition: btSoftBody.h:461
btDbvtNode * m_leaf
Definition: btSoftBody.h:475
btVector3 m_vimpulses[2]
Definition: btSoftBody.h:469
tScalarArray m_masses
Definition: btSoftBody.h:460
btScalar m_selfCollisionImpulseFactor
Definition: btSoftBody.h:481
btTransform m_framexform
Definition: btSoftBody.h:463
btScalar maxvolume
Definition: btSoftBody.h:729
tPSolverArray m_psequence
Definition: btSoftBody.h:737
tPSolverArray m_dsequence
Definition: btSoftBody.h:738
btScalar kSK_SPLT_CL
Definition: btSoftBody.h:727
btScalar kSS_SPLT_CL
Definition: btSoftBody.h:728
btScalar m_maxStress
Definition: btSoftBody.h:740
eAeroModel::_ aeromodel
Definition: btSoftBody.h:710
btScalar kSR_SPLT_CL
Definition: btSoftBody.h:726
tVSolverArray m_vsequence
Definition: btSoftBody.h:736
btScalar timescale
Definition: btSoftBody.h:730
const btCollisionObject * m_colObj
Definition: btSoftBody.h:410
btVector4 m_pcontact
Definition: btSoftBody.h:311
btVector3 m_normal
Definition: btSoftBody.h:308
btVector3 m_n0
Definition: btSoftBody.h:312
btVector3 m_n1
Definition: btSoftBody.h:312
btVector3 m_vn
Definition: btSoftBody.h:312
Node * m_n[3]
Definition: btSoftBody.h:307
btDbvtNode * m_leaf
Definition: btSoftBody.h:310
Material * m_material
Definition: btSoftBody.h:258
virtual btScalar Eval(const btVector3 &x)=0
Impulse operator*(btScalar x) const
Definition: btSoftBody.h:504
Impulse operator-() const
Definition: btSoftBody.h:497
btVector3 m_velocity
Definition: btSoftBody.h:492
btVector3 m_drift
Definition: btSoftBody.h:643
btVector3 m_sdrift
Definition: btSoftBody.h:644
btScalar m_split
Definition: btSoftBody.h:642
virtual void Solve(btScalar dt, btScalar sor)=0
virtual void Terminate(btScalar dt)=0
btMatrix3x3 m_massmatrix
Definition: btSoftBody.h:645
virtual ~Joint()
Definition: btSoftBody.h:647
btVector3 m_refs[2]
Definition: btSoftBody.h:639
virtual void Prepare(btScalar dt, int iterations)
virtual eType::_ Type() const =0
void Solve(btScalar dt, btScalar sor)
btVector3 m_rpos[2]
Definition: btSoftBody.h:661
eType::_ Type() const
Definition: btSoftBody.h:665
void Prepare(btScalar dt, int iterations)
void Terminate(btScalar dt)
btScalar m_area
Definition: btSoftBody.h:276
btVector3 m_x
Definition: btSoftBody.h:269
btVector3 m_splitv
Definition: btSoftBody.h:281
btVector3 m_vn
Definition: btSoftBody.h:272
btVector3 m_v
Definition: btSoftBody.h:271
btVector3 m_q
Definition: btSoftBody.h:270
btDbvtNode * m_leaf
Definition: btSoftBody.h:277
btVector3 m_n
Definition: btSoftBody.h:274
btVector3 m_f
Definition: btSoftBody.h:273
btMatrix3x3 m_effectiveMass_inv
Definition: btSoftBody.h:283
btMatrix3x3 m_effectiveMass
Definition: btSoftBody.h:282
btScalar m_coords[4]
Definition: btSoftBody.h:442
btVector3 m_offset
Definition: btSoftBody.h:439
Node * m_nodes[4]
Definition: btSoftBody.h:441
const char * m_text
Definition: btSoftBody.h:438
btMatrix3x3 m_scl
Definition: btSoftBody.h:454
btScalar m_volume
Definition: btSoftBody.h:449
btVector3 m_com
Definition: btSoftBody.h:452
tVector3Array m_pos
Definition: btSoftBody.h:450
btMatrix3x3 m_aqq
Definition: btSoftBody.h:455
btMatrix3x3 m_rot
Definition: btSoftBody.h:453
tScalarArray m_wgh
Definition: btSoftBody.h:451
btMultiBodyJacobianData jacobianData_t2
Definition: btSoftBody.h:354
btMultiBodyJacobianData jacobianData_t1
Definition: btSoftBody.h:353
btMatrix3x3 m_c0
Definition: btSoftBody.h:345
btMultiBodyJacobianData jacobianData_normal
Definition: btSoftBody.h:352
RayFromToCaster takes a ray from, ray to (instead of direction!)
Definition: btSoftBody.h:762
RayFromToCaster(const btVector3 &rayFrom, const btVector3 &rayTo, btScalar mxt)
void Process(const btDbvtNode *leaf)
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)
btVector3 m_rayNormalizedDirection
Definition: btSoftBody.h:765
RenderNode * m_n[3]
Definition: btSoftBody.h:301
btScalar m_cfm[2]
Definition: btSoftBody.h:422
btMatrix3x3 m_corotation
Definition: btSoftBody.h:337
btScalar m_element_measure
Definition: btSoftBody.h:326
btMatrix3x3 m_Dm_inverse
Definition: btSoftBody.h:324
btMatrix3x3 m_F
Definition: btSoftBody.h:325
btVector4 m_P_inv[3]
Definition: btSoftBody.h:327
btVector3 m_c0[4]
Definition: btSoftBody.h:321
btDbvtNode * m_leaf
Definition: btSoftBody.h:320
@ V_TwoSided
Vertex normals are oriented toward velocity.
Definition: btSoftBody.h:92
@ V_OneSided
Vertex normals are flipped to match velocity and lift and drag forces are applied.
Definition: btSoftBody.h:94
@ END
Face normals are taken as it is.
Definition: btSoftBody.h:98
@ V_TwoSidedLiftDrag
Vertex normals are flipped to match velocity.
Definition: btSoftBody.h:93
@ F_OneSided
Face normals are flipped to match velocity and lift and drag forces are applied.
Definition: btSoftBody.h:97
@ F_TwoSided
Vertex normals are taken as it is.
Definition: btSoftBody.h:95
@ F_TwoSidedLiftDrag
Face normals are flipped to match velocity.
Definition: btSoftBody.h:96
ePSolver : positions solvers
Definition: btSoftBody.h:114
@ RContacts
Anchor solver.
Definition: btSoftBody.h:119
@ SContacts
Rigid contacts solver.
Definition: btSoftBody.h:120
@ Anchors
Linear solver.
Definition: btSoftBody.h:118
@ END
Soft contacts solver.
Definition: btSoftBody.h:121
eVSolver : velocities solvers
Definition: btSoftBody.h:104
@ END
Linear solver.
Definition: btSoftBody.h:108
@ SDF_RDN
GJK based Multibody vs. deformable face.
Definition: btSoftBody.h:177
@ VF_SS
Rigid versus soft mask.
Definition: btSoftBody.h:169
@ Default
SDF based Rigid vs. deformable node.
Definition: btSoftBody.h:179
@ RVDFmask
Vertex vs face soft vs soft handling.
Definition: btSoftBody.h:174
@ VF_DD
Cluster soft body self collision.
Definition: btSoftBody.h:172
@ CL_SS
Vertex vs face soft vs soft handling.
Definition: btSoftBody.h:170
@ CL_SELF
Cluster vs cluster soft vs soft handling.
Definition: btSoftBody.h:171
@ SVSmask
rigid vs deformable
Definition: btSoftBody.h:168
@ SDF_RS
Rigid versus soft mask.
Definition: btSoftBody.h:164
@ SDF_RD
Cluster vs convex rigid vs soft.
Definition: btSoftBody.h:166
@ SDF_RDF
Rigid versus deformable face mask.
Definition: btSoftBody.h:175
@ SDF_MDF
GJK based Rigid vs. deformable face.
Definition: btSoftBody.h:176
@ CL_RS
SDF based rigid vs soft.
Definition: btSoftBody.h:165
@ Default
Enable debug draw.
Definition: btSoftBody.h:191
const btCollisionObject * m_colObj
Definition: btSoftBody.h:226
btVector3 m_bary
Definition: btSoftBody.h:229
btScalar m_offset
Definition: btSoftBody.h:228
btVector3 m_normal
Definition: btSoftBody.h:227
btVector3 m_velocity
Definition: btSoftBody.h:235
eFeature::_ feature
soft body
Definition: btSoftBody.h:204
btScalar fraction
feature index
Definition: btSoftBody.h:206
int index
feature type
Definition: btSoftBody.h:205
btSoftBody * body
Definition: btSoftBody.h:203