Synchronize changes from branches/GpuClothAMD to trunk

Main improvements are: GPU cloth collision detection against a capsule shape
,OpenCL-OpenGL interoperability (keeping data buffers on GPU), and bug fixes
Thanks to Lee Howes
This commit is contained in:
erwin.coumans
2011-02-27 09:07:07 +00:00
parent ec1bd45f4f
commit d52f58edd8
37 changed files with 3267 additions and 2481 deletions

View File

@@ -34,10 +34,13 @@ btDefaultSoftBodySolver::~btDefaultSoftBodySolver()
{
}
// In this case the data is already in the soft bodies so there is no need for us to do anything
void btDefaultSoftBodySolver::copyBackToSoftBodies()
{
}
void btDefaultSoftBodySolver::optimize( btAlignedObjectArray< btSoftBody * > &softBodies )
void btDefaultSoftBodySolver::optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate)
{
m_softBodySet.copyFromArray( softBodies );
}
@@ -121,6 +124,17 @@ void btDefaultSoftBodySolver::copySoftBodyToVertexBuffer( const btSoftBody *cons
}
} // btDefaultSoftBodySolver::copySoftBodyToVertexBuffer
void btDefaultSoftBodySolver::processCollision( btSoftBody* softBody, btSoftBody* otherSoftBody)
{
softBody->defaultCollisionHandler( otherSoftBody);
}
// For the default solver just leave the soft body to do its collision processing
void btDefaultSoftBodySolver::processCollision( btSoftBody *softBody, btCollisionObject* collisionObject )
{
softBody->defaultCollisionHandler( collisionObject );
} // btDefaultSoftBodySolver::processCollision
void btDefaultSoftBodySolver::predictMotion( float timeStep )
{

View File

@@ -34,18 +34,30 @@ public:
btDefaultSoftBodySolver();
virtual ~btDefaultSoftBodySolver();
virtual SolverTypes getSolverType() const
{
return DEFAULT_SOLVER;
}
virtual bool checkInitialized();
virtual void updateSoftBodies( );
virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies );
virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies,bool forceUpdate=false );
virtual void copyBackToSoftBodies();
virtual void solveConstraints( float solverdt );
virtual void predictMotion( float solverdt );
virtual void copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer );
virtual void processCollision( btSoftBody *, btCollisionObject* );
virtual void processCollision( btSoftBody*, btSoftBody* );
};
#endif // #ifndef BT_ACCELERATED_SOFT_BODY_CPU_SOLVER_H

View File

