Bullet Collision Detection & Physics Library
Classes | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
btDX11SoftBodySolver Class Reference

#include <btSoftBodySolver_DX11.h>

Inheritance diagram for btDX11SoftBodySolver:
Inheritance graph
[legend]
Collaboration diagram for btDX11SoftBodySolver:
Collaboration graph
[legend]

Classes

struct  AddVelocityCB
 
struct  ApplyForcesCB
 
class  btAcceleratedSoftBodyInterface
 SoftBody class to maintain information about a soft body instance within a solver. More...
 
struct  CollisionObjectIndices
 
struct  CollisionShapeDescription
 Entry in the collision shape array. More...
 
struct  ComputeBoundsCB
 
struct  IntegrateCB
 
struct  PrepareLinksCB
 
struct  SolveCollisionsAndUpdateVelocitiesCB
 
struct  SolvePositionsFromLinksKernelCB
 
struct  UIntVector3
 
struct  UpdatePositionsFromVelocitiesCB
 
struct  UpdateSoftBodiesCB
 
struct  UpdateVelocitiesFromPositionsWithoutVelocitiesCB
 
struct  UpdateVelocitiesFromPositionsWithVelocitiesCB
 
struct  VSolveLinksCB
 

Public Member Functions

 btDX11SoftBodySolver (ID3D11Device *dx11Device, ID3D11DeviceContext *dx11Context, DXFunctions::CompileFromMemoryFunc dx11CompileFromMemory=&D3DX11CompileFromMemory)
 
virtual ~btDX11SoftBodySolver ()
 
virtual SolverTypes getSolverType () const
 Return the type of the solver. More...
 
void setEnableUpdateBounds (bool enableBounds)
 
bool getEnableUpdateBounds () const
 
virtual btSoftBodyLinkDatagetLinkData ()
 
virtual btSoftBodyVertexDatagetVertexData ()
 
virtual btSoftBodyTriangleDatagetTriangleData ()
 
btAcceleratedSoftBodyInterfacefindSoftBodyInterface (const btSoftBody *const softBody)
 
const
btAcceleratedSoftBodyInterface
*const 
findSoftBodyInterface (const btSoftBody *const softBody) const
 
virtual bool checkInitialized ()
 Ensure that this solver is initialized. More...
 
virtual void updateSoftBodies ()
 Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes. More...
 
virtual void optimize (btAlignedObjectArray< btSoftBody * > &softBodies, bool forceUpdate=false)
 Optimize soft bodies in this solver. More...
 
virtual void copyBackToSoftBodies (bool bMove=true)
 Copy necessary data back to the original soft body source objects. More...
 
virtual void solveConstraints (float solverdt)
 Solve constraints for a set of soft bodies. More...
 
virtual void predictMotion (float solverdt)
 Predict motion of soft bodies into next timestep. More...
 
virtual void processCollision (btSoftBody *, const btCollisionObjectWrapper *)
 
virtual void processCollision (btSoftBody *, btSoftBody *)
 Process a collision between two soft bodies. More...
 
- Public Member Functions inherited from btSoftBodySolver
 btSoftBodySolver ()
 
virtual ~btSoftBodySolver ()
 
virtual void processCollision (btSoftBody *, const struct btCollisionObjectWrapper *)=0
 Process a collision between one of the world's soft bodies and another collision object. More...
 
virtual void setNumberOfPositionIterations (int iterations)
 Set the number of velocity constraint solver iterations this solver uses. More...
 
virtual int getNumberOfPositionIterations ()
 Get the number of velocity constraint solver iterations this solver uses. More...
 
virtual void setNumberOfVelocityIterations (int iterations)
 Set the number of velocity constraint solver iterations this solver uses. More...
 
virtual int getNumberOfVelocityIterations ()
 Get the number of velocity constraint solver iterations this solver uses. More...
 
float getTimeScale ()
 Return the timescale that the simulation is using. More...
 

Public Attributes

btSoftBodyLinkDataDX11 m_linkData
 Link data for all cloths. More...
 
btSoftBodyVertexDataDX11 m_vertexData
 
btSoftBodyTriangleDataDX11 m_triangleData
 

Protected Member Functions

virtual void integrate (float solverdt)
 Integrate motion on the solver. More...
 
