|
| btReducedDeformableBody (btSoftBodyWorldInfo *worldInfo, int node_count, const btVector3 *x, const btScalar *m) |
|
| ~btReducedDeformableBody () |
|
void | internalInitialization () |
|
void | setReducedModes (int num_modes, int full_size) |
|
void | setMassProps (const tDenseArray &mass_array) |
|
void | setInertiaProps () |
|
void | setRigidVelocity (const btVector3 &v) |
|
void | setRigidAngularVelocity (const btVector3 &omega) |
|
void | setStiffnessScale (const btScalar ks) |
|
void | setMassScale (const btScalar rho) |
|
void | setFixedNodes (const int n_node) |
|
void | setDamping (const btScalar alpha, const btScalar beta) |
|
void | disableReducedModes (const bool rigid_only) |
|
virtual void | setTotalMass (btScalar mass, bool fromfaces=false) |
|
virtual void | transformTo (const btTransform &trs) |
|
virtual void | transform (const btTransform &trs) |
|
virtual void | scale (const btVector3 &scl) |
|
void | updateLocalMomentArm () |
|
void | predictIntegratedTransform (btScalar dt, btTransform &predictedTransform) |
|
void | updateExternalForceProjectMatrix (bool initialized) |
|
void | endOfTimeStepZeroing () |
|
void | applyInternalVelocityChanges () |
|
void | updateReducedDofs (btScalar solverdt) |
|
void | updateReducedVelocity (btScalar solverdt) |
|
void | mapToFullPosition (const btTransform &ref_trans) |
|
void | mapToFullVelocity (const btTransform &ref_trans) |
|
const btVector3 | computeTotalAngularMomentum () const |
|
const btVector3 | computeNodeFullVelocity (const btTransform &ref_trans, int n_node) const |
|
const btVector3 | internalComputeNodeDeltaVelocity (const btTransform &ref_trans, int n_node) const |
|
void | applyDamping (btScalar timeStep) |
|
void | applyCentralImpulse (const btVector3 &impulse) |
|
void | applyTorqueImpulse (const btVector3 &torque) |
|
void | proceedToTransform (btScalar dt, bool end_of_time_step) |
|
void | internalApplyRigidImpulse (const btVector3 &impulse, const btVector3 &rel_pos) |
|
void | internalApplyFullSpaceImpulse (const btVector3 &impulse, const btVector3 &rel_pos, int n_node, btScalar dt) |
|
void | applyFullSpaceNodalForce (const btVector3 &f_ext, int n_node) |
|
void | applyRigidGravity (const btVector3 &gravity, btScalar dt) |
|
void | applyReducedElasticForce (const tDenseArray &reduce_dofs) |
|
void | applyReducedDampingForce (const tDenseArray &reduce_vel) |
|
virtual btMatrix3x3 | getImpulseFactor (int n_node) |
|
btVector3 | getRelativePos (int n_node) |
|
bool | isReducedModesOFF () const |
|
btScalar | getTotalMass () const |
|
btTransform & | getRigidTransform () |
|
const btVector3 & | getLinearVelocity () const |
|
const btVector3 & | getAngularVelocity () const |
|
Public Member Functions inherited from btSoftBody |
| btSoftBody (btSoftBodyWorldInfo *worldInfo, int node_count, const btVector3 *x, const btScalar *m) |
|
| btSoftBody (btSoftBodyWorldInfo *worldInfo) |
|
void | initDefaults () |
|
virtual | ~btSoftBody () |
|
btSoftBodyWorldInfo * | getWorldInfo () |
|
void | setDampingCoefficient (btScalar damping_coeff) |
|
virtual void | setCollisionShape (btCollisionShape *collisionShape) |
|
bool | checkLink (int node0, int node1) const |
|
bool | checkLink (const Node *node0, const Node *node1) const |
|
bool | checkFace (int node0, int node1, int node2) const |
|
Material * | appendMaterial () |
|
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) |
|
void | appendNote (const char *text, const btVector3 &o, Node *feature) |
|
void | appendNote (const char *text, const btVector3 &o, Link *feature) |
|
void | appendNote (const char *text, const btVector3 &o, Face *feature) |
|
void | appendNode (const btVector3 &x, btScalar m) |
|
void | appendLink (int model=-1, Material *mat=0) |
|
void | appendLink (int node0, int node1, Material *mat=0, bool bcheckexist=false) |
|
void | appendLink (Node *node0, Node *node1, Material *mat=0, bool bcheckexist=false) |
|
void | appendFace (int model=-1, Material *mat=0) |
|
void | appendFace (int node0, int node1, int node2, Material *mat=0) |
|
void | appendTetra (int model, Material *mat) |
|
void | appendTetra (int node0, int node1, int node2, int node3, Material *mat=0) |
|
void | appendDeformableAnchor (int node, btRigidBody *body) |
|
void | appendDeformableAnchor (int node, btMultiBodyLinkCollider *link) |
|
void | appendAnchor (int node, btRigidBody *body, bool disableCollisionBetweenLinkedBodies=false, btScalar influence=1) |
|
void | appendAnchor (int node, btRigidBody *body, const btVector3 &localPivot, bool disableCollisionBetweenLinkedBodies=false, btScalar influence=1) |
|
void | removeAnchor (int node) |
|
void | appendLinearJoint (const LJoint::Specs &specs, Cluster *body0, Body body1) |
|
void | appendLinearJoint (const LJoint::Specs &specs, Body body=Body()) |
|
void | appendLinearJoint (const LJoint::Specs &specs, btSoftBody *body) |
|
void | appendAngularJoint (const AJoint::Specs &specs, Cluster *body0, Body body1) |
|
void | appendAngularJoint (const AJoint::Specs &specs, Body body=Body()) |
|
void | appendAngularJoint (const AJoint::Specs &specs, btSoftBody *body) |
|
void | addForce (const btVector3 &force) |
|
void | addForce (const btVector3 &force, int node) |
|
void | addAeroForceToNode (const btVector3 &windVelocity, int nodeIndex) |
|
void | addAeroForceToFace (const btVector3 &windVelocity, int faceIndex) |
|
void | addVelocity (const btVector3 &velocity) |
|
void | setVelocity (const btVector3 &velocity) |
|
void | addVelocity (const btVector3 &velocity, int node) |
|
void | setMass (int node, btScalar mass) |
|
btScalar | getMass (int node) const |
|
btScalar | getTotalMass () const |
|
void | setTotalMass (btScalar mass, bool fromfaces=false) |
|
void | setTotalDensity (btScalar density) |
|
void | setVolumeMass (btScalar mass) |
|
void | setVolumeDensity (btScalar density) |
|
btVector3 | getLinearVelocity () |
|
void | setLinearVelocity (const btVector3 &linVel) |
|
void | setAngularVelocity (const btVector3 &angVel) |
|
btTransform | getRigidTransform () |
|
virtual void | transformTo (const btTransform &trs) |
|
virtual void | transform (const btTransform &trs) |
|
virtual void | translate (const btVector3 &trs) |
|
virtual void | rotate (const btQuaternion &rot) |
|
virtual void | scale (const btVector3 &scl) |
|
btScalar | getRestLengthScale () |
|
void | setRestLengthScale (btScalar restLength) |
|
void | setPose (bool bvolume, bool bframe) |
|
void | resetLinkRestLengths () |
|
btScalar | getVolume () const |
|
btVector3 | getCenterOfMass () const |
|
int | clusterCount () const |
|
btVector3 | clusterCom (int cluster) const |
|
int | generateBendingConstraints (int distance, Material *mat=0) |
|
void | randomizeConstraints () |
|
void | updateState (const btAlignedObjectArray< btVector3 > &qs, const btAlignedObjectArray< btVector3 > &vs) |
|
void | releaseCluster (int index) |
|
void | releaseClusters () |
|
int | generateClusters (int k, int maxiterations=8192) |
| generateClusters with k=0 will create a convex cluster for each tetrahedron or triangle otherwise an approximation will be used (better performance) More...
|
|
void | refine (ImplicitFn *ifn, btScalar accurary, bool cut) |
|
bool | cutLink (int node0, int node1, btScalar position) |
|
bool | cutLink (const Node *node0, const Node *node1, btScalar position) |
|
bool | rayTest (const btVector3 &rayFrom, const btVector3 &rayTo, sRayCast &results) |
| Ray casting using rayFrom and rayTo in worldspace, (not direction!) More...
|
|
bool | rayFaceTest (const btVector3 &rayFrom, const btVector3 &rayTo, sRayCast &results) |
|
int | rayFaceTest (const btVector3 &rayFrom, const btVector3 &rayTo, btScalar &mint, int &index) const |
|
void | setSolver (eSolverPresets::_ preset) |
|
void | predictMotion (btScalar dt) |
|
void | solveConstraints () |
|
void | staticSolve (int iterations) |
|
void | integrateMotion () |
|
void | defaultCollisionHandler (const btCollisionObjectWrapper *pcoWrap) |
|
void | defaultCollisionHandler (btSoftBody *psb) |
|
void | setSelfCollision (bool useSelfCollision) |
|
bool | useSelfCollision () |
|
void | updateDeactivation (btScalar timeStep) |
|
void | setZeroVelocity () |
|
bool | wantsSleeping () |
|
virtual btMatrix3x3 | getImpulseFactor (int n_node) |
|
void | setWindVelocity (const btVector3 &velocity) |
| Set a wind velocity for interaction with the air. More...
|
|
const btVector3 & | getWindVelocity () |
| Return the wind velocity for interaction with the air. More...
|
|
void | setSoftBodySolver (btSoftBodySolver *softBodySolver) |
|
btSoftBodySolver * | getSoftBodySolver () |
|
btSoftBodySolver * | getSoftBodySolver () const |
|
virtual void | getAabb (btVector3 &aabbMin, btVector3 &aabbMax) const |
|
void | pointersToIndices () |
|
void | indicesToPointers (const int *map=0) |
|
int | rayTest (const btVector3 &rayFrom, const btVector3 &rayTo, btScalar &mint, eFeature::_ &feature, int &index, bool bcountonly) const |
|
void | initializeFaceTree () |
|
void | rebuildNodeTree () |
|
btVector3 | evaluateCom () const |
|
bool | checkDeformableContact (const btCollisionObjectWrapper *colObjWrap, const btVector3 &x, btScalar margin, btSoftBody::sCti &cti, bool predict=false) const |
|
bool | checkDeformableFaceContact (const btCollisionObjectWrapper *colObjWrap, Face &f, btVector3 &contact_point, btVector3 &bary, btScalar margin, btSoftBody::sCti &cti, bool predict=false) const |
|
bool | checkContact (const btCollisionObjectWrapper *colObjWrap, const btVector3 &x, btScalar margin, btSoftBody::sCti &cti) const |
|
void | updateNormals () |
|
void | updateBounds () |
|
void | updatePose () |
|
void | updateConstants () |
|
void | updateLinkConstants () |
|
void | updateArea (bool averageArea=true) |
|
void | initializeClusters () |
|
void | updateClusters () |
|
void | cleanupClusters () |
|
void | prepareClusters (int iterations) |
|
void | solveClusters (btScalar sor) |
|
void | applyClusters (bool drift) |
|
void | dampClusters () |
|
void | setSpringStiffness (btScalar k) |
|
void | setGravityFactor (btScalar gravFactor) |
|
void | setCacheBarycenter (bool cacheBarycenter) |
|
void | initializeDmInverse () |
|
void | updateDeformation () |
|
void | advanceDeformation () |
|
void | applyForces () |
|
void | setMaxStress (btScalar maxStress) |
|
void | interpolateRenderMesh () |
|
void | setCollisionQuadrature (int N) |
|
void | geometricCollisionHandler (btSoftBody *psb) |
|
void | updateNode (btDbvtNode *node, bool use_velocity, bool margin) |
|
void | updateNodeTree (bool use_velocity, bool margin) |
|
template<class DBVTNODE > |
void | updateFace (DBVTNODE *node, bool use_velocity, bool margin) |
|
void | updateFaceTree (bool use_velocity, bool margin) |
|
void | applyRepulsionForce (btScalar timeStep, bool applySpringForce) |
|
virtual int | calculateSerializeBufferSize () const |
|
virtual const char * | serialize (void *dataBuffer, class btSerializer *serializer) const |
| fills the dataBuffer and returns the struct name (and 0 on failure) More...
|
|
| BT_DECLARE_ALIGNED_ALLOCATOR () |
|
bool | mergesSimulationIslands () const |
|
const btVector3 & | getAnisotropicFriction () const |
|
void | setAnisotropicFriction (const btVector3 &anisotropicFriction, int frictionMode=CF_ANISOTROPIC_FRICTION) |
|
bool | hasAnisotropicFriction (int frictionMode=CF_ANISOTROPIC_FRICTION) const |
|
void | setContactProcessingThreshold (btScalar contactProcessingThreshold) |
| the constraint solver can discard solving contacts, if the distance is above this threshold. More...
|
|
btScalar | getContactProcessingThreshold () const |
|
bool | isStaticObject () const |
|
bool | isKinematicObject () const |
|
bool | isStaticOrKinematicObject () const |
|
bool | hasContactResponse () const |
|
| btCollisionObject () |
|
virtual | ~btCollisionObject () |
|
virtual void | setCollisionShape (btCollisionShape *collisionShape) |
|
const btCollisionShape * | getCollisionShape () const |
|
btCollisionShape * | getCollisionShape () |
|
void | setIgnoreCollisionCheck (const btCollisionObject *co, bool ignoreCollisionCheck) |
|
int | getNumObjectsWithoutCollision () const |
|
const btCollisionObject * | getObjectWithoutCollision (int index) |
|
virtual bool | checkCollideWithOverride (const btCollisionObject *co) const |
|
void * | internalGetExtensionPointer () const |
| Avoid using this internal API call, the extension pointer is used by some Bullet extensions. More...
|
|
void | internalSetExtensionPointer (void *pointer) |
| Avoid using this internal API call, the extension pointer is used by some Bullet extensions If you need to store your own user pointer, use 'setUserPointer/getUserPointer' instead. More...
|
|
int | getActivationState () const |
|
void | setActivationState (int newState) const |
|
void | setDeactivationTime (btScalar time) |
|
btScalar | getDeactivationTime () const |
|
void | forceActivationState (int newState) const |
|
void | activate (bool forceActivation=false) const |
|
bool | isActive () const |
|
void | setRestitution (btScalar rest) |
|
btScalar | getRestitution () const |
|
void | setFriction (btScalar frict) |
|
btScalar | getFriction () const |
|
void | setRollingFriction (btScalar frict) |
|
btScalar | getRollingFriction () const |
|
void | setSpinningFriction (btScalar frict) |
|
btScalar | getSpinningFriction () const |
|
void | setContactStiffnessAndDamping (btScalar stiffness, btScalar damping) |
|
btScalar | getContactStiffness () const |
|
btScalar | getContactDamping () const |
|
int | getInternalType () const |
| reserved for Bullet internal usage More...
|
|
btTransform & | getWorldTransform () |
|
const btTransform & | getWorldTransform () const |
|
void | setWorldTransform (const btTransform &worldTrans) |
|
btBroadphaseProxy * | getBroadphaseHandle () |
|
const btBroadphaseProxy * | getBroadphaseHandle () const |
|
void | setBroadphaseHandle (btBroadphaseProxy *handle) |
|
const btTransform & | getInterpolationWorldTransform () const |
|
btTransform & | getInterpolationWorldTransform () |
|
void | setInterpolationWorldTransform (const btTransform &trans) |
|
void | setInterpolationLinearVelocity (const btVector3 &linvel) |
|
void | setInterpolationAngularVelocity (const btVector3 &angvel) |
|
const btVector3 & | getInterpolationLinearVelocity () const |
|
const btVector3 & | getInterpolationAngularVelocity () const |
|
int | getIslandTag () const |
|
void | setIslandTag (int tag) |
|
int | getCompanionId () const |
|
void | setCompanionId (int id) |
|
int | getWorldArrayIndex () const |
|
void | setWorldArrayIndex (int ix) |
|
btScalar | getHitFraction () const |
|
void | setHitFraction (btScalar hitFraction) |
|
int | getCollisionFlags () const |
|
void | setCollisionFlags (int flags) |
|
btScalar | getCcdSweptSphereRadius () const |
| Swept sphere radius (0.0 by default), see btConvexConvexAlgorithm:: More...
|
|
void | setCcdSweptSphereRadius (btScalar radius) |
| Swept sphere radius (0.0 by default), see btConvexConvexAlgorithm:: More...
|
|
btScalar | getCcdMotionThreshold () const |
|
btScalar | getCcdSquareMotionThreshold () const |
|
void | setCcdMotionThreshold (btScalar ccdMotionThreshold) |
| Don't do continuous collision detection if the motion (in one step) is less then m_ccdMotionThreshold. More...
|
|
void * | getUserPointer () const |
| users can point to their objects, userPointer is not used by Bullet More...
|
|
int | getUserIndex () const |
|
int | getUserIndex2 () const |
|
int | getUserIndex3 () const |
|
void | setUserPointer (void *userPointer) |
| users can point to their objects, userPointer is not used by Bullet More...
|
|
void | setUserIndex (int index) |
| users can point to their objects, userPointer is not used by Bullet More...
|
|
void | setUserIndex2 (int index) |
|
void | setUserIndex3 (int index) |
|
int | getUpdateRevisionInternal () const |
|
void | setCustomDebugColor (const btVector3 &colorRGB) |
|
void | removeCustomDebugColor () |
|
bool | getCustomDebugColor (btVector3 &colorRGB) const |
|
bool | checkCollideWith (const btCollisionObject *co) const |
|
virtual int | calculateSerializeBufferSize () const |
|
virtual const char * | serialize (void *dataBuffer, class btSerializer *serializer) const |
| fills the dataBuffer and returns the struct name (and 0 on failure) More...
|
|
virtual void | serializeSingleObject (class btSerializer *serializer) const |
|