@@ -21,7 +21,7 @@ subject to the following restrictions:
//
btSoftBody::btSoftBody(btSoftBodyWorldInfo* worldInfo,int node_count, const btVector3* x, const btScalar* m)
:m_worldInfo(worldInfo)
:m_worldInfo(worldInfo),m_softBodySolver(0)
{
/* Init */
initDefaults();
@@ -2903,59 +2903,42 @@ btSoftBody::vsolver_t btSoftBody::getSolver(eVSolver::_ solver)
//
void btSoftBody::defaultCollisionHandler(btCollisionObject* pco)
{
#if 0
// If we have a solver, skip this work.
// It will have been done within the solver.
// TODO: In the case of the collision handler we need to ensure that we're
// updating the data structures correctly and in here we generate the
// collision lists to deal with in the solver
if( this->m_acceleratedSoftBody )
switch(m_cfg.collisions&fCollision::RVSmask)
{
// We need to pass the collision data through to the solver collision engine
// Note that we only add the collision object here, we are not applying the collision or dealing with
// an impulse response.
m_acceleratedSoftBody->addCollisionObject(pco);
} else {
#endif
switch(m_cfg.collisions&fCollision::RVSmask)
case fCollision::SDF_RS:
{
case fCollision::SDF_RS:
{
btSoftColliders::CollideSDF_RS docollide;
btRigidBody* prb1=btRigidBody::upcast(pco);
//btTransform wtr=prb1 ? prb1->getWorldTransform() : pco->getWorldTransform();
btTransform wtr=pco->getWorldTransform();
btSoftColliders::CollideSDF_RS docollide;
btRigidBody* prb1=btRigidBody::upcast(pco);
btTransform wtr=pco->getWorldTransform();
const btTransform ctr=pco->getWorldTransform();
const btScalar timemargin=(wtr.getOrigin()-ctr.getOrigin()).length();
const btScalar basemargin=getCollisionShape()->getMargin();
btVector3 mins;
btVector3 maxs;
ATTRIBUTE_ALIGNED16(btDbvtVolume) volume;
pco->getCollisionShape()->getAabb( pco->getWorldTransform(),
mins,
maxs);
volume=btDbvtVolume::FromMM(mins,maxs);
volume.Expand(btVector3(basemargin,basemargin,basemargin));
docollide.psb = this;
docollide.m_colObj1 = pco;
docollide.m_rigidBody = prb1;
const btTransform ctr=pco->getWorldTransform();
const btScalar timemargin=(wtr.getOrigin()-ctr.getOrigin()).length();
const btScalar basemargin=getCollisionShape()->getMargin();
btVector3 mins;
btVector3 maxs;
ATTRIBUTE_ALIGNED16(btDbvtVolume) volume;
pco->getCollisionShape()->getAabb( pco->getWorldTransform(),
mins,
maxs);
volume=btDbvtVolume::FromMM(mins,maxs);
volume.Expand(btVector3(basemargin,basemargin,basemargin));
docollide.psb = this;
docollide.m_colObj1 = pco;
docollide.m_rigidBody = prb1;
docollide.dynmargin = basemargin+timemargin;
docollide.stamargin = basemargin;
m_ndbvt.collideTV(m_ndbvt.m_root,volume,docollide);
}
break;
case fCollision::CL_RS:
{
btSoftColliders::CollideCL_RS collider;
collider.Process(this,pco);
}
break;
docollide.dynmargin = basemargin+timemargin;
docollide.stamargin = basemargin;
m_ndbvt.collideTV(m_ndbvt.m_root,volume,docollide);
}
#if 0
break;
case fCollision::CL_RS:
{
btSoftColliders::CollideCL_RS collider;
collider.Process(this,pco);
}
break;
}
#endif
}
//

View File

@@ -37,7 +37,7 @@ subject to the following restrictions:
class btBroadphaseInterface;
class btDispatcher;
class btSoftBodySolver;
/* btSoftBodyWorldInfo */
struct btSoftBodyWorldInfo
@@ -50,6 +50,17 @@ struct btSoftBodyWorldInfo
btDispatcher* m_dispatcher;
btVector3 m_gravity;
btSparseSdf<3> m_sparsesdf;
btSoftBodyWorldInfo()
:air_density((btScalar)1.2),
water_density(0),
water_offset(0),
water_normal(0,0,0),
m_broadphase(0),
m_dispatcher(0),
m_gravity(0,-10,0)
{
}
};
@@ -60,6 +71,9 @@ class btSoftBody : public btCollisionObject
public:
btAlignedObjectArray<class btCollisionObject*> m_collisionDisabledObjects;
// The solver object that handles this soft body
btSoftBodySolver *m_softBodySolver;
//
// Enumerations
//
@@ -870,6 +884,31 @@ public:
*/
const btVector3& getWindVelocity();
//
// Set the solver that handles this soft body
// Should not be allowed to get out of sync with reality
// Currently called internally on addition to the world
void setSoftBodySolver( btSoftBodySolver *softBodySolver )
{
m_softBodySolver = softBodySolver;
}
//
// Return the solver that handles this soft body
//
btSoftBodySolver *getSoftBodySolver()
{
return m_softBodySolver;
}
//
// Return the solver that handles this soft body
//
btSoftBodySolver *getSoftBodySolver() const
{
return m_softBodySolver;
}
//
// Cast

View File

@@ -25,7 +25,7 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btConvexInternalShape.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include <string.h> //for memset
//
// btSymMatrix
//
@@ -172,8 +172,7 @@ public:
template <typename T>
static inline void ZeroInitialize(T& value)
{
static const T zerodummy;
value=zerodummy;
memset(&value,0,sizeof(T));
}
//
template <typename T>

View File

