#include <btSoftBody.h>
Classes | |
struct | AJoint |
struct | Anchor |
struct | Body |
struct | CJoint |
struct | Cluster |
struct | Config |
struct | eAeroModel |
eAeroModel More... | |
struct | eFeature |
eFeature More... | |
struct | Element |
struct | ePSolver |
ePSolver : positions solvers More... | |
struct | eSolverPresets |
eSolverPresets More... | |
struct | eVSolver |
eVSolver : velocities solvers More... | |
struct | Face |
struct | fCollision |
fCollision More... | |
struct | Feature |
struct | fMaterial |
fMaterial More... | |
struct | ImplicitFn |
struct | Impulse |
struct | Joint |
struct | Link |
struct | LJoint |
struct | Material |
struct | Node |
struct | Note |
struct | Pose |
struct | RayFromToCaster |
RayFromToCaster takes a ray from, ray to (instead of direction!) More... | |
struct | RContact |
struct | SContact |
struct | sCti |
struct | sMedium |
struct | SolverState |
struct | sRayCast |
struct | Tetra |
Public Types | |
typedef void(* | psolver_t )(btSoftBody *, btScalar, btScalar) |
typedef btAlignedObjectArray < Anchor > | tAnchorArray |
typedef btAlignedObjectArray < Cluster * > | tClusterArray |
typedef btAlignedObjectArray < Face > | tFaceArray |
typedef btAlignedObjectArray < Joint * > | tJointArray |
typedef btAlignedObjectArray < btDbvtNode * > | tLeafArray |
typedef btAlignedObjectArray < Link > | tLinkArray |
typedef btAlignedObjectArray < Material * > | tMaterialArray |
typedef btAlignedObjectArray < Node > | tNodeArray |
typedef btAlignedObjectArray < Note > | tNoteArray |
typedef btAlignedObjectArray < ePSolver::_ > | tPSolverArray |
typedef btAlignedObjectArray < RContact > | tRContactArray |
typedef btAlignedObjectArray < btScalar > | tScalarArray |
typedef btAlignedObjectArray < SContact > | tSContactArray |
typedef btAlignedObjectArray < btSoftBody * > | tSoftBodyArray |
typedef btAlignedObjectArray < Tetra > | tTetraArray |
typedef btAlignedObjectArray < btVector3 > | tVector3Array |
typedef btAlignedObjectArray < eVSolver::_ > | tVSolverArray |
typedef void(* | vsolver_t )(btSoftBody *, btScalar) |
Public Member Functions | |
void | addForce (const btVector3 &force) |
void | addForce (const btVector3 &force, int node) |
void | addVelocity (const btVector3 &velocity) |
void | addVelocity (const btVector3 &velocity, int node) |
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 | 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 | appendFace (int model=-1, Material *mat=0) |
void | appendFace (int node0, int node1, int node2, Material *mat=0) |
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 | 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) |
Material * | appendMaterial () |
void | appendNode (const btVector3 &x, btScalar m) |
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 | appendTetra (int model, Material *mat) |
void | appendTetra (int node0, int node1, int node2, int node3, Material *mat=0) |
void | applyClusters (bool drift) |
void | applyForces () |
btSoftBody (btSoftBodyWorldInfo *worldInfo, int node_count, const btVector3 *x, const btScalar *m) | |
btSoftBody (btSoftBodyWorldInfo *worldInfo) | |
virtual int | calculateSerializeBufferSize () const |
bool | checkContact (btCollisionObject *colObj, const btVector3 &x, btScalar margin, btSoftBody::sCti &cti) const |
bool | checkFace (int node0, int node1, int node2) const |
bool | checkLink (int node0, int node1) const |
bool | checkLink (const Node *node0, const Node *node1) const |
void | cleanupClusters () |
btVector3 | clusterCom (int cluster) const |
int | clusterCount () const |
bool | cutLink (int node0, int node1, btScalar position) |
bool | cutLink (const Node *node0, const Node *node1, btScalar position) |
void | dampClusters () |
void | defaultCollisionHandler (btCollisionObject *pco) |
void | defaultCollisionHandler (btSoftBody *psb) |
btVector3 | evaluateCom () const |
int | generateBendingConstraints (int distance, Material *mat=0) |
int | generateClusters (int k, int maxiterations=8192) |
virtual void | getAabb (btVector3 &aabbMin, btVector3 &aabbMax) const |
btScalar | getMass (int node) const |
btSoftBodySolver * | getSoftBodySolver () |
btSoftBodySolver * | getSoftBodySolver () const |
btScalar | getTotalMass () const |
btScalar | getVolume () const |
const btVector3 & | getWindVelocity () |
btSoftBodyWorldInfo * | getWorldInfo () |
void | indicesToPointers (const int *map=0) |
void | initDefaults () |
void | initializeClusters () |
void | initializeFaceTree () |
void | integrateMotion () |
void | pointersToIndices () |
void | predictMotion (btScalar dt) |
void | prepareClusters (int iterations) |
void | randomizeConstraints () |
bool | rayTest (const btVector3 &rayFrom, const btVector3 &rayTo, sRayCast &results) |
Ray casting using rayFrom and rayTo in worldspace, (not direction!) | |
int | rayTest (const btVector3 &rayFrom, const btVector3 &rayTo, btScalar &mint, eFeature::_ &feature, int &index, bool bcountonly) const |
void | refine (ImplicitFn *ifn, btScalar accurary, bool cut) |
void | releaseCluster (int index) |
void | releaseClusters () |
void | rotate (const btQuaternion &rot) |
void | scale (const btVector3 &scl) |
virtual const char * | serialize (void *dataBuffer, class btSerializer *serializer) const |
fills the dataBuffer and returns the struct name (and 0 on failure) | |
virtual void | setCollisionShape (btCollisionShape *collisionShape) |
void | setMass (int node, btScalar mass) |
void | setPose (bool bvolume, bool bframe) |
void | setSoftBodySolver (btSoftBodySolver *softBodySolver) |
void | setSolver (eSolverPresets::_ preset) |
void | setTotalDensity (btScalar density) |
void | setTotalMass (btScalar mass, bool fromfaces=false) |
void | setVelocity (const btVector3 &velocity) |
void | setVolumeDensity (btScalar density) |
void | setVolumeMass (btScalar mass) |
void | setWindVelocity (const btVector3 &velocity) |
void | solveClusters (btScalar sor) |
void | solveConstraints () |
void | staticSolve (int iterations) |
void | transform (const btTransform &trs) |
void | translate (const btVector3 &trs) |
void | updateBounds () |
void | updateClusters () |
void | updateConstants () |
void | updateNormals () |
void | updatePose () |
virtual | ~btSoftBody () |
Static Public Member Functions | |
static void | clusterAImpulse (Cluster *cluster, const Impulse &impulse) |
static btVector3 | clusterCom (const Cluster *cluster) |
static void | clusterDAImpulse (Cluster *cluster, const btVector3 &impulse) |
static void | clusterDCImpulse (Cluster *cluster, const btVector3 &impulse) |
static void | clusterDImpulse (Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse) |
static void | clusterImpulse (Cluster *cluster, const btVector3 &rpos, const Impulse &impulse) |
static void | clusterVAImpulse (Cluster *cluster, const btVector3 &impulse) |
static btVector3 | clusterVelocity (const Cluster *cluster, const btVector3 &rpos) |
static void | clusterVImpulse (Cluster *cluster, const btVector3 &rpos, const btVector3 &impulse) |
static psolver_t | getSolver (ePSolver::_ solver) |
static vsolver_t | getSolver (eVSolver::_ solver) |
static void | PSolve_Anchors (btSoftBody *psb, btScalar kst, btScalar ti) |
static void | PSolve_Links (btSoftBody *psb, btScalar kst, btScalar ti) |
static void | PSolve_RContacts (btSoftBody *psb, btScalar kst, btScalar ti) |
static void | PSolve_SContacts (btSoftBody *psb, btScalar, btScalar ti) |
static void | solveClusters (const btAlignedObjectArray< btSoftBody * > &bodies) |
static void | solveCommonConstraints (btSoftBody **bodies, int count, int iterations) |
static const btSoftBody * | upcast (const btCollisionObject *colObj) |
static btSoftBody * | upcast (btCollisionObject *colObj) |
static void | VSolve_Links (btSoftBody *psb, btScalar kst) |
Public Attributes | |
tAnchorArray | m_anchors |
btVector3 | m_bounds [2] |
bool | m_bUpdateRtCst |
btDbvt | m_cdbvt |
Config | m_cfg |
btAlignedObjectArray< bool > | m_clusterConnectivity |
tClusterArray | m_clusters |
btAlignedObjectArray< class btCollisionObject * > | m_collisionDisabledObjects |
tFaceArray | m_faces |
btDbvt | m_fdbvt |
btTransform | m_initialWorldTransform |
tJointArray | m_joints |
tLinkArray | m_links |
tMaterialArray | m_materials |
btDbvt | m_ndbvt |
tNodeArray | m_nodes |
tNoteArray | m_notes |
Pose | m_pose |
tRContactArray | m_rcontacts |
tSContactArray | m_scontacts |
btSoftBodySolver * | m_softBodySolver |
SolverState | m_sst |
void * | m_tag |
tTetraArray | m_tetras |
btScalar | m_timeacc |
btAlignedObjectArray< int > | m_userIndexMapping |
btVector3 | m_windVelocity |
btSoftBodyWorldInfo * | m_worldInfo |
The btSoftBody is an class to simulate cloth and volumetric soft bodies. There is two-way interaction between btSoftBody and btRigidBody/btCollisionObject.
Definition at line 69 of file btSoftBody.h.
typedef void(* btSoftBody::psolver_t)(btSoftBody *, btScalar, btScalar) |
Definition at line 626 of file btSoftBody.h.
Definition at line 635 of file btSoftBody.h.
Definition at line 628 of file btSoftBody.h.
Definition at line 633 of file btSoftBody.h.
typedef btAlignedObjectArray<Joint*> btSoftBody::tJointArray |
Definition at line 639 of file btSoftBody.h.
Definition at line 631 of file btSoftBody.h.
Definition at line 632 of file btSoftBody.h.
Definition at line 638 of file btSoftBody.h.
Definition at line 630 of file btSoftBody.h.
Definition at line 629 of file btSoftBody.h.
Definition at line 127 of file btSoftBody.h.
Definition at line 636 of file btSoftBody.h.
Definition at line 179 of file btSoftBody.h.
Definition at line 637 of file btSoftBody.h.
Definition at line 640 of file btSoftBody.h.
Definition at line 634 of file btSoftBody.h.
typedef btAlignedObjectArray<btVector3> btSoftBody::tVector3Array |
Definition at line 180 of file btSoftBody.h.
Definition at line 126 of file btSoftBody.h.
typedef void(* btSoftBody::vsolver_t)(btSoftBody *, btScalar) |
Definition at line 627 of file btSoftBody.h.
btSoftBody::btSoftBody | ( | btSoftBodyWorldInfo * | worldInfo, |
int | node_count, | ||
const btVector3 * | x, | ||
const btScalar * | m | ||
) |
btSoftBody::btSoftBody | ( | btSoftBodyWorldInfo * | worldInfo | ) |
virtual btSoftBody::~btSoftBody | ( | ) | [virtual] |
void btSoftBody::addForce | ( | const btVector3 & | force | ) |
void btSoftBody::addForce | ( | const btVector3 & | force, |
int | node | ||
) |
void btSoftBody::addVelocity | ( | const btVector3 & | velocity | ) |
void btSoftBody::addVelocity | ( | const btVector3 & | velocity, |
int | node | ||
) |
void btSoftBody::appendAnchor | ( | int | node, |
btRigidBody * | body, | ||
bool | disableCollisionBetweenLinkedBodies = false , |
||
btScalar | influence = 1 |
||
) |
void btSoftBody::appendAnchor | ( | int | node, |
btRigidBody * | body, | ||
const btVector3 & | localPivot, | ||
bool | disableCollisionBetweenLinkedBodies = false , |
||
btScalar | influence = 1 |
||
) |
void btSoftBody::appendAngularJoint | ( | const AJoint::Specs & | specs, |
Cluster * | body0, | ||
Body | body1 | ||
) |
void btSoftBody::appendAngularJoint | ( | const AJoint::Specs & | specs, |
Body | body = Body() |
||
) |
void btSoftBody::appendAngularJoint | ( | const AJoint::Specs & | specs, |
btSoftBody * | body | ||
) |
void btSoftBody::appendFace | ( | int | model = -1 , |
Material * | mat = 0 |
||
) |
void btSoftBody::appendFace | ( | int | node0, |
int | node1, | ||
int | node2, | ||
Material * | mat = 0 |
||
) |
void btSoftBody::appendLinearJoint | ( | const LJoint::Specs & | specs, |
Cluster * | body0, | ||
Body | body1 | ||
) |
void btSoftBody::appendLinearJoint | ( | const LJoint::Specs & | specs, |
Body | body = Body() |
||
) |
void btSoftBody::appendLinearJoint | ( | const LJoint::Specs & | specs, |
btSoftBody * | body | ||
) |
void btSoftBody::appendLink | ( | int | model = -1 , |
Material * | mat = 0 |
||
) |
void btSoftBody::appendLink | ( | int | node0, |
int | node1, | ||
Material * | mat = 0 , |
||
bool | bcheckexist = false |
||
) |
void btSoftBody::appendLink | ( | Node * | node0, |
Node * | node1, | ||
Material * | mat = 0 , |
||
bool | bcheckexist = false |
||
) |
void btSoftBody::appendNode | ( | const btVector3 & | x, |
btScalar | m | ||
) |
void btSoftBody::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 btSoftBody::appendNote | ( | const char * | text, |
const btVector3 & | o, | ||
Node * | feature | ||
) |
void btSoftBody::appendNote | ( | const char * | text, |
const btVector3 & | o, | ||
Link * | feature | ||
) |
void btSoftBody::appendNote | ( | const char * | text, |
const btVector3 & | o, | ||
Face * | feature | ||
) |
void btSoftBody::appendTetra | ( | int | model, |
Material * | mat | ||
) |
void btSoftBody::appendTetra | ( | int | node0, |
int | node1, | ||
int | node2, | ||
int | node3, | ||
Material * | mat = 0 |
||
) |
void btSoftBody::applyClusters | ( | bool | drift | ) |
void btSoftBody::applyForces | ( | ) |
virtual int btSoftBody::calculateSerializeBufferSize | ( | ) | const [virtual] |
bool btSoftBody::checkContact | ( | btCollisionObject * | colObj, |
const btVector3 & | x, | ||
btScalar | margin, | ||
btSoftBody::sCti & | cti | ||
) | const |
bool btSoftBody::checkFace | ( | int | node0, |
int | node1, | ||
int | node2 | ||
) | const |
bool btSoftBody::checkLink | ( | int | node0, |
int | node1 | ||
) | const |
bool btSoftBody::checkLink | ( | const Node * | node0, |
const Node * | node1 | ||
) | const |
void btSoftBody::cleanupClusters | ( | ) |
static void btSoftBody::clusterAImpulse | ( | Cluster * | cluster, |
const Impulse & | impulse | ||
) | [static] |
static btVector3 btSoftBody::clusterCom | ( | const Cluster * | cluster | ) | [static] |
btVector3 btSoftBody::clusterCom | ( | int | cluster | ) | const |
int btSoftBody::clusterCount | ( | ) | const |
static void btSoftBody::clusterDAImpulse | ( | Cluster * | cluster, |
const btVector3 & | impulse | ||
) | [static] |
static void btSoftBody::clusterDCImpulse | ( | Cluster * | cluster, |
const btVector3 & | impulse | ||
) | [static] |
static void btSoftBody::clusterDImpulse | ( | Cluster * | cluster, |
const btVector3 & | rpos, | ||
const btVector3 & | impulse | ||
) | [static] |
static void btSoftBody::clusterImpulse | ( | Cluster * | cluster, |
const btVector3 & | rpos, | ||
const Impulse & | impulse | ||
) | [static] |
static void btSoftBody::clusterVAImpulse | ( | Cluster * | cluster, |
const btVector3 & | impulse | ||
) | [static] |
static btVector3 btSoftBody::clusterVelocity | ( | const Cluster * | cluster, |
const btVector3 & | rpos | ||
) | [static] |
static void btSoftBody::clusterVImpulse | ( | Cluster * | cluster, |
const btVector3 & | rpos, | ||
const btVector3 & | impulse | ||
) | [static] |
bool btSoftBody::cutLink | ( | int | node0, |
int | node1, | ||
btScalar | position | ||
) |
bool btSoftBody::cutLink | ( | const Node * | node0, |
const Node * | node1, | ||
btScalar | position | ||
) |
void btSoftBody::dampClusters | ( | ) |
void btSoftBody::defaultCollisionHandler | ( | btCollisionObject * | pco | ) |
void btSoftBody::defaultCollisionHandler | ( | btSoftBody * | psb | ) |
btVector3 btSoftBody::evaluateCom | ( | ) | const |
int btSoftBody::generateBendingConstraints | ( | int | distance, |
Material * | mat = 0 |
||
) |
int btSoftBody::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)
virtual void btSoftBody::getAabb | ( | btVector3 & | aabbMin, |
btVector3 & | aabbMax | ||
) | const [inline, virtual] |
Definition at line 931 of file btSoftBody.h.
btScalar btSoftBody::getMass | ( | int | node | ) | const |
btSoftBodySolver* btSoftBody::getSoftBodySolver | ( | ) | [inline] |
Definition at line 896 of file btSoftBody.h.
btSoftBodySolver* btSoftBody::getSoftBodySolver | ( | ) | const [inline] |
Definition at line 904 of file btSoftBody.h.
static psolver_t btSoftBody::getSolver | ( | ePSolver::_ | solver | ) | [static] |
static vsolver_t btSoftBody::getSolver | ( | eVSolver::_ | solver | ) | [static] |
btScalar btSoftBody::getTotalMass | ( | ) | const |
btScalar btSoftBody::getVolume | ( | ) | const |
const btVector3& btSoftBody::getWindVelocity | ( | ) |
Return the wind velocity for interaction with the air.
btSoftBodyWorldInfo* btSoftBody::getWorldInfo | ( | ) | [inline] |
Definition at line 692 of file btSoftBody.h.
void btSoftBody::indicesToPointers | ( | const int * | map = 0 | ) |
void btSoftBody::initDefaults | ( | ) |
void btSoftBody::initializeClusters | ( | ) |
void btSoftBody::initializeFaceTree | ( | ) |
void btSoftBody::integrateMotion | ( | ) |
void btSoftBody::pointersToIndices | ( | ) |
void btSoftBody::predictMotion | ( | btScalar | dt | ) |
void btSoftBody::prepareClusters | ( | int | iterations | ) |
static void btSoftBody::PSolve_Anchors | ( | btSoftBody * | psb, |
btScalar | kst, | ||
btScalar | ti | ||
) | [static] |
static void btSoftBody::PSolve_Links | ( | btSoftBody * | psb, |
btScalar | kst, | ||
btScalar | ti | ||
) | [static] |
static void btSoftBody::PSolve_RContacts | ( | btSoftBody * | psb, |
btScalar | kst, | ||
btScalar | ti | ||
) | [static] |
static void btSoftBody::PSolve_SContacts | ( | btSoftBody * | psb, |
btScalar | , | ||
btScalar | ti | ||
) | [static] |
void btSoftBody::randomizeConstraints | ( | ) |
bool btSoftBody::rayTest | ( | const btVector3 & | rayFrom, |
const btVector3 & | rayTo, | ||
sRayCast & | results | ||
) |
Ray casting using rayFrom and rayTo in worldspace, (not direction!)
int btSoftBody::rayTest | ( | const btVector3 & | rayFrom, |
const btVector3 & | rayTo, | ||
btScalar & | mint, | ||
eFeature::_ & | feature, | ||
int & | index, | ||
bool | bcountonly | ||
) | const |
void btSoftBody::refine | ( | ImplicitFn * | ifn, |
btScalar | accurary, | ||
bool | cut | ||
) |
void btSoftBody::releaseCluster | ( | int | index | ) |
void btSoftBody::releaseClusters | ( | ) |
void btSoftBody::rotate | ( | const btQuaternion & | rot | ) |
void btSoftBody::scale | ( | const btVector3 & | scl | ) |
virtual const char* btSoftBody::serialize | ( | void * | dataBuffer, |
class btSerializer * | serializer | ||
) | const [virtual] |
fills the dataBuffer and returns the struct name (and 0 on failure)
virtual void btSoftBody::setCollisionShape | ( | btCollisionShape * | collisionShape | ) | [inline, virtual] |
Definition at line 698 of file btSoftBody.h.
void btSoftBody::setMass | ( | int | node, |
btScalar | mass | ||
) |
void btSoftBody::setPose | ( | bool | bvolume, |
bool | bframe | ||
) |
void btSoftBody::setSoftBodySolver | ( | btSoftBodySolver * | softBodySolver | ) | [inline] |
Definition at line 888 of file btSoftBody.h.
void btSoftBody::setSolver | ( | eSolverPresets::_ | preset | ) |
void btSoftBody::setTotalDensity | ( | btScalar | density | ) |
void btSoftBody::setTotalMass | ( | btScalar | mass, |
bool | fromfaces = false |
||
) |
void btSoftBody::setVelocity | ( | const btVector3 & | velocity | ) |
void btSoftBody::setVolumeDensity | ( | btScalar | density | ) |
void btSoftBody::setVolumeMass | ( | btScalar | mass | ) |
void btSoftBody::setWindVelocity | ( | const btVector3 & | velocity | ) |
Set a wind velocity for interaction with the air.
static void btSoftBody::solveClusters | ( | const btAlignedObjectArray< btSoftBody * > & | bodies | ) | [static] |
void btSoftBody::solveClusters | ( | btScalar | sor | ) |
static void btSoftBody::solveCommonConstraints | ( | btSoftBody ** | bodies, |
int | count, | ||
int | iterations | ||
) | [static] |
void btSoftBody::solveConstraints | ( | ) |
void btSoftBody::staticSolve | ( | int | iterations | ) |
void btSoftBody::transform | ( | const btTransform & | trs | ) |
void btSoftBody::translate | ( | const btVector3 & | trs | ) |
static const btSoftBody* btSoftBody::upcast | ( | const btCollisionObject * | colObj | ) | [inline, static] |
Definition at line 914 of file btSoftBody.h.
static btSoftBody* btSoftBody::upcast | ( | btCollisionObject * | colObj | ) | [inline, static] |
Definition at line 920 of file btSoftBody.h.
void btSoftBody::updateBounds | ( | ) |
void btSoftBody::updateClusters | ( | ) |
void btSoftBody::updateConstants | ( | ) |
void btSoftBody::updateNormals | ( | ) |
void btSoftBody::updatePose | ( | ) |
static void btSoftBody::VSolve_Links | ( | btSoftBody * | psb, |
btScalar | kst | ||
) | [static] |
Definition at line 656 of file btSoftBody.h.
btVector3 btSoftBody::m_bounds[2] |
Definition at line 662 of file btSoftBody.h.
Definition at line 663 of file btSoftBody.h.
Definition at line 666 of file btSoftBody.h.
Definition at line 646 of file btSoftBody.h.
Definition at line 669 of file btSoftBody.h.
Definition at line 667 of file btSoftBody.h.
btAlignedObjectArray<class btCollisionObject*> btSoftBody::m_collisionDisabledObjects |
Definition at line 72 of file btSoftBody.h.
Definition at line 654 of file btSoftBody.h.
Definition at line 665 of file btSoftBody.h.
Definition at line 671 of file btSoftBody.h.
Definition at line 659 of file btSoftBody.h.
Definition at line 653 of file btSoftBody.h.
Definition at line 660 of file btSoftBody.h.
Definition at line 664 of file btSoftBody.h.
Definition at line 652 of file btSoftBody.h.
Definition at line 651 of file btSoftBody.h.
Definition at line 648 of file btSoftBody.h.
Definition at line 657 of file btSoftBody.h.
Definition at line 658 of file btSoftBody.h.
Definition at line 75 of file btSoftBody.h.
Definition at line 647 of file btSoftBody.h.
void* btSoftBody::m_tag |
Definition at line 649 of file btSoftBody.h.
Definition at line 655 of file btSoftBody.h.
Definition at line 661 of file btSoftBody.h.
Definition at line 690 of file btSoftBody.h.
btVector3 btSoftBody::m_windVelocity |
Definition at line 673 of file btSoftBody.h.
Definition at line 650 of file btSoftBody.h.