float computeTriangleArea (const Vectormath::Aos::Point3 &vertex0, const Vectormath::Aos::Point3 &vertex1, const Vectormath::Aos::Point3 &vertex2)
 
virtual bool buildShaders ()
 
void resetNormalsAndAreas (int numVertices)
 
void normalizeNormalsAndAreas (int numVertices)
 
void executeUpdateSoftBodies (int firstTriangle, int numTriangles)
 
void prepareCollisionConstraints ()
 Sort the collision object details array and generate indexing into it for the per-cloth collision object array. More...
 
Vectormath::Aos::Vector3 ProjectOnAxis (const Vectormath::Aos::Vector3 &v, const Vectormath::Aos::Vector3 &a)
 
void ApplyClampedForce (float solverdt, const Vectormath::Aos::Vector3 &force, const Vectormath::Aos::Vector3 &vertexVelocity, float inverseMass, Vectormath::Aos::Vector3 &vertexForce)
 
virtual void applyForces (float solverdt)
 
virtual void updateConstants (float timeStep)
 
int findSoftBodyIndex (const btSoftBody *const softBody)
 
virtual void prepareLinks ()
 
void updatePositionsFromVelocities (float solverdt)
 
void solveLinksForPosition (int startLink, int numLinks, float kst, float ti)
 
void solveLinksForVelocity (int startLink, int numLinks, float kst)
 
void updateVelocitiesFromPositionsWithVelocities (float isolverdt)
 
void updateVelocitiesFromPositionsWithoutVelocities (float isolverdt)
 
void computeBounds ()
 
void solveCollisionsAndUpdateVelocities (float isolverdt)
 
void updateBounds ()
 
void releaseKernels ()
 

Protected Attributes

ID3D11Device * m_dx11Device
 
ID3D11DeviceContext * m_dx11Context
 
DXFunctions dxFunctions
 
bool m_updateSolverConstants
 Variable to define whether we need to update solver constants on the next iteration. More...
 
bool m_shadersInitialized
 
btAlignedObjectArray
< btAcceleratedSoftBodyInterface * > 
m_softBodySet
 Cloths owned by this solver. More...
 
btAlignedObjectArray
< Vectormath::Aos::Vector3
m_perClothAcceleration
 Acceleration value to be applied to all non-static vertices in the solver. More...
 
btDX11Buffer
< Vectormath::Aos::Vector3
m_dx11PerClothAcceleration
 
btAlignedObjectArray
< Vectormath::Aos::Vector3
m_perClothWindVelocity
 Wind velocity to be applied normal to all non-static vertices in the solver. More...
 
btDX11Buffer
< Vectormath::Aos::Vector3
m_dx11PerClothWindVelocity
 
btAlignedObjectArray< float > m_perClothDampingFactor
 Velocity damping factor. More...
 
btDX11Buffer< float > m_dx11PerClothDampingFactor
 
btAlignedObjectArray< float > m_perClothVelocityCorrectionCoefficient
 Velocity correction coefficient. More...
 
btDX11Buffer< float > m_dx11PerClothVelocityCorrectionCoefficient
 
btAlignedObjectArray< float > m_perClothLiftFactor
 Lift parameter for wind effect on cloth. More...
 
btDX11Buffer< float > m_dx11PerClothLiftFactor
 
btAlignedObjectArray< float > m_perClothDragFactor
 Drag parameter for wind effect on cloth. More...
 
btDX11Buffer< float > m_dx11PerClothDragFactor
 
btAlignedObjectArray< float > m_perClothMediumDensity
 Density of the medium in which each cloth sits. More...
 
btDX11Buffer< float > m_dx11PerClothMediumDensity
 
btAlignedObjectArray
< CollisionObjectIndices
m_perClothCollisionObjects
 Collision shape details: pair of index of first collision shape for the cloth and number of collision objects. More...
 
btDX11Buffer
< CollisionObjectIndices
m_dx11PerClothCollisionObjects
 
btAlignedObjectArray
< CollisionShapeDescription
m_collisionObjectDetails
 Collision shapes being passed across to the cloths in this solver. More...
 
btDX11Buffer
< CollisionShapeDescription
m_dx11CollisionObjectDetails
 