@@ -1,165 +1,165 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
#define BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
class btVertexBufferDescriptor
{
public:
enum BufferTypes
{
CPU_BUFFER,
DX11_BUFFER,
OPENGL_BUFFER
};
protected:
bool m_hasVertexPositions;
bool m_hasNormals;
int m_vertexOffset;
int m_vertexStride;
int m_normalOffset;
int m_normalStride;
public:
btVertexBufferDescriptor()
{
m_hasVertexPositions = false;
m_hasNormals = false;
m_vertexOffset = 0;
m_vertexStride = 0;
m_normalOffset = 0;
m_normalStride = 0;
}
virtual ~btVertexBufferDescriptor()
{
}
virtual bool hasVertexPositions() const
{
return m_hasVertexPositions;
}
virtual bool hasNormals() const
{
return m_hasNormals;
}
/**
* Return the type of the vertex buffer descriptor.
*/
virtual BufferTypes getBufferType() const = 0;
/**
* Return the vertex offset in floats from the base pointer.
*/
virtual int getVertexOffset() const
{
return m_vertexOffset;
}
/**
* Return the vertex stride in number of floats between vertices.
*/
virtual int getVertexStride() const
{
return m_vertexStride;
}
/**
* Return the vertex offset in floats from the base pointer.
*/
virtual int getNormalOffset() const
{
return m_normalOffset;
}
/**
* Return the vertex stride in number of floats between vertices.
*/
virtual int getNormalStride() const
{
return m_normalStride;
}
};
class btCPUVertexBufferDescriptor : public btVertexBufferDescriptor
{
protected:
float *m_basePointer;
public:
/**
* vertexBasePointer is pointer to beginning of the buffer.
* vertexOffset is the offset in floats to the first vertex.
* vertexStride is the stride in floats between vertices.
*/
btCPUVertexBufferDescriptor( float *basePointer, int vertexOffset, int vertexStride )
{
m_basePointer = basePointer;
m_vertexOffset = vertexOffset;
m_vertexStride = vertexStride;
m_hasVertexPositions = true;
}
/**
* vertexBasePointer is pointer to beginning of the buffer.
* vertexOffset is the offset in floats to the first vertex.
* vertexStride is the stride in floats between vertices.
*/
btCPUVertexBufferDescriptor( float *basePointer, int vertexOffset, int vertexStride, int normalOffset, int normalStride )
{
m_basePointer = basePointer;
m_vertexOffset = vertexOffset;
m_vertexStride = vertexStride;
m_hasVertexPositions = true;
m_normalOffset = normalOffset;
m_normalStride = normalStride;
m_hasNormals = true;
}
virtual ~btCPUVertexBufferDescriptor()
{
}
/**
* Return the type of the vertex buffer descriptor.
*/
virtual BufferTypes getBufferType() const
{
return CPU_BUFFER;
}
/**
* Return the base pointer in memory to the first vertex.
*/
virtual float *getBasePointer() const
{
return m_basePointer;
}
};
#endif // #ifndef BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
#define BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H
class btVertexBufferDescriptor
{
public:
enum BufferTypes
{
CPU_BUFFER,
DX11_BUFFER,
OPENGL_BUFFER
};
protected:
bool m_hasVertexPositions;
bool m_hasNormals;
int m_vertexOffset;
int m_vertexStride;
int m_normalOffset;
int m_normalStride;
public:
btVertexBufferDescriptor()
{
m_hasVertexPositions = false;
m_hasNormals = false;
m_vertexOffset = 0;
m_vertexStride = 0;
m_normalOffset = 0;
m_normalStride = 0;
}
virtual ~btVertexBufferDescriptor()
{
}
virtual bool hasVertexPositions() const
{
return m_hasVertexPositions;
}
virtual bool hasNormals() const
{
return m_hasNormals;
}
/**
* Return the type of the vertex buffer descriptor.
*/
virtual BufferTypes getBufferType() const = 0;
/**
* Return the vertex offset in floats from the base pointer.
*/
virtual int getVertexOffset() const
{
return m_vertexOffset;
}
/**
* Return the vertex stride in number of floats between vertices.
*/
virtual int getVertexStride() const
{
return m_vertexStride;
}
/**
* Return the vertex offset in floats from the base pointer.
*/
virtual int getNormalOffset() const
{
return m_normalOffset;
}
/**
* Return the vertex stride in number of floats between vertices.
*/
virtual int getNormalStride() const
{
return m_normalStride;
}
};
class btCPUVertexBufferDescriptor : public btVertexBufferDescriptor
{
protected:
float *m_basePointer;
public:
/**
* vertexBasePointer is pointer to beginning of the buffer.
* vertexOffset is the offset in floats to the first vertex.
* vertexStride is the stride in floats between vertices.
*/
btCPUVertexBufferDescriptor( float *basePointer, int vertexOffset, int vertexStride )
{
m_basePointer = basePointer;
m_vertexOffset = vertexOffset;
m_vertexStride = vertexStride;
m_hasVertexPositions = true;
}
/**
* vertexBasePointer is pointer to beginning of the buffer.
* vertexOffset is the offset in floats to the first vertex.
* vertexStride is the stride in floats between vertices.
*/
btCPUVertexBufferDescriptor( float *basePointer, int vertexOffset, int vertexStride, int normalOffset, int normalStride )
{
m_basePointer = basePointer;
m_vertexOffset = vertexOffset;
m_vertexStride = vertexStride;
m_hasVertexPositions = true;
m_normalOffset = normalOffset;
m_normalStride = normalStride;
m_hasNormals = true;
}
virtual ~btCPUVertexBufferDescriptor()
{
}
/**
* Return the type of the vertex buffer descriptor.
*/
virtual BufferTypes getBufferType() const
{
return CPU_BUFFER;
}
/**
* Return the base pointer in memory to the first vertex.
*/
virtual float *getBasePointer() const
{
return m_basePointer;
}
};
#endif // #ifndef BT_SOFT_BODY_SOLVER_VERTEX_BUFFER_H

