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 class btBroadphaseInterface;
33 /* btSoftBodyWorldInfo */
34 struct btSoftBodyWorldInfo
37 btScalar water_density;
38 btScalar water_offset;
39 btVector3 water_normal;
40 btBroadphaseInterface* m_broadphase;
41 btDispatcher* m_dispatcher;
43 btSparseSdf<3> m_sparsesdf;
47 ///The btSoftBody is an class to simulate cloth and volumetric soft bodies.
48 ///There is two-way interaction between btSoftBody and btRigidBody/btCollisionObject.
49 class btSoftBody : public btCollisionObject
52 btAlignedObjectArray<class btCollisionObject*> m_collisionDisabledObjects;
59 struct eAeroModel { enum _ {
60 V_Point, ///Vertex normals are oriented toward velocity
61 V_TwoSided, ///Vertex normals are fliped to match velocity
62 V_OneSided, ///Vertex normals are taken as it is
63 F_TwoSided, ///Face normals are fliped to match velocity
64 F_OneSided, ///Face normals are taken as it is
68 ///eVSolver : velocities solvers
69 struct eVSolver { enum _ {
70 Linear, ///Linear solver
74 ///ePSolver : positions solvers
75 struct ePSolver { enum _ {
76 Linear, ///Linear solver
77 Anchors, ///Anchor solver
78 RContacts, ///Rigid contacts solver
79 SContacts, ///Soft contacts solver
84 struct eSolverPresets { enum _ {
92 struct eFeature { enum _ {
100 typedef btAlignedObjectArray<eVSolver::_> tVSolverArray;
101 typedef btAlignedObjectArray<ePSolver::_> tPSolverArray;
108 struct fCollision { enum _ {
109 RVSmask = 0x000f, ///Rigid versus soft mask
110 SDF_RS = 0x0001, ///SDF based rigid vs soft
111 CL_RS = 0x0002, ///Cluster vs convex rigid vs soft
113 SVSmask = 0x00f0, ///Rigid versus soft mask
114 VF_SS = 0x0010, ///Vertex vs face soft vs soft handling
115 CL_SS = 0x0020, ///Cluster vs cluster soft vs soft handling
122 struct fMaterial { enum _ {
123 DebugDraw = 0x0001, /// Enable debug draw
136 btSoftBody* body; /// soft body
137 eFeature::_ feature; /// feature type
138 int index; /// feature index
139 btScalar fraction; /// time of impact fraction (rayorg+(rayto-rayfrom)*fraction)
145 virtual btScalar Eval(const btVector3& x)=0;
152 typedef btAlignedObjectArray<btScalar> tScalarArray;
153 typedef btAlignedObjectArray<btVector3> tVector3Array;
155 /* sCti is Softbody contact info */
158 btCollisionObject* m_colObj; /* Rigid body */
159 btVector3 m_normal; /* Outward normal */
160 btScalar m_offset; /* Offset from origin */
166 btVector3 m_velocity; /* Velocity */
167 btScalar m_pressure; /* Pressure */
168 btScalar m_density; /* Density */
174 void* m_tag; // User data
175 Element() : m_tag(0) {}
178 struct Material : Element
180 btScalar m_kLST; // Linear stiffness coefficient [0,1]
181 btScalar m_kAST; // Area/Angular stiffness coefficient [0,1]
182 btScalar m_kVST; // Volume stiffness coefficient [0,1]
183 int m_flags; // Flags
187 struct Feature : Element
189 Material* m_material; // Material
192 struct Node : Feature
194 btVector3 m_x; // Position
195 btVector3 m_q; // Previous step position
196 btVector3 m_v; // Velocity
197 btVector3 m_f; // Force accumulator
198 btVector3 m_n; // Normal
199 btScalar m_im; // 1/mass
200 btScalar m_area; // Area
201 btDbvtNode* m_leaf; // Leaf data
202 int m_battach:1; // Attached
205 struct Link : Feature
207 Node* m_n[2]; // Node pointers
208 btScalar m_rl; // Rest length
209 int m_bbending:1; // Bending link
210 btScalar m_c0; // (ima+imb)*kLST
211 btScalar m_c1; // rl^2
212 btScalar m_c2; // |gradient|^2/c0
213 btVector3 m_c3; // gradient
216 struct Face : Feature
218 Node* m_n[3]; // Node pointers
219 btVector3 m_normal; // Normal
220 btScalar m_ra; // Rest area
221 btDbvtNode* m_leaf; // Leaf data
226 sCti m_cti; // Contact infos
227 Node* m_node; // Owner node
228 btMatrix3x3 m_c0; // Impulse matrix
229 btVector3 m_c1; // Relative anchor
230 btScalar m_c2; // ima*dt
231 btScalar m_c3; // Friction
232 btScalar m_c4; // Hardness
237 Node* m_node; // Node
238 Face* m_face; // Face
239 btVector3 m_weights; // Weigths
240 btVector3 m_normal; // Normal
241 btScalar m_margin; // Margin
242 btScalar m_friction; // Friction
243 btScalar m_cfm[2]; // Constraint force mixing
248 Node* m_node; // Node pointer
249 btVector3 m_local; // Anchor position in body space
250 btRigidBody* m_body; // Body
251 btMatrix3x3 m_c0; // Impulse matrix
252 btVector3 m_c1; // Relative anchor
253 btScalar m_c2; // ima*dt
256 struct Note : Element
258 const char* m_text; // Text
259 btVector3 m_offset; // Offset
261 Node* m_nodes[4]; // Nodes
262 btScalar m_coords[4]; // Coordinates
267 bool m_bvolume; // Is valid
268 bool m_bframe; // Is frame
269 btScalar m_volume; // Rest volume
270 tVector3Array m_pos; // Reference positions
271 tScalarArray m_wgh; // Weights
272 btVector3 m_com; // COM
273 btMatrix3x3 m_rot; // Rotation
274 btMatrix3x3 m_scl; // Scale
275 btMatrix3x3 m_aqq; // Base scaling
280 btAlignedObjectArray<Node*> m_nodes;
281 tScalarArray m_masses;
282 tVector3Array m_framerefs;
283 btTransform m_framexform;
289 btVector3 m_vimpulses[2];
290 btVector3 m_dimpulses[2];
296 btScalar m_ndamping; /* Node damping */
297 btScalar m_ldamping; /* Linear damping */
298 btScalar m_adamping; /* Angular damping */
302 Cluster() : m_leaf(0),m_ndamping(0),m_ldamping(0),m_adamping(0),m_matching(0) {}
307 btVector3 m_velocity;
311 Impulse() : m_velocity(0,0,0),m_drift(0,0,0),m_asVelocity(0),m_asDrift(0) {}
312 Impulse operator -() const
315 i.m_velocity=-i.m_velocity;
316 i.m_drift=-i.m_drift;
319 Impulse operator*(btScalar x) const
331 btRigidBody* m_rigid;
332 btCollisionObject* m_collisionObject;
334 Body() : m_soft(0),m_rigid(0),m_collisionObject(0) {}
335 Body(Cluster* p) : m_soft(p),m_rigid(0),m_collisionObject(0) {}
336 Body(btCollisionObject* colObj) : m_soft(0),m_collisionObject(colObj)
338 m_rigid = btRigidBody::upcast(m_collisionObject);
341 void activate() const
343 if(m_rigid) m_rigid->activate();
345 const btMatrix3x3& invWorldInertia() const
347 static const btMatrix3x3 iwi(0,0,0,0,0,0,0,0,0);
348 if(m_rigid) return(m_rigid->getInvInertiaTensorWorld());
349 if(m_soft) return(m_soft->m_invwi);
352 btScalar invMass() const
354 if(m_rigid) return(m_rigid->getInvMass());
355 if(m_soft) return(m_soft->m_imass);
358 const btTransform& xform() const
360 static const btTransform identity=btTransform::getIdentity();
361 if(m_collisionObject) return(m_collisionObject->getInterpolationWorldTransform());
362 if(m_soft) return(m_soft->m_framexform);
365 btVector3 linearVelocity() const
367 if(m_rigid) return(m_rigid->getLinearVelocity());
368 if(m_soft) return(m_soft->m_lv);
369 return(btVector3(0,0,0));
371 btVector3 angularVelocity(const btVector3& rpos) const
373 if(m_rigid) return(cross(m_rigid->getAngularVelocity(),rpos));
374 if(m_soft) return(cross(m_soft->m_av,rpos));
375 return(btVector3(0,0,0));
377 btVector3 angularVelocity() const
379 if(m_rigid) return(m_rigid->getAngularVelocity());
380 if(m_soft) return(m_soft->m_av);
381 return(btVector3(0,0,0));
383 btVector3 velocity(const btVector3& rpos) const
385 return(linearVelocity()+angularVelocity(rpos));
387 void applyVImpulse(const btVector3& impulse,const btVector3& rpos) const
389 if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
390 if(m_soft) btSoftBody::clusterVImpulse(m_soft,rpos,impulse);
392 void applyDImpulse(const btVector3& impulse,const btVector3& rpos) const
394 if(m_rigid) m_rigid->applyImpulse(impulse,rpos);
395 if(m_soft) btSoftBody::clusterDImpulse(m_soft,rpos,impulse);
397 void applyImpulse(const Impulse& impulse,const btVector3& rpos) const
399 if(impulse.m_asVelocity) applyVImpulse(impulse.m_velocity,rpos);
400 if(impulse.m_asDrift) applyDImpulse(impulse.m_drift,rpos);
402 void applyVAImpulse(const btVector3& impulse) const
404 if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
405 if(m_soft) btSoftBody::clusterVAImpulse(m_soft,impulse);
407 void applyDAImpulse(const btVector3& impulse) const
409 if(m_rigid) m_rigid->applyTorqueImpulse(impulse);
410 if(m_soft) btSoftBody::clusterDAImpulse(m_soft,impulse);
412 void applyAImpulse(const Impulse& impulse) const
414 if(impulse.m_asVelocity) applyVAImpulse(impulse.m_velocity);
415 if(impulse.m_asDrift) applyDAImpulse(impulse.m_drift);
417 void applyDCImpulse(const btVector3& impulse) const
419 if(m_rigid) m_rigid->applyCentralImpulse(impulse);
420 if(m_soft) btSoftBody::clusterDCImpulse(m_soft,impulse);
426 struct eType { enum _ {
433 Specs() : erp(1),cfm(1),split(1) {}
445 btMatrix3x3 m_massmatrix;
448 Joint() : m_delete(false) {}
449 virtual void Prepare(btScalar dt,int iterations);
450 virtual void Solve(btScalar dt,btScalar sor)=0;
451 virtual void Terminate(btScalar dt)=0;
452 virtual eType::_ Type() const=0;
455 struct LJoint : Joint
457 struct Specs : Joint::Specs
462 void Prepare(btScalar dt,int iterations);
463 void Solve(btScalar dt,btScalar sor);
464 void Terminate(btScalar dt);
465 eType::_ Type() const { return(eType::Linear); }
468 struct AJoint : Joint
472 virtual void Prepare(AJoint*) {}
473 virtual btScalar Speed(AJoint*,btScalar current) { return(current); }
474 static IControl* Default() { static IControl def;return(&def); }
476 struct Specs : Joint::Specs
478 Specs() : icontrol(IControl::Default()) {}
483 IControl* m_icontrol;
484 void Prepare(btScalar dt,int iterations);
485 void Solve(btScalar dt,btScalar sor);
486 void Terminate(btScalar dt);
487 eType::_ Type() const { return(eType::Angular); }
490 struct CJoint : Joint
497 void Prepare(btScalar dt,int iterations);
498 void Solve(btScalar dt,btScalar sor);
499 void Terminate(btScalar dt);
500 eType::_ Type() const { return(eType::Contact); }
505 eAeroModel::_ aeromodel; // Aerodynamic model (default: V_Point)
506 btScalar kVCF; // Velocities correction factor (Baumgarte)
507 btScalar kDP; // Damping coefficient [0,1]
508 btScalar kDG; // Drag coefficient [0,+inf]
509 btScalar kLF; // Lift coefficient [0,+inf]
510 btScalar kPR; // Pressure coefficient [-inf,+inf]
511 btScalar kVC; // Volume conversation coefficient [0,+inf]
512 btScalar kDF; // Dynamic friction coefficient [0,1]
513 btScalar kMT; // Pose matching coefficient [0,1]
514 btScalar kCHR; // Rigid contacts hardness [0,1]
515 btScalar kKHR; // Kinetic contacts hardness [0,1]
516 btScalar kSHR; // Soft contacts hardness [0,1]
517 btScalar kAHR; // Anchors hardness [0,1]
518 btScalar kSRHR_CL; // Soft vs rigid hardness [0,1] (cluster only)
519 btScalar kSKHR_CL; // Soft vs kinetic hardness [0,1] (cluster only)
520 btScalar kSSHR_CL; // Soft vs soft hardness [0,1] (cluster only)
521 btScalar kSR_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
522 btScalar kSK_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
523 btScalar kSS_SPLT_CL; // Soft vs rigid impulse split [0,1] (cluster only)
524 btScalar maxvolume; // Maximum volume ratio for pose
525 btScalar timescale; // Time scale
526 int viterations; // Velocities solver iterations
527 int piterations; // Positions solver iterations
528 int diterations; // Drift solver iterations
529 int citerations; // Cluster solver iterations
530 int collisions; // Collisions flags
531 tVSolverArray m_vsequence; // Velocity solvers sequence
532 tPSolverArray m_psequence; // Position solvers sequence
533 tPSolverArray m_dsequence; // Drift solvers sequence
538 btScalar sdt; // dt*timescale
539 btScalar isdt; // 1/sdt
540 btScalar velmrg; // velocity margin
541 btScalar radmrg; // radial margin
542 btScalar updmrg; // Update margin
544 /// RayFromToCaster takes a ray from, ray to (instead of direction!)
545 struct RayFromToCaster : btDbvt::ICollide
549 btVector3 m_rayNormalizedDirection;
553 RayFromToCaster(const btVector3& rayFrom,const btVector3& rayTo,btScalar mxt);
554 void Process(const btDbvtNode* leaf);
556 static inline btScalar rayFromToTriangle(const btVector3& rayFrom,
557 const btVector3& rayTo,
558 const btVector3& rayNormalizedDirection,
562 btScalar maxt=SIMD_INFINITY);
569 typedef void (*psolver_t)(btSoftBody*,btScalar,btScalar);
570 typedef void (*vsolver_t)(btSoftBody*,btScalar);
571 typedef btAlignedObjectArray<Cluster*> tClusterArray;
572 typedef btAlignedObjectArray<Note> tNoteArray;
573 typedef btAlignedObjectArray<Node> tNodeArray;
574 typedef btAlignedObjectArray<btDbvtNode*> tLeafArray;
575 typedef btAlignedObjectArray<Link> tLinkArray;
576 typedef btAlignedObjectArray<Face> tFaceArray;
577 typedef btAlignedObjectArray<Anchor> tAnchorArray;
578 typedef btAlignedObjectArray<RContact> tRContactArray;
579 typedef btAlignedObjectArray<SContact> tSContactArray;
580 typedef btAlignedObjectArray<Material*> tMaterialArray;
581 typedef btAlignedObjectArray<Joint*> tJointArray;
582 typedef btAlignedObjectArray<btSoftBody*> tSoftBodyArray;
588 Config m_cfg; // Configuration
589 SolverState m_sst; // Solver state
591 void* m_tag; // User data
592 btSoftBodyWorldInfo* m_worldInfo; // World info
593 tNoteArray m_notes; // Notes
594 tNodeArray m_nodes; // Nodes
595 tLinkArray m_links; // Links
596 tFaceArray m_faces; // Faces
597 tAnchorArray m_anchors; // Anchors
598 tRContactArray m_rcontacts; // Rigid contacts
599 tSContactArray m_scontacts; // Soft contacts
600 tJointArray m_joints; // Joints
601 tMaterialArray m_materials; // Materials
602 btScalar m_timeacc; // Time accumulator
603 btVector3 m_bounds[2]; // Spatial bounds
604 bool m_bUpdateRtCst; // Update runtime constants
605 btDbvt m_ndbvt; // Nodes tree
606 btDbvt m_fdbvt; // Faces tree
607 btDbvt m_cdbvt; // Clusters tree
608 tClusterArray m_clusters; // Clusters
610 btAlignedObjectArray<bool>m_clusterConnectivity;//cluster connectivity, for self-collision
612 btTransform m_initialWorldTransform;
619 btSoftBody( btSoftBodyWorldInfo* worldInfo,int node_count,
623 virtual ~btSoftBody();
624 /* Check for existing link */
626 btAlignedObjectArray<int> m_userIndexMapping;
628 btSoftBodyWorldInfo* getWorldInfo()
633 ///@todo: avoid internal softbody shape hack and move collision code to collision library
634 virtual void setCollisionShape(btCollisionShape* collisionShape)
639 bool checkLink( int node0,
641 bool checkLink( const Node* node0,
642 const Node* node1) const;
643 /* Check for existring face */
644 bool checkFace( int node0,
647 /* Append material */
648 Material* appendMaterial();
650 void appendNote( const char* text,
652 const btVector4& c=btVector4(1,0,0,0),
657 void appendNote( const char* text,
660 void appendNote( const char* text,
663 void appendNote( const char* text,
667 void appendNode( const btVector3& x,btScalar m);
669 void appendLink(int model=-1,Material* mat=0);
670 void appendLink( int node0,
673 bool bcheckexist=false);
674 void appendLink( Node* node0,
677 bool bcheckexist=false);
679 void appendFace(int model=-1,Material* mat=0);
680 void appendFace( int node0,
685 void appendAnchor( int node,
686 btRigidBody* body, bool disableCollisionBetweenLinkedBodies=false);
687 /* Append linear joint */
688 void appendLinearJoint(const LJoint::Specs& specs,Cluster* body0,Body body1);
689 void appendLinearJoint(const LJoint::Specs& specs,Body body=Body());
690 void appendLinearJoint(const LJoint::Specs& specs,btSoftBody* body);
691 /* Append linear joint */
692 void appendAngularJoint(const AJoint::Specs& specs,Cluster* body0,Body body1);
693 void appendAngularJoint(const AJoint::Specs& specs,Body body=Body());
694 void appendAngularJoint(const AJoint::Specs& specs,btSoftBody* body);
695 /* Add force (or gravity) to the entire body */
696 void addForce( const btVector3& force);
697 /* Add force (or gravity) to a node of the body */
698 void addForce( const btVector3& force,
700 /* Add velocity to the entire body */
701 void addVelocity( const btVector3& velocity);
703 /* Set velocity for the entire body */
704 void setVelocity( const btVector3& velocity);
706 /* Add velocity to a node of the body */
707 void addVelocity( const btVector3& velocity,
710 void setMass( int node,
713 btScalar getMass( int node) const;
715 btScalar getTotalMass() const;
716 /* Set total mass (weighted by previous masses) */
717 void setTotalMass( btScalar mass,
718 bool fromfaces=false);
719 /* Set total density */
720 void setTotalDensity(btScalar density);
722 void transform( const btTransform& trs);
724 void translate( const btVector3& trs);
726 void rotate( const btQuaternion& rot);
728 void scale( const btVector3& scl);
729 /* Set current state as pose */
730 void setPose( bool bvolume,
732 /* Return the volume */
733 btScalar getVolume() const;
735 int clusterCount() const;
736 /* Cluster center of mass */
737 static btVector3 clusterCom(const Cluster* cluster);
738 btVector3 clusterCom(int cluster) const;
739 /* Cluster velocity at rpos */
740 static btVector3 clusterVelocity(const Cluster* cluster,const btVector3& rpos);
741 /* Cluster impulse */
742 static void clusterVImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
743 static void clusterDImpulse(Cluster* cluster,const btVector3& rpos,const btVector3& impulse);
744 static void clusterImpulse(Cluster* cluster,const btVector3& rpos,const Impulse& impulse);
745 static void clusterVAImpulse(Cluster* cluster,const btVector3& impulse);
746 static void clusterDAImpulse(Cluster* cluster,const btVector3& impulse);
747 static void clusterAImpulse(Cluster* cluster,const Impulse& impulse);
748 static void clusterDCImpulse(Cluster* cluster,const btVector3& impulse);
749 /* Generate bending constraints based on distance in the adjency graph */
750 int generateBendingConstraints( int distance,
752 /* Randomize constraints to reduce solver bias */
753 void randomizeConstraints();
754 /* Release clusters */
755 void releaseCluster(int index);
756 void releaseClusters();
757 /* Generate clusters (K-mean) */
758 int generateClusters(int k,int maxiterations=8192);
760 void refine(ImplicitFn* ifn,btScalar accurary,bool cut);
762 bool cutLink(int node0,int node1,btScalar position);
763 bool cutLink(const Node* node0,const Node* node1,btScalar position);
765 ///Ray casting using rayFrom and rayTo in worldspace, (not direction!)
766 bool rayTest(const btVector3& rayFrom,
767 const btVector3& rayTo,
770 void setSolver(eSolverPresets::_ preset);
772 void predictMotion(btScalar dt);
773 /* solveConstraints */
774 void solveConstraints();
776 void staticSolve(int iterations);
777 /* solveCommonConstraints */
778 static void solveCommonConstraints(btSoftBody** bodies,int count,int iterations);
780 static void solveClusters(const btAlignedObjectArray<btSoftBody*>& bodies);
781 /* integrateMotion */
782 void integrateMotion();
783 /* defaultCollisionHandlers */
784 void defaultCollisionHandler(btCollisionObject* pco);
785 void defaultCollisionHandler(btSoftBody* psb);
791 static const btSoftBody* upcast(const btCollisionObject* colObj)
793 if (colObj->getInternalType()==CO_SOFT_BODY)
794 return (const btSoftBody*)colObj;
797 static btSoftBody* upcast(btCollisionObject* colObj)
799 if (colObj->getInternalType()==CO_SOFT_BODY)
800 return (btSoftBody*)colObj;
805 // ::btCollisionObject
808 virtual void getAabb(btVector3& aabbMin,btVector3& aabbMax) const
810 aabbMin = m_bounds[0];
811 aabbMax = m_bounds[1];
816 void pointersToIndices();
817 void indicesToPointers(const int* map=0);
819 int rayTest(const btVector3& rayFrom,const btVector3& rayTo,
820 btScalar& mint,eFeature::_& feature,int& index,bool bcountonly) const;
821 void initializeFaceTree();
822 btVector3 evaluateCom() const;
823 bool checkContact(btCollisionObject* colObj,const btVector3& x,btScalar margin,btSoftBody::sCti& cti) const;
824 void updateNormals();
827 void updateConstants();
828 void initializeClusters();
829 void updateClusters();
830 void cleanupClusters();
831 void prepareClusters(int iterations);
832 void solveClusters(btScalar sor);
833 void applyClusters(bool drift);
836 static void PSolve_Anchors(btSoftBody* psb,btScalar kst,btScalar ti);
837 static void PSolve_RContacts(btSoftBody* psb,btScalar kst,btScalar ti);
838 static void PSolve_SContacts(btSoftBody* psb,btScalar,btScalar ti);
839 static void PSolve_Links(btSoftBody* psb,btScalar kst,btScalar ti);
840 static void VSolve_Links(btSoftBody* psb,btScalar kst);
841 static psolver_t getSolver(ePSolver::_ solver);
842 static vsolver_t getSolver(eVSolver::_ solver);
848 #endif //_BT_SOFT_BODY_H