btAlignedObjectArray< UIntVector3m_perClothMinBounds
 Minimum bounds for each cloth. More...
 
btDX11Buffer< UIntVector3m_dx11PerClothMinBounds
 
btAlignedObjectArray< UIntVector3m_perClothMaxBounds
 Maximum bounds for each cloth. More...
 
btDX11Buffer< UIntVector3m_dx11PerClothMaxBounds
 
btAlignedObjectArray< float > m_perClothFriction
 Friction coefficient for each cloth. More...
 
btDX11Buffer< float > m_dx11PerClothFriction
 
DXFunctions::KernelDesc prepareLinksKernel
 
DXFunctions::KernelDesc solvePositionsFromLinksKernel
 
DXFunctions::KernelDesc vSolveLinksKernel
 
DXFunctions::KernelDesc integrateKernel
 
DXFunctions::KernelDesc addVelocityKernel
 
DXFunctions::KernelDesc updatePositionsFromVelocitiesKernel
 
DXFunctions::KernelDesc updateVelocitiesFromPositionsWithoutVelocitiesKernel
 
DXFunctions::KernelDesc updateVelocitiesFromPositionsWithVelocitiesKernel
 
DXFunctions::KernelDesc solveCollisionsAndUpdateVelocitiesKernel
 
DXFunctions::KernelDesc resetNormalsAndAreasKernel
 
DXFunctions::KernelDesc normalizeNormalsAndAreasKernel
 
DXFunctions::KernelDesc computeBoundsKernel
 
DXFunctions::KernelDesc updateSoftBodiesKernel
 
DXFunctions::KernelDesc applyForcesKernel
 
bool m_enableUpdateBounds
 
- Protected Attributes inherited from btSoftBodySolver
int m_numberOfPositionIterations
 
int m_numberOfVelocityIterations
 
float m_timeScale
 

Additional Inherited Members

- Public Types inherited from btSoftBodySolver
enum  SolverTypes {
  DEFAULT_SOLVER,
  CPU_SOLVER,
  CL_SOLVER,
  CL_SIMD_SOLVER,
  DX_SOLVER,
  DX_SIMD_SOLVER
}
 

Detailed Description

Definition at line 76 of file btSoftBodySolver_DX11.h.

Constructor & Destructor Documentation

btDX11SoftBodySolver::btDX11SoftBodySolver ( ID3D11Device *  dx11Device,
ID3D11DeviceContext *  dx11Context,
DXFunctions::CompileFromMemoryFunc  dx11CompileFromMemory = &D3DX11CompileFromMemory 
)

Definition at line 574 of file btSoftBodySolver_DX11.cpp.

btDX11SoftBodySolver::~btDX11SoftBodySolver ( )
virtual

Definition at line 603 of file btSoftBodySolver_DX11.cpp.

Member Function Documentation

void btDX11SoftBodySolver::ApplyClampedForce ( float  solverdt,
const Vectormath::Aos::Vector3 force,
const Vectormath::Aos::Vector3 vertexVelocity,
float  inverseMass,
Vectormath::Aos::Vector3 vertexForce 
)
protected

Definition at line 985 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::applyForces ( float  solverdt)
protectedvirtual

Definition at line 996 of file btSoftBodySolver_DX11.cpp.

bool btDX11SoftBodySolver::buildShaders ( )
protectedvirtual

Reimplemented in btDX11SIMDAwareSoftBodySolver.

Definition at line 2078 of file btSoftBodySolver_DX11.cpp.

bool btDX11SoftBodySolver::checkInitialized ( )
virtual

Ensure that this solver is initialized.

Implements btSoftBodySolver.

Definition at line 815 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::computeBounds ( )
protected

Definition at line 1651 of file btSoftBodySolver_DX11.cpp.

float btDX11SoftBodySolver::computeTriangleArea ( const Vectormath::Aos::Point3 vertex0,
const Vectormath::Aos::Point3 vertex1,
const Vectormath::Aos::Point3 vertex2 
)
protected

Definition at line 1118 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::copyBackToSoftBodies ( bool  bMove = true)
virtual

Copy necessary data back to the original soft body source objects.

Implements btSoftBodySolver.

Definition at line 646 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::executeUpdateSoftBodies ( int  firstTriangle,
int  numTriangles 
)
protected