View File

@@ -1,142 +1,154 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BT_SOFT_BODY_SOLVERS_H
#define BT_SOFT_BODY_SOLVERS_H
#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
class btSoftBodyTriangleData;
class btSoftBodyLinkData;
class btSoftBodyVertexData;
class btVertexBufferDescriptor;
class btCollisionObject;
class btSoftBody;
class btSoftBodySolver
{
protected:
int m_numberOfPositionIterations;
int m_numberOfVelocityIterations;
// Simulation timescale
float m_timeScale;
public:
btSoftBodySolver() :
m_numberOfPositionIterations( 10 ),
m_timeScale( 1 )
{
m_numberOfVelocityIterations = 0;
m_numberOfPositionIterations = 5;
}
virtual ~btSoftBodySolver()
{
}
#if 0
/** Acceleration for all cloths in the solver. Can be used to efficiently apply gravity. */
virtual void setPerClothAcceleration( int clothIdentifier, Vectormath::Aos::Vector3 acceleration ) = 0;
/** A wind velocity applied normal to the cloth for all cloths in the solver. */
virtual void setPerClothWindVelocity( int clothIdentifier, Vectormath::Aos::Vector3 windVelocity ) = 0;
/** Set the density of the medium a given cloth is situated in. This could be air or possibly water. */
virtual void setPerClothMediumDensity( int clothIdentifier, float mediumDensity ) = 0;
/** A damping factor specific to each cloth applied for all cloths. */
virtual void setPerClothDampingFactor( int clothIdentifier, float dampingFactor ) = 0;
/** A damping factor specific to each cloth applied for all cloths. */
virtual void setPerClothVelocityCorrectionCoefficient( int clothIdentifier, float velocityCorrectionCoefficient ) = 0;
/** Lift parameter for wind action on cloth. */
virtual void setPerClothLiftFactor( int clothIdentifier, float liftFactor ) = 0;
/** Drag parameter for wind action on cloth. */
virtual void setPerClothDragFactor( int clothIdentifier, float dragFactor ) = 0;
/**
* Add a velocity to all soft bodies in the solver - useful for doing world-wide velocities such as a change due to gravity
* Only add a velocity to nodes with a non-zero inverse mass.
*/
virtual void addVelocity( Vectormath::Aos::Vector3 velocity ) = 0;
#endif
/** Ensure that this solver is initialized. */
virtual bool checkInitialized() = 0;
/** Optimize soft bodies in this solver. */
virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies ) = 0;
/** Predict motion of soft bodies into next timestep */
virtual void predictMotion( float solverdt ) = 0;
/** Solve constraints for a set of soft bodies */
virtual void solveConstraints( float solverdt ) = 0;
/** Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes */
virtual void updateSoftBodies() = 0;
/** Output current computed vertex data to the vertex buffers for all cloths in the solver. */
virtual void copySoftBodyToVertexBuffer( const btSoftBody * const softBody, btVertexBufferDescriptor *vertexBuffer ) = 0;
/** Set the number of velocity constraint solver iterations this solver uses. */
virtual void setNumberOfPositionIterations( int iterations )
{
m_numberOfPositionIterations = iterations;
}
/** Get the number of velocity constraint solver iterations this solver uses. */
virtual int getNumberOfPositionIterations()
{
return m_numberOfPositionIterations;
}
/** Set the number of velocity constraint solver iterations this solver uses. */
virtual void setNumberOfVelocityIterations( int iterations )
{
m_numberOfVelocityIterations = iterations;
}
/** Get the number of velocity constraint solver iterations this solver uses. */
virtual int getNumberOfVelocityIterations()
{
return m_numberOfVelocityIterations;
}
/** Return the timescale that the simulation is using */
float getTimeScale()
{
return m_timeScale;
}
#if 0
/**
* Add a collision object to be used by the indicated softbody.
*/
virtual void addCollisionObjectForSoftBody( int clothIdentifier, btCollisionObject *collisionObject ) = 0;
#endif
};
#endif // #ifndef BT_SOFT_BODY_SOLVERS_H
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/
This software is provided 'as-is', without any express or implied warranty.
In no event will the authors be held liable for any damages arising from the use of this software.
Permission is granted to anyone to use this software for any purpose,
including commercial applications, and to alter it and redistribute it freely,
subject to the following restrictions:
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.
2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
3. This notice may not be removed or altered from any source distribution.
*/
#ifndef BT_SOFT_BODY_SOLVERS_H
#define BT_SOFT_BODY_SOLVERS_H
#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
class btSoftBodyTriangleData;
class btSoftBodyLinkData;
class btSoftBodyVertexData;
class btVertexBufferDescriptor;
class btCollisionObject;
class btSoftBody;
class btSoftBodySolver
{
public:
enum SolverTypes
{
DEFAULT_SOLVER,
CPU_SOLVER,
CL_SOLVER,
CL_SIMD_SOLVER,
DX_SOLVER,
DX_SIMD_SOLVER
};
protected:
int m_numberOfPositionIterations;
int m_numberOfVelocityIterations;
// Simulation timescale
float m_timeScale;
public:
btSoftBodySolver() :
m_numberOfPositionIterations( 10 ),
m_timeScale( 1 )
{
m_numberOfVelocityIterations = 0;
m_numberOfPositionIterations = 5;
}
virtual ~btSoftBodySolver()
{
}
/**
* Return the type of the solver.
*/
virtual SolverTypes getSolverType() const = 0;
/** Ensure that this solver is initialized. */
virtual bool checkInitialized() = 0;
/** Optimize soft bodies in this solver. */
virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate=false) = 0;
/** Copy necessary data back to the original soft body source objects. */
virtual void copyBackToSoftBodies() = 0;
/** Predict motion of soft bodies into next timestep */
virtual void predictMotion( float solverdt ) = 0;
/** Solve constraints for a set of soft bodies */
virtual void solveConstraints( float solverdt ) = 0;
/** Perform necessary per-step updates of soft bodies such as recomputing normals and bounding boxes */
virtual void updateSoftBodies() = 0;
/** Process a collision between one of the world's soft bodies and another collision object */
virtual void processCollision( btSoftBody *, btCollisionObject* ) = 0;
/** Process a collision between two soft bodies */
virtual void processCollision( btSoftBody*, btSoftBody* ) = 0;
/** Set the number of velocity constraint solver iterations this solver uses. */
virtual void setNumberOfPositionIterations( int iterations )
{
m_numberOfPositionIterations = iterations;
}
/** Get the number of velocity constraint solver iterations this solver uses. */
virtual int getNumberOfPositionIterations()
{
return m_numberOfPositionIterations;
}
/** Set the number of velocity constraint solver iterations this solver uses. */
virtual void setNumberOfVelocityIterations( int iterations )
{
m_numberOfVelocityIterations = iterations;
}
/** Get the number of velocity constraint solver iterations this solver uses. */
virtual int getNumberOfVelocityIterations()
{
return m_numberOfVelocityIterations;
}
/** Return the timescale that the simulation is using */
float getTimeScale()
{
return m_timeScale;
}
#if 0
/**
* Add a collision object to be used by the indicated softbody.
*/
virtual void addCollisionObjectForSoftBody( int clothIdentifier, btCollisionObject *collisionObject ) = 0;
#endif
};
/**
* Class to manage movement of data from a solver to a given target.
* This version is abstract. Subclasses will have custom pairings for different combinations.
*/
class btSoftBodySolverOutput
{
protected:
public:
btSoftBodySolverOutput()
{
}
virtual ~btSoftBodySolverOutput()
{
}
/** Output current computed vertex data to the vertex buffers for all cloths in the solver. */
virtual void copySoftBodyToVertexBuffer( const btSoftBody * const softBody, btVertexBufferDescriptor *vertexBuffer ) = 0;
};
#endif // #ifndef BT_SOFT_BODY_SOLVERS_H