Definition at line 903 of file btSoftBodySolver_DX11.cpp.

int btDX11SoftBodySolver::findSoftBodyIndex ( const btSoftBody *const  softBody)
protected

Definition at line 1796 of file btSoftBodySolver_DX11.cpp.

btDX11SoftBodySolver::btAcceleratedSoftBodyInterface * btDX11SoftBodySolver::findSoftBodyInterface ( const btSoftBody *const  softBody)

Definition at line 1774 of file btSoftBodySolver_DX11.cpp.

const btDX11SoftBodySolver::btAcceleratedSoftBodyInterface *const btDX11SoftBodySolver::findSoftBodyInterface ( const btSoftBody *const  softBody) const

Definition at line 1785 of file btSoftBodySolver_DX11.cpp.

bool btDX11SoftBodySolver::getEnableUpdateBounds ( ) const
inline

Definition at line 584 of file btSoftBodySolver_DX11.h.

btSoftBodyLinkData & btDX11SoftBodySolver::getLinkData ( )
virtual

Reimplemented in btDX11SIMDAwareSoftBodySolver.

Definition at line 797 of file btSoftBodySolver_DX11.cpp.

virtual SolverTypes btDX11SoftBodySolver::getSolverType ( ) const
inlinevirtual

Return the type of the solver.

Implements btSoftBodySolver.

Reimplemented in btDX11SIMDAwareSoftBodySolver.

Definition at line 575 of file btSoftBodySolver_DX11.h.

btSoftBodyTriangleData & btDX11SoftBodySolver::getTriangleData ( )
virtual

Definition at line 809 of file btSoftBodySolver_DX11.cpp.

btSoftBodyVertexData & btDX11SoftBodySolver::getVertexData ( )
virtual

Definition at line 803 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::integrate ( float  solverdt)
protectedvirtual

Integrate motion on the solver.

Definition at line 1069 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::normalizeNormalsAndAreas ( int  numVertices)
protected

Definition at line 861 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::optimize ( btAlignedObjectArray< btSoftBody * > &  softBodies,
bool  forceUpdate = false 
)
virtual

Optimize soft bodies in this solver.

Implements btSoftBodySolver.

Reimplemented in btDX11SIMDAwareSoftBodySolver.

Definition at line 678 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::predictMotion ( float  solverdt)
virtual

Predict motion of soft bodies into next timestep.

Implements btSoftBodySolver.

Definition at line 2204 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::prepareCollisionConstraints ( )
protected

Sort the collision object details array and generate indexing into it for the per-cloth collision object array.

Definition at line 1235 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::prepareLinks ( )
protectedvirtual

Definition at line 1362 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::processCollision ( btSoftBody softBody,
const btCollisionObjectWrapper collisionObject 
)
virtual

Definition at line 2165 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::processCollision ( btSoftBody ,
btSoftBody  
)
virtual

Process a collision between two soft bodies.

Implements btSoftBodySolver.

Definition at line 2159 of file btSoftBodySolver_DX11.cpp.

Vectormath::Aos::Vector3 btDX11SoftBodySolver::ProjectOnAxis ( const Vectormath::Aos::Vector3 v,
const Vectormath::Aos::Vector3 a 
)
protected

Definition at line 980 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::releaseKernels ( )
protected

Definition at line 608 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::resetNormalsAndAreas ( int  numVertices)
protected

Definition at line 824 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::setEnableUpdateBounds ( bool  enableBounds)
inline

Definition at line 580 of file btSoftBodySolver_DX11.h.

void btDX11SoftBodySolver::solveCollisionsAndUpdateVelocities ( float  isolverdt)
protected

Definition at line 1695 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::solveConstraints ( float  solverdt)
virtual

Solve constraints for a set of soft bodies.

Implements btSoftBodySolver.

Reimplemented in btDX11SIMDAwareSoftBodySolver.

Definition at line 1287 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::solveLinksForPosition ( int  startLink,
int  numLinks,
float  kst,
float  ti 
)
protected

Definition at line 1449 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::solveLinksForVelocity ( int  startLink,
int  numLinks,
float  kst 
)
protected

Definition at line 1499 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::updateBounds ( )
protected