View File

@@ -19,6 +19,8 @@ subject to the following restrictions:
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "btSoftBody.h"
#include "BulletSoftBody/btSoftBodySolvers.h"
///TODO: include all the shapes that the softbody can collide with
///alternatively, implement special case collision algorithms (just like for rigid collision shapes)
@@ -61,7 +63,7 @@ void btSoftRigidCollisionAlgorithm::processCollision (btCollisionObject* body0,b
if (softBody->m_collisionDisabledObjects.findLinearSearch(rigidCollisionObject)==softBody->m_collisionDisabledObjects.size())
{
softBody->defaultCollisionHandler(rigidCollisionObject);
softBody->getSoftBodySolver()->processCollision(softBody, rigidCollisionObject);
}

View File

@@ -82,14 +82,15 @@ void btSoftRigidDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
void btSoftRigidDynamicsWorld::internalSingleStepSimulation( btScalar timeStep )
{
// Let the solver grab the soft bodies and if necessary optimize for it
m_softBodySolver->optimize( getSoftBodyArray() );
if( !m_softBodySolver->checkInitialized() )
{
btAssert( "Solver initialization failed\n" );
}
// Let the solver grab the soft bodies and if necessary optimize for it
m_softBodySolver->optimize( getSoftBodyArray() );
btDiscreteDynamicsWorld::internalSingleStepSimulation( timeStep );
///solve soft bodies constraints
@@ -128,6 +129,10 @@ void btSoftRigidDynamicsWorld::addSoftBody(btSoftBody* body,short int collisionF
{
m_softBodies.push_back(body);
// Set the soft body solver that will deal with this body
// to be the world's solver
body->setSoftBodySolver( m_softBodySolver );
btCollisionWorld::addCollisionObject(body,
collisionFilterGroup,
collisionFilterMask);

View File

@@ -17,6 +17,7 @@ subject to the following restrictions:
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletSoftBody/btSoftBodySolvers.h"
#include "btSoftBody.h"
#define USE_PERSISTENT_CONTACTS 1
@@ -36,7 +37,7 @@ void btSoftSoftCollisionAlgorithm::processCollision (btCollisionObject* body0,bt
{
btSoftBody* soft0 = (btSoftBody*)body0;
btSoftBody* soft1 = (btSoftBody*)body1;
soft0->defaultCollisionHandler(soft1);
soft0->getSoftBodySolver()->processCollision(soft0, soft1);
}
btScalar btSoftSoftCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* /*body0*/,btCollisionObject* /*body1*/,const btDispatcherInfo& /*dispatchInfo*/,btManifoldResult* /*resultOut*/)