Definition at line 1131 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::updateConstants ( float  timeStep)
protectedvirtual

Reimplemented in btDX11SIMDAwareSoftBodySolver.

Definition at line 1204 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::updatePositionsFromVelocities ( float  solverdt)
protected

Definition at line 1407 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::updateSoftBodies ( )
virtual

Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes.

Implements btSoftBodySolver.

Definition at line 948 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::updateVelocitiesFromPositionsWithoutVelocities ( float  isolverdt)
protected

Definition at line 1600 of file btSoftBodySolver_DX11.cpp.

void btDX11SoftBodySolver::updateVelocitiesFromPositionsWithVelocities ( float  isolverdt)
protected

Definition at line 1548 of file btSoftBodySolver_DX11.cpp.

Member Data Documentation

DXFunctions::KernelDesc btDX11SoftBodySolver::addVelocityKernel
protected

Definition at line 505 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::applyForcesKernel
protected

Definition at line 515 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::computeBoundsKernel
protected

Definition at line 512 of file btSoftBodySolver_DX11.h.

DXFunctions btDX11SoftBodySolver::dxFunctions
protected

Definition at line 411 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::integrateKernel
protected

Definition at line 504 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< CollisionShapeDescription > btDX11SoftBodySolver::m_collisionObjectDetails
protected

Collision shapes being passed across to the cloths in this solver.

Definition at line 473 of file btSoftBodySolver_DX11.h.

btDX11Buffer< CollisionShapeDescription > btDX11SoftBodySolver::m_dx11CollisionObjectDetails
protected

Definition at line 474 of file btSoftBodySolver_DX11.h.

ID3D11DeviceContext* btDX11SoftBodySolver::m_dx11Context
protected

Definition at line 409 of file btSoftBodySolver_DX11.h.

ID3D11Device* btDX11SoftBodySolver::m_dx11Device
protected

Definition at line 408 of file btSoftBodySolver_DX11.h.

btDX11Buffer<Vectormath::Aos::Vector3> btDX11SoftBodySolver::m_dx11PerClothAcceleration
protected

Definition at line 435 of file btSoftBodySolver_DX11.h.

btDX11Buffer<CollisionObjectIndices> btDX11SoftBodySolver::m_dx11PerClothCollisionObjects
protected

Definition at line 468 of file btSoftBodySolver_DX11.h.

btDX11Buffer<float> btDX11SoftBodySolver::m_dx11PerClothDampingFactor
protected

Definition at line 445 of file btSoftBodySolver_DX11.h.

btDX11Buffer<float> btDX11SoftBodySolver::m_dx11PerClothDragFactor
protected

Definition at line 457 of file btSoftBodySolver_DX11.h.

btDX11Buffer< float > btDX11SoftBodySolver::m_dx11PerClothFriction
protected

Definition at line 499 of file btSoftBodySolver_DX11.h.

btDX11Buffer<float> btDX11SoftBodySolver::m_dx11PerClothLiftFactor
protected

Definition at line 453 of file btSoftBodySolver_DX11.h.

btDX11Buffer< UIntVector3 > btDX11SoftBodySolver::m_dx11PerClothMaxBounds
protected

Definition at line 492 of file btSoftBodySolver_DX11.h.

btDX11Buffer<float> btDX11SoftBodySolver::m_dx11PerClothMediumDensity
protected

Definition at line 461 of file btSoftBodySolver_DX11.h.

btDX11Buffer< UIntVector3 > btDX11SoftBodySolver::m_dx11PerClothMinBounds
protected

Definition at line 483 of file btSoftBodySolver_DX11.h.

btDX11Buffer<float> btDX11SoftBodySolver::m_dx11PerClothVelocityCorrectionCoefficient
protected

Definition at line 449 of file btSoftBodySolver_DX11.h.

btDX11Buffer<Vectormath::Aos::Vector3> btDX11SoftBodySolver::m_dx11PerClothWindVelocity
protected

Definition at line 441 of file btSoftBodySolver_DX11.h.

bool btDX11SoftBodySolver::m_enableUpdateBounds
protected

Definition at line 517 of file btSoftBodySolver_DX11.h.

btSoftBodyLinkDataDX11 btDX11SoftBodySolver::m_linkData

Link data for all cloths.

Note that this will be sorted batch-wise for efficient computation and m_linkAddresses will maintain the addressing.

Definition at line 414 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< Vectormath::Aos::Vector3 > btDX11SoftBodySolver::m_perClothAcceleration
protected

Acceleration value to be applied to all non-static vertices in the solver.

Index n is cloth n, array sized by number of cloths in the world not the solver.

Definition at line 434 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< CollisionObjectIndices > btDX11SoftBodySolver::m_perClothCollisionObjects
protected

Collision shape details: pair of index of first collision shape for the cloth and number of collision objects.

Definition at line 467 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< float > btDX11SoftBodySolver::m_perClothDampingFactor
protected

Velocity damping factor.

Definition at line 444 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< float > btDX11SoftBodySolver::m_perClothDragFactor
protected

Drag parameter for wind effect on cloth.

Definition at line 456 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< float > btDX11SoftBodySolver::m_perClothFriction
protected

Friction coefficient for each cloth.

Definition at line 498 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< float > btDX11SoftBodySolver::m_perClothLiftFactor
protected

Lift parameter for wind effect on cloth.

Definition at line 452 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< UIntVector3 > btDX11SoftBodySolver::m_perClothMaxBounds
protected

Maximum bounds for each cloth.

Updated by GPU and returned for use by broad phase. These are int vectors as a reminder that they store the int representation of a float, not a float. Bit 31 is inverted - is floats are stored with int-sortable values.

Definition at line 491 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< float > btDX11SoftBodySolver::m_perClothMediumDensity
protected

Density of the medium in which each cloth sits.

Definition at line 460 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< UIntVector3 > btDX11SoftBodySolver::m_perClothMinBounds
protected

Minimum bounds for each cloth.

Updated by GPU and returned for use by broad phase. These are int vectors as a reminder that they store the int representation of a float, not a float. Bit 31 is inverted - is floats are stored with int-sortable values.

Definition at line 482 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< float > btDX11SoftBodySolver::m_perClothVelocityCorrectionCoefficient
protected

Velocity correction coefficient.

Definition at line 448 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< Vectormath::Aos::Vector3 > btDX11SoftBodySolver::m_perClothWindVelocity
protected

Wind velocity to be applied normal to all non-static vertices in the solver.

Index n is cloth n, array sized by number of cloths in the world not the solver.

Definition at line 440 of file btSoftBodySolver_DX11.h.

bool btDX11SoftBodySolver::m_shadersInitialized
protected

Definition at line 423 of file btSoftBodySolver_DX11.h.

btAlignedObjectArray< btAcceleratedSoftBodyInterface * > btDX11SoftBodySolver::m_softBodySet
protected

Cloths owned by this solver.

Only our cloths are in this array.

Definition at line 429 of file btSoftBodySolver_DX11.h.

btSoftBodyTriangleDataDX11 btDX11SoftBodySolver::m_triangleData

Definition at line 416 of file btSoftBodySolver_DX11.h.

bool btDX11SoftBodySolver::m_updateSolverConstants
protected

Variable to define whether we need to update solver constants on the next iteration.

Definition at line 421 of file btSoftBodySolver_DX11.h.

btSoftBodyVertexDataDX11 btDX11SoftBodySolver::m_vertexData

Definition at line 415 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::normalizeNormalsAndAreasKernel
protected

Definition at line 511 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::prepareLinksKernel
protected

Definition at line 501 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::resetNormalsAndAreasKernel
protected

Definition at line 510 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::solveCollisionsAndUpdateVelocitiesKernel
protected

Definition at line 509 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::solvePositionsFromLinksKernel
protected

Definition at line 502 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::updatePositionsFromVelocitiesKernel
protected

Definition at line 506 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::updateSoftBodiesKernel
protected

Definition at line 513 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::updateVelocitiesFromPositionsWithoutVelocitiesKernel
protected

Definition at line 507 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::updateVelocitiesFromPositionsWithVelocitiesKernel
protected

Definition at line 508 of file btSoftBodySolver_DX11.h.

DXFunctions::KernelDesc btDX11SoftBodySolver::vSolveLinksKernel
protected

Definition at line 503 of file btSoftBodySolver_DX11.h.


The documentation for this class was generated from the following files: