Update Files

This commit is contained in:
2025-01-22 16:18:30 +01:00
parent ed4603cf95
commit a36294b518
16718 changed files with 2960346 additions and 0 deletions

View File

@ -0,0 +1,69 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
)
#SUBDIRS( Solvers )
SET(BulletSoftBody_SRCS
btSoftBody.cpp
btSoftBodyConcaveCollisionAlgorithm.cpp
btSoftBodyHelpers.cpp
btSoftBodyRigidBodyCollisionConfiguration.cpp
btSoftRigidCollisionAlgorithm.cpp
btSoftRigidDynamicsWorld.cpp
btSoftMultiBodyDynamicsWorld.cpp
btSoftSoftCollisionAlgorithm.cpp
btDefaultSoftBodySolver.cpp
)
SET(BulletSoftBody_HDRS
btSoftBody.h
btSoftBodyData.h
btSoftBodyConcaveCollisionAlgorithm.h
btSoftBodyHelpers.h
btSoftBodyRigidBodyCollisionConfiguration.h
btSoftRigidCollisionAlgorithm.h
btSoftRigidDynamicsWorld.h
btSoftMultiBodyDynamicsWorld.h
btSoftSoftCollisionAlgorithm.h
btSparseSDF.h
btSoftBodySolvers.h
btDefaultSoftBodySolver.h
btSoftBodySolverVertexBuffer.h
)
ADD_LIBRARY(BulletSoftBody ${BulletSoftBody_SRCS} ${BulletSoftBody_HDRS})
SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES SOVERSION ${BULLET_VERSION})
IF (BUILD_SHARED_LIBS)
TARGET_LINK_LIBRARIES(BulletSoftBody BulletDynamics)
ENDIF (BUILD_SHARED_LIBS)
IF (INSTALL_LIBS)
IF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
IF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5)
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
INSTALL(TARGETS BulletSoftBody DESTINATION .)
ELSE (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
INSTALL(TARGETS BulletSoftBody RUNTIME DESTINATION bin
LIBRARY DESTINATION lib${LIB_SUFFIX}
ARCHIVE DESTINATION lib${LIB_SUFFIX})
INSTALL(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}
DESTINATION ${INCLUDE_INSTALL_DIR} FILES_MATCHING PATTERN "*.h" PATTERN
".svn" EXCLUDE PATTERN "CMakeFiles" EXCLUDE)
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
ENDIF (${CMAKE_MAJOR_VERSION}.${CMAKE_MINOR_VERSION} GREATER 2.5)
IF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES FRAMEWORK true)
SET_TARGET_PROPERTIES(BulletSoftBody PROPERTIES PUBLIC_HEADER "${BulletSoftBody_HDRS}")
ENDIF (APPLE AND BUILD_SHARED_LIBS AND FRAMEWORK)
ENDIF (NOT INTERNAL_CREATE_DISTRIBUTABLE_MSVC_PROJECTFILES)
ENDIF (INSTALL_LIBS)

View File

@ -0,0 +1,151 @@
/*
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.
*/
#include "BulletCollision/CollisionShapes/btTriangleIndexVertexArray.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
#include "btDefaultSoftBodySolver.h"
#include "BulletCollision/CollisionShapes/btCapsuleShape.h"
#include "BulletSoftBody/btSoftBody.h"
btDefaultSoftBodySolver::btDefaultSoftBodySolver()
{
// Initial we will clearly need to update solver constants
// For now this is global for the cloths linked with this solver - we should probably make this body specific
// for performance in future once we understand more clearly when constants need to be updated
m_updateSolverConstants = true;
}
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(bool bMove)
{
}
void btDefaultSoftBodySolver::optimize( btAlignedObjectArray< btSoftBody * > &softBodies , bool forceUpdate)
{
m_softBodySet.copyFromArray( softBodies );
}
void btDefaultSoftBodySolver::updateSoftBodies( )
{
for ( int i=0; i < m_softBodySet.size(); i++)
{
btSoftBody* psb=(btSoftBody*)m_softBodySet[i];
if (psb->isActive())
{
psb->integrateMotion();
}
}
} // updateSoftBodies
bool btDefaultSoftBodySolver::checkInitialized()
{
return true;
}
void btDefaultSoftBodySolver::solveConstraints( float solverdt )
{
// Solve constraints for non-solver softbodies
for(int i=0; i < m_softBodySet.size(); ++i)
{
btSoftBody* psb = static_cast<btSoftBody*>(m_softBodySet[i]);
if (psb->isActive())
{
psb->solveConstraints();
}
}
} // btDefaultSoftBodySolver::solveConstraints
void btDefaultSoftBodySolver::copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer )
{
// Currently only support CPU output buffers
// TODO: check for DX11 buffers. Take all offsets into the same DX11 buffer
// and use them together on a single kernel call if possible by setting up a
// per-cloth target buffer array for the copy kernel.
if( vertexBuffer->getBufferType() == btVertexBufferDescriptor::CPU_BUFFER )
{
const btAlignedObjectArray<btSoftBody::Node> &clothVertices( softBody->m_nodes );
int numVertices = clothVertices.size();
const btCPUVertexBufferDescriptor *cpuVertexBuffer = static_cast< btCPUVertexBufferDescriptor* >(vertexBuffer);
float *basePointer = cpuVertexBuffer->getBasePointer();
if( vertexBuffer->hasVertexPositions() )
{
const int vertexOffset = cpuVertexBuffer->getVertexOffset();
const int vertexStride = cpuVertexBuffer->getVertexStride();
float *vertexPointer = basePointer + vertexOffset;
for( int vertexIndex = 0; vertexIndex < numVertices; ++vertexIndex )
{
btVector3 position = clothVertices[vertexIndex].m_x;
*(vertexPointer + 0) = (float)position.getX();
*(vertexPointer + 1) = (float)position.getY();
*(vertexPointer + 2) = (float)position.getZ();
vertexPointer += vertexStride;
}
}
if( vertexBuffer->hasNormals() )
{
const int normalOffset = cpuVertexBuffer->getNormalOffset();
const int normalStride = cpuVertexBuffer->getNormalStride();
float *normalPointer = basePointer + normalOffset;
for( int vertexIndex = 0; vertexIndex < numVertices; ++vertexIndex )
{
btVector3 normal = clothVertices[vertexIndex].m_n;
*(normalPointer + 0) = (float)normal.getX();
*(normalPointer + 1) = (float)normal.getY();
*(normalPointer + 2) = (float)normal.getZ();
normalPointer += normalStride;
}
}
}
} // 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, const btCollisionObjectWrapper* collisionObjectWrap )
{
softBody->defaultCollisionHandler( collisionObjectWrap );
} // btDefaultSoftBodySolver::processCollision
void btDefaultSoftBodySolver::predictMotion( float timeStep )
{
for ( int i=0; i < m_softBodySet.size(); ++i)
{
btSoftBody* psb = m_softBodySet[i];
if (psb->isActive())
{
psb->predictMotion(timeStep);
}
}
}

View File

@ -0,0 +1,63 @@
/*
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_DEFAULT_SOLVER_H
#define BT_SOFT_BODY_DEFAULT_SOLVER_H
#include "BulletSoftBody/btSoftBodySolvers.h"
#include "btSoftBodySolverVertexBuffer.h"
struct btCollisionObjectWrapper;
class btDefaultSoftBodySolver : public btSoftBodySolver
{
protected:
/** Variable to define whether we need to update solver constants on the next iteration */
bool m_updateSolverConstants;
btAlignedObjectArray< btSoftBody * > m_softBodySet;
public:
btDefaultSoftBodySolver();
virtual ~btDefaultSoftBodySolver();
virtual SolverTypes getSolverType() const
{
return DEFAULT_SOLVER;
}
virtual bool checkInitialized();
virtual void updateSoftBodies( );
virtual void optimize( btAlignedObjectArray< btSoftBody * > &softBodies,bool forceUpdate=false );
virtual void copyBackToSoftBodies(bool bMove = true);
virtual void solveConstraints( float solverdt );
virtual void predictMotion( float solverdt );
virtual void copySoftBodyToVertexBuffer( const btSoftBody *const softBody, btVertexBufferDescriptor *vertexBuffer );
virtual void processCollision( btSoftBody *, const btCollisionObjectWrapper* );
virtual void processCollision( btSoftBody*, btSoftBody* );
};
#endif // #ifndef BT_ACCELERATED_SOFT_BODY_CPU_SOLVER_H

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,358 @@
/*
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.
*/
#include "btSoftBodyConcaveCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/CollisionShapes/btMultiSphereShape.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/CollisionShapes/btConcaveShape.h"
#include "BulletCollision/CollisionDispatch/btManifoldResult.h"
#include "BulletCollision/NarrowPhaseCollision/btRaycastCallback.h"
#include "BulletCollision/CollisionShapes/btTriangleShape.h"
#include "BulletCollision/CollisionShapes/btSphereShape.h"
#include "BulletCollision/CollisionShapes/btTetrahedronShape.h"
#include "BulletCollision/CollisionShapes/btConvexHullShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
#include "LinearMath/btIDebugDraw.h"
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
#include "BulletSoftBody/btSoftBody.h"
#define BT_SOFTBODY_TRIANGLE_EXTRUSION btScalar(0.06)//make this configurable
btSoftBodyConcaveCollisionAlgorithm::btSoftBodyConcaveCollisionAlgorithm( const btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped)
: btCollisionAlgorithm(ci),
m_isSwapped(isSwapped),
m_btSoftBodyTriangleCallback(ci.m_dispatcher1,body0Wrap,body1Wrap,isSwapped)
{
}
btSoftBodyConcaveCollisionAlgorithm::~btSoftBodyConcaveCollisionAlgorithm()
{
}
btSoftBodyTriangleCallback::btSoftBodyTriangleCallback(btDispatcher* dispatcher,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped):
m_dispatcher(dispatcher),
m_dispatchInfoPtr(0)
{
m_softBody = (isSwapped? (btSoftBody*)body1Wrap->getCollisionObject():(btSoftBody*)body0Wrap->getCollisionObject());
m_triBody = isSwapped? body0Wrap->getCollisionObject():body1Wrap->getCollisionObject();
//
// create the manifold from the dispatcher 'manifold pool'
//
// m_manifoldPtr = m_dispatcher->getNewManifold(m_convexBody,m_triBody);
clearCache();
}
btSoftBodyTriangleCallback::~btSoftBodyTriangleCallback()
{
clearCache();
// m_dispatcher->releaseManifold( m_manifoldPtr );
}
void btSoftBodyTriangleCallback::clearCache()
{
for (int i=0;i<m_shapeCache.size();i++)
{
btTriIndex* tmp = m_shapeCache.getAtIndex(i);
btAssert(tmp);
btAssert(tmp->m_childShape);
m_softBody->getWorldInfo()->m_sparsesdf.RemoveReferences(tmp->m_childShape);//necessary?
delete tmp->m_childShape;
}
m_shapeCache.clear();
}
void btSoftBodyTriangleCallback::processTriangle(btVector3* triangle,int partId, int triangleIndex)
{
//just for debugging purposes
//printf("triangle %d",m_triangleCount++);
btCollisionAlgorithmConstructionInfo ci;
ci.m_dispatcher1 = m_dispatcher;
///debug drawing of the overlapping triangles
if (m_dispatchInfoPtr && m_dispatchInfoPtr->m_debugDraw && (m_dispatchInfoPtr->m_debugDraw->getDebugMode() &btIDebugDraw::DBG_DrawWireframe))
{
btVector3 color(1,1,0);
const btTransform& tr = m_triBody->getWorldTransform();
m_dispatchInfoPtr->m_debugDraw->drawLine(tr(triangle[0]),tr(triangle[1]),color);
m_dispatchInfoPtr->m_debugDraw->drawLine(tr(triangle[1]),tr(triangle[2]),color);
m_dispatchInfoPtr->m_debugDraw->drawLine(tr(triangle[2]),tr(triangle[0]),color);
}
btTriIndex triIndex(partId,triangleIndex,0);
btHashKey<btTriIndex> triKey(triIndex.getUid());
btTriIndex* shapeIndex = m_shapeCache[triKey];
if (shapeIndex)
{
btCollisionShape* tm = shapeIndex->m_childShape;
btAssert(tm);
//copy over user pointers to temporary shape
tm->setUserPointer(m_triBody->getCollisionShape()->getUserPointer());
btCollisionObjectWrapper softBody(0,m_softBody->getCollisionShape(),m_softBody,m_softBody->getWorldTransform(),-1,-1);
//btCollisionObjectWrapper triBody(0,tm, ob, btTransform::getIdentity());//ob->getWorldTransform());//??
btCollisionObjectWrapper triBody(0,tm, m_triBody, m_triBody->getWorldTransform(),partId, triangleIndex);
ebtDispatcherQueryType algoType = m_resultOut->m_closestPointDistanceThreshold > 0 ? BT_CLOSEST_POINT_ALGORITHMS : BT_CONTACT_POINT_ALGORITHMS;
btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(&softBody,&triBody,0, algoType);//m_manifoldPtr);
colAlgo->processCollision(&softBody,&triBody,*m_dispatchInfoPtr,m_resultOut);
colAlgo->~btCollisionAlgorithm();
ci.m_dispatcher1->freeCollisionAlgorithm(colAlgo);
return;
}
//aabb filter is already applied!
//btCollisionObject* colObj = static_cast<btCollisionObject*>(m_convexProxy->m_clientObject);
// if (m_softBody->getCollisionShape()->getShapeType()==
{
// btVector3 other;
btVector3 normal = (triangle[1]-triangle[0]).cross(triangle[2]-triangle[0]);
normal.normalize();
normal*= BT_SOFTBODY_TRIANGLE_EXTRUSION;
// other=(triangle[0]+triangle[1]+triangle[2])*0.333333f;
// other+=normal*22.f;
btVector3 pts[6] = {triangle[0]+normal,
triangle[1]+normal,
triangle[2]+normal,
triangle[0]-normal,
triangle[1]-normal,
triangle[2]-normal};
btConvexHullShape* tm = new btConvexHullShape(&pts[0].getX(),6);
// btBU_Simplex1to4 tm(triangle[0],triangle[1],triangle[2],other);
//btTriangleShape tm(triangle[0],triangle[1],triangle[2]);
// tm.setMargin(m_collisionMarginTriangle);
//copy over user pointers to temporary shape
tm->setUserPointer(m_triBody->getCollisionShape()->getUserPointer());
btCollisionObjectWrapper softBody(0,m_softBody->getCollisionShape(),m_softBody,m_softBody->getWorldTransform(),-1,-1);
btCollisionObjectWrapper triBody(0,tm, m_triBody, m_triBody->getWorldTransform(),partId, triangleIndex);//btTransform::getIdentity());//??
ebtDispatcherQueryType algoType = m_resultOut->m_closestPointDistanceThreshold > 0 ? BT_CLOSEST_POINT_ALGORITHMS : BT_CONTACT_POINT_ALGORITHMS;
btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(&softBody,&triBody,0, algoType);//m_manifoldPtr);
colAlgo->processCollision(&softBody,&triBody,*m_dispatchInfoPtr,m_resultOut);
colAlgo->~btCollisionAlgorithm();
ci.m_dispatcher1->freeCollisionAlgorithm(colAlgo);
triIndex.m_childShape = tm;
m_shapeCache.insert(triKey,triIndex);
}
}
void btSoftBodyTriangleCallback::setTimeStepAndCounters(btScalar collisionMarginTriangle,const btCollisionObjectWrapper* triBodyWrap, const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
m_dispatchInfoPtr = &dispatchInfo;
m_collisionMarginTriangle = collisionMarginTriangle+btScalar(BT_SOFTBODY_TRIANGLE_EXTRUSION);
m_resultOut = resultOut;
btVector3 aabbWorldSpaceMin,aabbWorldSpaceMax;
m_softBody->getAabb(aabbWorldSpaceMin,aabbWorldSpaceMax);
btVector3 halfExtents = (aabbWorldSpaceMax-aabbWorldSpaceMin)*btScalar(0.5);
btVector3 softBodyCenter = (aabbWorldSpaceMax+aabbWorldSpaceMin)*btScalar(0.5);
btTransform softTransform;
softTransform.setIdentity();
softTransform.setOrigin(softBodyCenter);
btTransform convexInTriangleSpace;
convexInTriangleSpace = triBodyWrap->getWorldTransform().inverse() * softTransform;
btTransformAabb(halfExtents,m_collisionMarginTriangle,convexInTriangleSpace,m_aabbMin,m_aabbMax);
}
void btSoftBodyConcaveCollisionAlgorithm::clearCache()
{
m_btSoftBodyTriangleCallback.clearCache();
}
void btSoftBodyConcaveCollisionAlgorithm::processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
//btCollisionObject* convexBody = m_isSwapped ? body1 : body0;
const btCollisionObjectWrapper* triBody = m_isSwapped ? body0Wrap : body1Wrap;
if (triBody->getCollisionShape()->isConcave())
{
const btCollisionObject* triOb = triBody->getCollisionObject();
const btConcaveShape* concaveShape = static_cast<const btConcaveShape*>( triOb->getCollisionShape());
// if (convexBody->getCollisionShape()->isConvex())
{
btScalar collisionMarginTriangle = concaveShape->getMargin();
// resultOut->setPersistentManifold(m_btSoftBodyTriangleCallback.m_manifoldPtr);
m_btSoftBodyTriangleCallback.setTimeStepAndCounters(collisionMarginTriangle,triBody,dispatchInfo,resultOut);
concaveShape->processAllTriangles( &m_btSoftBodyTriangleCallback,m_btSoftBodyTriangleCallback.getAabbMin(),m_btSoftBodyTriangleCallback.getAabbMax());
// resultOut->refreshContactPoints();
}
}
}
btScalar btSoftBodyConcaveCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
(void)resultOut;
(void)dispatchInfo;
btCollisionObject* convexbody = m_isSwapped ? body1 : body0;
btCollisionObject* triBody = m_isSwapped ? body0 : body1;
//quick approximation using raycast, todo: hook up to the continuous collision detection (one of the btConvexCast)
//only perform CCD above a certain threshold, this prevents blocking on the long run
//because object in a blocked ccd state (hitfraction<1) get their linear velocity halved each frame...
btScalar squareMot0 = (convexbody->getInterpolationWorldTransform().getOrigin() - convexbody->getWorldTransform().getOrigin()).length2();
if (squareMot0 < convexbody->getCcdSquareMotionThreshold())
{
return btScalar(1.);
}
//const btVector3& from = convexbody->m_worldTransform.getOrigin();
//btVector3 to = convexbody->m_interpolationWorldTransform.getOrigin();
//todo: only do if the motion exceeds the 'radius'
btTransform triInv = triBody->getWorldTransform().inverse();
btTransform convexFromLocal = triInv * convexbody->getWorldTransform();
btTransform convexToLocal = triInv * convexbody->getInterpolationWorldTransform();
struct LocalTriangleSphereCastCallback : public btTriangleCallback
{
btTransform m_ccdSphereFromTrans;
btTransform m_ccdSphereToTrans;
btTransform m_meshTransform;
btScalar m_ccdSphereRadius;
btScalar m_hitFraction;
LocalTriangleSphereCastCallback(const btTransform& from,const btTransform& to,btScalar ccdSphereRadius,btScalar hitFraction)
:m_ccdSphereFromTrans(from),
m_ccdSphereToTrans(to),
m_ccdSphereRadius(ccdSphereRadius),
m_hitFraction(hitFraction)
{
}
virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex)
{
(void)partId;
(void)triangleIndex;
//do a swept sphere for now
btTransform ident;
ident.setIdentity();
btConvexCast::CastResult castResult;
castResult.m_fraction = m_hitFraction;
btSphereShape pointShape(m_ccdSphereRadius);
btTriangleShape triShape(triangle[0],triangle[1],triangle[2]);
btVoronoiSimplexSolver simplexSolver;
btSubsimplexConvexCast convexCaster(&pointShape,&triShape,&simplexSolver);
//GjkConvexCast convexCaster(&pointShape,convexShape,&simplexSolver);
//ContinuousConvexCollision convexCaster(&pointShape,convexShape,&simplexSolver,0);
//local space?
if (convexCaster.calcTimeOfImpact(m_ccdSphereFromTrans,m_ccdSphereToTrans,
ident,ident,castResult))
{
if (m_hitFraction > castResult.m_fraction)
m_hitFraction = castResult.m_fraction;
}
}
};
if (triBody->getCollisionShape()->isConcave())
{
btVector3 rayAabbMin = convexFromLocal.getOrigin();
rayAabbMin.setMin(convexToLocal.getOrigin());
btVector3 rayAabbMax = convexFromLocal.getOrigin();
rayAabbMax.setMax(convexToLocal.getOrigin());
btScalar ccdRadius0 = convexbody->getCcdSweptSphereRadius();
rayAabbMin -= btVector3(ccdRadius0,ccdRadius0,ccdRadius0);
rayAabbMax += btVector3(ccdRadius0,ccdRadius0,ccdRadius0);
btScalar curHitFraction = btScalar(1.); //is this available?
LocalTriangleSphereCastCallback raycastCallback(convexFromLocal,convexToLocal,
convexbody->getCcdSweptSphereRadius(),curHitFraction);
raycastCallback.m_hitFraction = convexbody->getHitFraction();
btCollisionObject* concavebody = triBody;
btConcaveShape* triangleMesh = (btConcaveShape*) concavebody->getCollisionShape();
if (triangleMesh)
{
triangleMesh->processAllTriangles(&raycastCallback,rayAabbMin,rayAabbMax);
}
if (raycastCallback.m_hitFraction < convexbody->getHitFraction())
{
convexbody->setHitFraction( raycastCallback.m_hitFraction);
return raycastCallback.m_hitFraction;
}
}
return btScalar(1.);
}

View File

@ -0,0 +1,155 @@
/*
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_CONCAVE_COLLISION_ALGORITHM_H
#define BT_SOFT_BODY_CONCAVE_COLLISION_ALGORITHM_H
#include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "BulletCollision/CollisionShapes/btTriangleCallback.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
class btDispatcher;
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
class btSoftBody;
class btCollisionShape;
#include "LinearMath/btHashMap.h"
#include "BulletCollision/BroadphaseCollision/btQuantizedBvh.h" //for definition of MAX_NUM_PARTS_IN_BITS
struct btTriIndex
{
int m_PartIdTriangleIndex;
class btCollisionShape* m_childShape;
btTriIndex(int partId,int triangleIndex,btCollisionShape* shape)
{
m_PartIdTriangleIndex = (partId<<(31-MAX_NUM_PARTS_IN_BITS)) | triangleIndex;
m_childShape = shape;
}
int getTriangleIndex() const
{
// Get only the lower bits where the triangle index is stored
unsigned int x = 0;
unsigned int y = (~(x&0))<<(31-MAX_NUM_PARTS_IN_BITS);
return (m_PartIdTriangleIndex&~(y));
}
int getPartId() const
{
// Get only the highest bits where the part index is stored
return (m_PartIdTriangleIndex>>(31-MAX_NUM_PARTS_IN_BITS));
}
int getUid() const
{
return m_PartIdTriangleIndex;
}
};
///For each triangle in the concave mesh that overlaps with the AABB of a soft body (m_softBody), processTriangle is called.
class btSoftBodyTriangleCallback : public btTriangleCallback
{
btSoftBody* m_softBody;
const btCollisionObject* m_triBody;
btVector3 m_aabbMin;
btVector3 m_aabbMax ;
btManifoldResult* m_resultOut;
btDispatcher* m_dispatcher;
const btDispatcherInfo* m_dispatchInfoPtr;
btScalar m_collisionMarginTriangle;
btHashMap<btHashKey<btTriIndex>,btTriIndex> m_shapeCache;
public:
int m_triangleCount;
// btPersistentManifold* m_manifoldPtr;
btSoftBodyTriangleCallback(btDispatcher* dispatcher,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped);
void setTimeStepAndCounters(btScalar collisionMarginTriangle,const btCollisionObjectWrapper* triObjWrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
virtual ~btSoftBodyTriangleCallback();
virtual void processTriangle(btVector3* triangle, int partId, int triangleIndex);
void clearCache();
SIMD_FORCE_INLINE const btVector3& getAabbMin() const
{
return m_aabbMin;
}
SIMD_FORCE_INLINE const btVector3& getAabbMax() const
{
return m_aabbMax;
}
};
/// btSoftBodyConcaveCollisionAlgorithm supports collision between soft body shapes and (concave) trianges meshes.
class btSoftBodyConcaveCollisionAlgorithm : public btCollisionAlgorithm
{
bool m_isSwapped;
btSoftBodyTriangleCallback m_btSoftBodyTriangleCallback;
public:
btSoftBodyConcaveCollisionAlgorithm( const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,bool isSwapped);
virtual ~btSoftBodyConcaveCollisionAlgorithm();
virtual void processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
btScalar calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
virtual void getAllContactManifolds(btManifoldArray& manifoldArray)
{
//we don't add any manifolds
}
void clearCache();
struct CreateFunc :public btCollisionAlgorithmCreateFunc
{
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(btSoftBodyConcaveCollisionAlgorithm));
return new(mem) btSoftBodyConcaveCollisionAlgorithm(ci,body0Wrap,body1Wrap,false);
}
};
struct SwappedCreateFunc :public btCollisionAlgorithmCreateFunc
{
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(btSoftBodyConcaveCollisionAlgorithm));
return new(mem) btSoftBodyConcaveCollisionAlgorithm(ci,body0Wrap,body1Wrap,true);
}
};
};
#endif //BT_SOFT_BODY_CONCAVE_COLLISION_ALGORITHM_H

View File

@ -0,0 +1,217 @@
/*
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_SOFTBODY_FLOAT_DATA
#define BT_SOFTBODY_FLOAT_DATA
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletDynamics/Dynamics/btRigidBody.h"
struct SoftBodyMaterialData
{
float m_linearStiffness;
float m_angularStiffness;
float m_volumeStiffness;
int m_flags;
};
struct SoftBodyNodeData
{
SoftBodyMaterialData *m_material;
btVector3FloatData m_position;
btVector3FloatData m_previousPosition;
btVector3FloatData m_velocity;
btVector3FloatData m_accumulatedForce;
btVector3FloatData m_normal;
float m_inverseMass;
float m_area;
int m_attach;
int m_pad;
};
struct SoftBodyLinkData
{
SoftBodyMaterialData *m_material;
int m_nodeIndices[2]; // Node pointers
float m_restLength; // Rest length
int m_bbending; // Bending link
};
struct SoftBodyFaceData
{
btVector3FloatData m_normal; // Normal
SoftBodyMaterialData *m_material;
int m_nodeIndices[3]; // Node pointers
float m_restArea; // Rest area
};
struct SoftBodyTetraData
{
btVector3FloatData m_c0[4]; // gradients
SoftBodyMaterialData *m_material;
int m_nodeIndices[4]; // Node pointers
float m_restVolume; // Rest volume
float m_c1; // (4*kVST)/(im0+im1+im2+im3)
float m_c2; // m_c1/sum(|g0..3|^2)
int m_pad;
};
struct SoftRigidAnchorData
{
btMatrix3x3FloatData m_c0; // Impulse matrix
btVector3FloatData m_c1; // Relative anchor
btVector3FloatData m_localFrame; // Anchor position in body space
btRigidBodyData *m_rigidBody;
int m_nodeIndex; // Node pointer
float m_c2; // ima*dt
};
struct SoftBodyConfigData
{
int m_aeroModel; // Aerodynamic model (default: V_Point)
float m_baumgarte; // Velocities correction factor (Baumgarte)
float m_damping; // Damping coefficient [0,1]
float m_drag; // Drag coefficient [0,+inf]
float m_lift; // Lift coefficient [0,+inf]
float m_pressure; // Pressure coefficient [-inf,+inf]
float m_volume; // Volume conversation coefficient [0,+inf]
float m_dynamicFriction; // Dynamic friction coefficient [0,1]
float m_poseMatch; // Pose matching coefficient [0,1]
float m_rigidContactHardness; // Rigid contacts hardness [0,1]
float m_kineticContactHardness; // Kinetic contacts hardness [0,1]
float m_softContactHardness; // Soft contacts hardness [0,1]
float m_anchorHardness; // Anchors hardness [0,1]
float m_softRigidClusterHardness; // Soft vs rigid hardness [0,1] (cluster only)
float m_softKineticClusterHardness; // Soft vs kinetic hardness [0,1] (cluster only)
float m_softSoftClusterHardness; // Soft vs soft hardness [0,1] (cluster only)
float m_softRigidClusterImpulseSplit; // Soft vs rigid impulse split [0,1] (cluster only)
float m_softKineticClusterImpulseSplit; // Soft vs rigid impulse split [0,1] (cluster only)
float m_softSoftClusterImpulseSplit; // Soft vs rigid impulse split [0,1] (cluster only)
float m_maxVolume; // Maximum volume ratio for pose
float m_timeScale; // Time scale
int m_velocityIterations; // Velocities solver iterations
int m_positionIterations; // Positions solver iterations
int m_driftIterations; // Drift solver iterations
int m_clusterIterations; // Cluster solver iterations
int m_collisionFlags; // Collisions flags
};
struct SoftBodyPoseData
{
btMatrix3x3FloatData m_rot; // Rotation
btMatrix3x3FloatData m_scale; // Scale
btMatrix3x3FloatData m_aqq; // Base scaling
btVector3FloatData m_com; // COM
btVector3FloatData *m_positions; // Reference positions
float *m_weights; // Weights
int m_numPositions;
int m_numWeigts;
int m_bvolume; // Is valid
int m_bframe; // Is frame
float m_restVolume; // Rest volume
int m_pad;
};
struct SoftBodyClusterData
{
btTransformFloatData m_framexform;
btMatrix3x3FloatData m_locii;
btMatrix3x3FloatData m_invwi;
btVector3FloatData m_com;
btVector3FloatData m_vimpulses[2];
btVector3FloatData m_dimpulses[2];
btVector3FloatData m_lv;
btVector3FloatData m_av;
btVector3FloatData *m_framerefs;
int *m_nodeIndices;
float *m_masses;
int m_numFrameRefs;
int m_numNodes;
int m_numMasses;
float m_idmass;
float m_imass;
int m_nvimpulses;
int m_ndimpulses;
float m_ndamping;
float m_ldamping;
float m_adamping;
float m_matching;
float m_maxSelfCollisionImpulse;
float m_selfCollisionImpulseFactor;
int m_containsAnchor;
int m_collide;
int m_clusterIndex;
};
enum btSoftJointBodyType
{
BT_JOINT_SOFT_BODY_CLUSTER=1,
BT_JOINT_RIGID_BODY,
BT_JOINT_COLLISION_OBJECT
};
struct btSoftBodyJointData
{
void *m_bodyA;
void *m_bodyB;
btVector3FloatData m_refs[2];
float m_cfm;
float m_erp;
float m_split;
int m_delete;
btVector3FloatData m_relPosition[2];//linear
int m_bodyAtype;
int m_bodyBtype;
int m_jointType;
int m_pad;
};
///do not change those serialization structures, it requires an updated sBulletDNAstr/sBulletDNAstr64
struct btSoftBodyFloatData
{
btCollisionObjectFloatData m_collisionObjectData;
SoftBodyPoseData *m_pose;
SoftBodyMaterialData **m_materials;
SoftBodyNodeData *m_nodes;
SoftBodyLinkData *m_links;
SoftBodyFaceData *m_faces;
SoftBodyTetraData *m_tetrahedra;
SoftRigidAnchorData *m_anchors;
SoftBodyClusterData *m_clusters;
btSoftBodyJointData *m_joints;
int m_numMaterials;
int m_numNodes;
int m_numLinks;
int m_numFaces;
int m_numTetrahedra;
int m_numAnchors;
int m_numClusters;
int m_numJoints;
SoftBodyConfigData m_config;
};
#endif //BT_SOFTBODY_FLOAT_DATA

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,148 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2008 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_HELPERS_H
#define BT_SOFT_BODY_HELPERS_H
#include "btSoftBody.h"
//
// Helpers
//
/* fDrawFlags */
struct fDrawFlags { enum _ {
Nodes = 0x0001,
Links = 0x0002,
Faces = 0x0004,
Tetras = 0x0008,
Normals = 0x0010,
Contacts = 0x0020,
Anchors = 0x0040,
Notes = 0x0080,
Clusters = 0x0100,
NodeTree = 0x0200,
FaceTree = 0x0400,
ClusterTree = 0x0800,
Joints = 0x1000,
/* presets */
Std = Links+Faces+Tetras+Anchors+Notes+Joints,
StdTetra = Std-Faces+Tetras
};};
struct btSoftBodyHelpers
{
/* Draw body */
static void Draw( btSoftBody* psb,
btIDebugDraw* idraw,
int drawflags=fDrawFlags::Std);
/* Draw body infos */
static void DrawInfos( btSoftBody* psb,
btIDebugDraw* idraw,
bool masses,
bool areas,
bool stress);
/* Draw node tree */
static void DrawNodeTree( btSoftBody* psb,
btIDebugDraw* idraw,
int mindepth=0,
int maxdepth=-1);
/* Draw face tree */
static void DrawFaceTree( btSoftBody* psb,
btIDebugDraw* idraw,
int mindepth=0,
int maxdepth=-1);
/* Draw cluster tree */
static void DrawClusterTree(btSoftBody* psb,
btIDebugDraw* idraw,
int mindepth=0,
int maxdepth=-1);
/* Draw rigid frame */
static void DrawFrame( btSoftBody* psb,
btIDebugDraw* idraw);
/* Create a rope */
static btSoftBody* CreateRope( btSoftBodyWorldInfo& worldInfo,
const btVector3& from,
const btVector3& to,
int res,
int fixeds);
/* Create a patch */
static btSoftBody* CreatePatch(btSoftBodyWorldInfo& worldInfo,
const btVector3& corner00,
const btVector3& corner10,
const btVector3& corner01,
const btVector3& corner11,
int resx,
int resy,
int fixeds,
bool gendiags);
/* Create a patch with UV Texture Coordinates */
static btSoftBody* CreatePatchUV(btSoftBodyWorldInfo& worldInfo,
const btVector3& corner00,
const btVector3& corner10,
const btVector3& corner01,
const btVector3& corner11,
int resx,
int resy,
int fixeds,
bool gendiags,
float* tex_coords=0);
static float CalculateUV(int resx,int resy,int ix,int iy,int id);
/* Create an ellipsoid */
static btSoftBody* CreateEllipsoid(btSoftBodyWorldInfo& worldInfo,
const btVector3& center,
const btVector3& radius,
int res);
/* Create from trimesh */
static btSoftBody* CreateFromTriMesh( btSoftBodyWorldInfo& worldInfo,
const btScalar* vertices,
const int* triangles,
int ntriangles,
bool randomizeConstraints = true);
/* Create from convex-hull */
static btSoftBody* CreateFromConvexHull( btSoftBodyWorldInfo& worldInfo,
const btVector3* vertices,
int nvertices,
bool randomizeConstraints = true);
/* Export TetGen compatible .smesh file */
// static void ExportAsSMeshFile( btSoftBody* psb,
// const char* filename);
/* Create from TetGen .ele, .face, .node files */
// static btSoftBody* CreateFromTetGenFile( btSoftBodyWorldInfo& worldInfo,
// const char* ele,
// const char* face,
// const char* node,
// bool bfacelinks,
// bool btetralinks,
// bool bfacesfromtetras);
/* Create from TetGen .ele, .face, .node data */
static btSoftBody* CreateFromTetGenData( btSoftBodyWorldInfo& worldInfo,
const char* ele,
const char* face,
const char* node,
bool bfacelinks,
bool btetralinks,
bool bfacesfromtetras);
/// Sort the list of links to move link calculations that are dependent upon earlier
/// ones as far as possible away from the calculation of those values
/// This tends to make adjacent loop iterations not dependent upon one another,
/// so out-of-order processors can execute instructions from multiple iterations at once
static void ReoptimizeLinkOrder(btSoftBody *psb );
};
#endif //BT_SOFT_BODY_HELPERS_H

View File

@ -0,0 +1,911 @@
/*
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.
*/
///btSoftBody implementation by Nathanael Presson
#ifndef _BT_SOFT_BODY_INTERNALS_H
#define _BT_SOFT_BODY_INTERNALS_H
#include "btSoftBody.h"
#include "LinearMath/btQuickprof.h"
#include "LinearMath/btPolarDecomposition.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btConvexInternalShape.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include <string.h> //for memset
//
// btSymMatrix
//
template <typename T>
struct btSymMatrix
{
btSymMatrix() : dim(0) {}
btSymMatrix(int n,const T& init=T()) { resize(n,init); }
void resize(int n,const T& init=T()) { dim=n;store.resize((n*(n+1))/2,init); }
int index(int c,int r) const { if(c>r) btSwap(c,r);btAssert(r<dim);return((r*(r+1))/2+c); }
T& operator()(int c,int r) { return(store[index(c,r)]); }
const T& operator()(int c,int r) const { return(store[index(c,r)]); }
btAlignedObjectArray<T> store;
int dim;
};
//
// btSoftBodyCollisionShape
//
class btSoftBodyCollisionShape : public btConcaveShape
{
public:
btSoftBody* m_body;
btSoftBodyCollisionShape(btSoftBody* backptr)
{
m_shapeType = SOFTBODY_SHAPE_PROXYTYPE;
m_body=backptr;
}
virtual ~btSoftBodyCollisionShape()
{
}
void processAllTriangles(btTriangleCallback* /*callback*/,const btVector3& /*aabbMin*/,const btVector3& /*aabbMax*/) const
{
//not yet
btAssert(0);
}
///getAabb returns the axis aligned bounding box in the coordinate frame of the given transform t.
virtual void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const
{
/* t is usually identity, except when colliding against btCompoundShape. See Issue 512 */
const btVector3 mins=m_body->m_bounds[0];
const btVector3 maxs=m_body->m_bounds[1];
const btVector3 crns[]={t*btVector3(mins.x(),mins.y(),mins.z()),
t*btVector3(maxs.x(),mins.y(),mins.z()),
t*btVector3(maxs.x(),maxs.y(),mins.z()),
t*btVector3(mins.x(),maxs.y(),mins.z()),
t*btVector3(mins.x(),mins.y(),maxs.z()),
t*btVector3(maxs.x(),mins.y(),maxs.z()),
t*btVector3(maxs.x(),maxs.y(),maxs.z()),
t*btVector3(mins.x(),maxs.y(),maxs.z())};
aabbMin=aabbMax=crns[0];
for(int i=1;i<8;++i)
{
aabbMin.setMin(crns[i]);
aabbMax.setMax(crns[i]);
}
}
virtual void setLocalScaling(const btVector3& /*scaling*/)
{
///na
}
virtual const btVector3& getLocalScaling() const
{
static const btVector3 dummy(1,1,1);
return dummy;
}
virtual void calculateLocalInertia(btScalar /*mass*/,btVector3& /*inertia*/) const
{
///not yet
btAssert(0);
}
virtual const char* getName()const
{
return "SoftBody";
}
};
//
// btSoftClusterCollisionShape
//
class btSoftClusterCollisionShape : public btConvexInternalShape
{
public:
const btSoftBody::Cluster* m_cluster;
btSoftClusterCollisionShape (const btSoftBody::Cluster* cluster) : m_cluster(cluster) { setMargin(0); }
virtual btVector3 localGetSupportingVertex(const btVector3& vec) const
{
btSoftBody::Node* const * n=&m_cluster->m_nodes[0];
btScalar d=btDot(vec,n[0]->m_x);
int j=0;
for(int i=1,ni=m_cluster->m_nodes.size();i<ni;++i)
{
const btScalar k=btDot(vec,n[i]->m_x);
if(k>d) { d=k;j=i; }
}
return(n[j]->m_x);
}
virtual btVector3 localGetSupportingVertexWithoutMargin(const btVector3& vec)const
{
return(localGetSupportingVertex(vec));
}
//notice that the vectors should be unit length
virtual void batchedUnitVectorGetSupportingVertexWithoutMargin(const btVector3* vectors,btVector3* supportVerticesOut,int numVectors) const
{}
virtual void calculateLocalInertia(btScalar mass,btVector3& inertia) const
{}
virtual void getAabb(const btTransform& t,btVector3& aabbMin,btVector3& aabbMax) const
{}
virtual int getShapeType() const { return SOFTBODY_SHAPE_PROXYTYPE; }
//debugging
virtual const char* getName()const {return "SOFTCLUSTER";}
virtual void setMargin(btScalar margin)
{
btConvexInternalShape::setMargin(margin);
}
virtual btScalar getMargin() const
{
return btConvexInternalShape::getMargin();
}
};
//
// Inline's
//
//
template <typename T>
static inline void ZeroInitialize(T& value)
{
memset(&value,0,sizeof(T));
}
//
template <typename T>
static inline bool CompLess(const T& a,const T& b)
{ return(a<b); }
//
template <typename T>
static inline bool CompGreater(const T& a,const T& b)
{ return(a>b); }
//
template <typename T>
static inline T Lerp(const T& a,const T& b,btScalar t)
{ return(a+(b-a)*t); }
//
template <typename T>
static inline T InvLerp(const T& a,const T& b,btScalar t)
{ return((b+a*t-b*t)/(a*b)); }
//
static inline btMatrix3x3 Lerp( const btMatrix3x3& a,
const btMatrix3x3& b,
btScalar t)
{
btMatrix3x3 r;
r[0]=Lerp(a[0],b[0],t);
r[1]=Lerp(a[1],b[1],t);
r[2]=Lerp(a[2],b[2],t);
return(r);
}
//
static inline btVector3 Clamp(const btVector3& v,btScalar maxlength)
{
const btScalar sql=v.length2();
if(sql>(maxlength*maxlength))
return((v*maxlength)/btSqrt(sql));
else
return(v);
}
//
template <typename T>
static inline T Clamp(const T& x,const T& l,const T& h)
{ return(x<l?l:x>h?h:x); }
//
template <typename T>
static inline T Sq(const T& x)
{ return(x*x); }
//
template <typename T>
static inline T Cube(const T& x)
{ return(x*x*x); }
//
template <typename T>
static inline T Sign(const T& x)
{ return((T)(x<0?-1:+1)); }
//
template <typename T>
static inline bool SameSign(const T& x,const T& y)
{ return((x*y)>0); }
//
static inline btScalar ClusterMetric(const btVector3& x,const btVector3& y)
{
const btVector3 d=x-y;
return(btFabs(d[0])+btFabs(d[1])+btFabs(d[2]));
}
//
static inline btMatrix3x3 ScaleAlongAxis(const btVector3& a,btScalar s)
{
const btScalar xx=a.x()*a.x();
const btScalar yy=a.y()*a.y();
const btScalar zz=a.z()*a.z();
const btScalar xy=a.x()*a.y();
const btScalar yz=a.y()*a.z();
const btScalar zx=a.z()*a.x();
btMatrix3x3 m;
m[0]=btVector3(1-xx+xx*s,xy*s-xy,zx*s-zx);
m[1]=btVector3(xy*s-xy,1-yy+yy*s,yz*s-yz);
m[2]=btVector3(zx*s-zx,yz*s-yz,1-zz+zz*s);
return(m);
}
//
static inline btMatrix3x3 Cross(const btVector3& v)
{
btMatrix3x3 m;
m[0]=btVector3(0,-v.z(),+v.y());
m[1]=btVector3(+v.z(),0,-v.x());
m[2]=btVector3(-v.y(),+v.x(),0);
return(m);
}
//
static inline btMatrix3x3 Diagonal(btScalar x)
{
btMatrix3x3 m;
m[0]=btVector3(x,0,0);
m[1]=btVector3(0,x,0);
m[2]=btVector3(0,0,x);
return(m);
}
//
static inline btMatrix3x3 Add(const btMatrix3x3& a,
const btMatrix3x3& b)
{
btMatrix3x3 r;
for(int i=0;i<3;++i) r[i]=a[i]+b[i];
return(r);
}
//
static inline btMatrix3x3 Sub(const btMatrix3x3& a,
const btMatrix3x3& b)
{
btMatrix3x3 r;
for(int i=0;i<3;++i) r[i]=a[i]-b[i];
return(r);
}
//
static inline btMatrix3x3 Mul(const btMatrix3x3& a,
btScalar b)
{
btMatrix3x3 r;
for(int i=0;i<3;++i) r[i]=a[i]*b;
return(r);
}
//
static inline void Orthogonalize(btMatrix3x3& m)
{
m[2]=btCross(m[0],m[1]).normalized();
m[1]=btCross(m[2],m[0]).normalized();
m[0]=btCross(m[1],m[2]).normalized();
}
//
static inline btMatrix3x3 MassMatrix(btScalar im,const btMatrix3x3& iwi,const btVector3& r)
{
const btMatrix3x3 cr=Cross(r);
return(Sub(Diagonal(im),cr*iwi*cr));
}
//
static inline btMatrix3x3 ImpulseMatrix( btScalar dt,
btScalar ima,
btScalar imb,
const btMatrix3x3& iwi,
const btVector3& r)
{
return(Diagonal(1/dt)*Add(Diagonal(ima),MassMatrix(imb,iwi,r)).inverse());
}
//
static inline btMatrix3x3 ImpulseMatrix( btScalar ima,const btMatrix3x3& iia,const btVector3& ra,
btScalar imb,const btMatrix3x3& iib,const btVector3& rb)
{
return(Add(MassMatrix(ima,iia,ra),MassMatrix(imb,iib,rb)).inverse());
}
//
static inline btMatrix3x3 AngularImpulseMatrix( const btMatrix3x3& iia,
const btMatrix3x3& iib)
{
return(Add(iia,iib).inverse());
}
//
static inline btVector3 ProjectOnAxis( const btVector3& v,
const btVector3& a)
{
return(a*btDot(v,a));
}
//
static inline btVector3 ProjectOnPlane( const btVector3& v,
const btVector3& a)
{
return(v-ProjectOnAxis(v,a));
}
//
static inline void ProjectOrigin( const btVector3& a,
const btVector3& b,
btVector3& prj,
btScalar& sqd)
{
const btVector3 d=b-a;
const btScalar m2=d.length2();
if(m2>SIMD_EPSILON)
{
const btScalar t=Clamp<btScalar>(-btDot(a,d)/m2,0,1);
const btVector3 p=a+d*t;
const btScalar l2=p.length2();
if(l2<sqd)
{
prj=p;
sqd=l2;
}
}
}
//
static inline void ProjectOrigin( const btVector3& a,
const btVector3& b,
const btVector3& c,
btVector3& prj,
btScalar& sqd)
{
const btVector3& q=btCross(b-a,c-a);
const btScalar m2=q.length2();
if(m2>SIMD_EPSILON)
{
const btVector3 n=q/btSqrt(m2);
const btScalar k=btDot(a,n);
const btScalar k2=k*k;
if(k2<sqd)
{
const btVector3 p=n*k;
if( (btDot(btCross(a-p,b-p),q)>0)&&
(btDot(btCross(b-p,c-p),q)>0)&&
(btDot(btCross(c-p,a-p),q)>0))
{
prj=p;
sqd=k2;
}
else
{
ProjectOrigin(a,b,prj,sqd);
ProjectOrigin(b,c,prj,sqd);
ProjectOrigin(c,a,prj,sqd);
}
}
}
}
//
template <typename T>
static inline T BaryEval( const T& a,
const T& b,
const T& c,
const btVector3& coord)
{
return(a*coord.x()+b*coord.y()+c*coord.z());
}
//
static inline btVector3 BaryCoord( const btVector3& a,
const btVector3& b,
const btVector3& c,
const btVector3& p)
{
const btScalar w[]={ btCross(a-p,b-p).length(),
btCross(b-p,c-p).length(),
btCross(c-p,a-p).length()};
const btScalar isum=1/(w[0]+w[1]+w[2]);
return(btVector3(w[1]*isum,w[2]*isum,w[0]*isum));
}
//
inline static btScalar ImplicitSolve( btSoftBody::ImplicitFn* fn,
const btVector3& a,
const btVector3& b,
const btScalar accuracy,
const int maxiterations=256)
{
btScalar span[2]={0,1};
btScalar values[2]={fn->Eval(a),fn->Eval(b)};
if(values[0]>values[1])
{
btSwap(span[0],span[1]);
btSwap(values[0],values[1]);
}
if(values[0]>-accuracy) return(-1);
if(values[1]<+accuracy) return(-1);
for(int i=0;i<maxiterations;++i)
{
const btScalar t=Lerp(span[0],span[1],values[0]/(values[0]-values[1]));
const btScalar v=fn->Eval(Lerp(a,b,t));
if((t<=0)||(t>=1)) break;
if(btFabs(v)<accuracy) return(t);
if(v<0)
{ span[0]=t;values[0]=v; }
else
{ span[1]=t;values[1]=v; }
}
return(-1);
}
inline static void EvaluateMedium( const btSoftBodyWorldInfo* wfi,
const btVector3& x,
btSoftBody::sMedium& medium)
{
medium.m_velocity = btVector3(0,0,0);
medium.m_pressure = 0;
medium.m_density = wfi->air_density;
if(wfi->water_density>0)
{
const btScalar depth=-(btDot(x,wfi->water_normal)+wfi->water_offset);
if(depth>0)
{
medium.m_density = wfi->water_density;
medium.m_pressure = depth*wfi->water_density*wfi->m_gravity.length();
}
}
}
//
static inline btVector3 NormalizeAny(const btVector3& v)
{
const btScalar l=v.length();
if(l>SIMD_EPSILON)
return(v/l);
else
return(btVector3(0,0,0));
}
//
static inline btDbvtVolume VolumeOf( const btSoftBody::Face& f,
btScalar margin)
{
const btVector3* pts[]={ &f.m_n[0]->m_x,
&f.m_n[1]->m_x,
&f.m_n[2]->m_x};
btDbvtVolume vol=btDbvtVolume::FromPoints(pts,3);
vol.Expand(btVector3(margin,margin,margin));
return(vol);
}
//
static inline btVector3 CenterOf( const btSoftBody::Face& f)
{
return((f.m_n[0]->m_x+f.m_n[1]->m_x+f.m_n[2]->m_x)/3);
}
//
static inline btScalar AreaOf( const btVector3& x0,
const btVector3& x1,
const btVector3& x2)
{
const btVector3 a=x1-x0;
const btVector3 b=x2-x0;
const btVector3 cr=btCross(a,b);
const btScalar area=cr.length();
return(area);
}
//
static inline btScalar VolumeOf( const btVector3& x0,
const btVector3& x1,
const btVector3& x2,
const btVector3& x3)
{
const btVector3 a=x1-x0;
const btVector3 b=x2-x0;
const btVector3 c=x3-x0;
return(btDot(a,btCross(b,c)));
}
//
//
static inline void ApplyClampedForce( btSoftBody::Node& n,
const btVector3& f,
btScalar dt)
{
const btScalar dtim=dt*n.m_im;
if((f*dtim).length2()>n.m_v.length2())
{/* Clamp */
n.m_f-=ProjectOnAxis(n.m_v,f.normalized())/dtim;
}
else
{/* Apply */
n.m_f+=f;
}
}
//
static inline int MatchEdge( const btSoftBody::Node* a,
const btSoftBody::Node* b,
const btSoftBody::Node* ma,
const btSoftBody::Node* mb)
{
if((a==ma)&&(b==mb)) return(0);
if((a==mb)&&(b==ma)) return(1);
return(-1);
}
//
// btEigen : Extract eigen system,
// straitforward implementation of http://math.fullerton.edu/mathews/n2003/JacobiMethodMod.html
// outputs are NOT sorted.
//
struct btEigen
{
static int system(btMatrix3x3& a,btMatrix3x3* vectors,btVector3* values=0)
{
static const int maxiterations=16;
static const btScalar accuracy=(btScalar)0.0001;
btMatrix3x3& v=*vectors;
int iterations=0;
vectors->setIdentity();
do {
int p=0,q=1;
if(btFabs(a[p][q])<btFabs(a[0][2])) { p=0;q=2; }
if(btFabs(a[p][q])<btFabs(a[1][2])) { p=1;q=2; }
if(btFabs(a[p][q])>accuracy)
{
const btScalar w=(a[q][q]-a[p][p])/(2*a[p][q]);
const btScalar z=btFabs(w);
const btScalar t=w/(z*(btSqrt(1+w*w)+z));
if(t==t)/* [WARNING] let hope that one does not get thrown aways by some compilers... */
{
const btScalar c=1/btSqrt(t*t+1);
const btScalar s=c*t;
mulPQ(a,c,s,p,q);
mulTPQ(a,c,s,p,q);
mulPQ(v,c,s,p,q);
} else break;
} else break;
} while((++iterations)<maxiterations);
if(values)
{
*values=btVector3(a[0][0],a[1][1],a[2][2]);
}
return(iterations);
}
private:
static inline void mulTPQ(btMatrix3x3& a,btScalar c,btScalar s,int p,int q)
{
const btScalar m[2][3]={ {a[p][0],a[p][1],a[p][2]},
{a[q][0],a[q][1],a[q][2]}};
int i;
for(i=0;i<3;++i) a[p][i]=c*m[0][i]-s*m[1][i];
for(i=0;i<3;++i) a[q][i]=c*m[1][i]+s*m[0][i];
}
static inline void mulPQ(btMatrix3x3& a,btScalar c,btScalar s,int p,int q)
{
const btScalar m[2][3]={ {a[0][p],a[1][p],a[2][p]},
{a[0][q],a[1][q],a[2][q]}};
int i;
for(i=0;i<3;++i) a[i][p]=c*m[0][i]-s*m[1][i];
for(i=0;i<3;++i) a[i][q]=c*m[1][i]+s*m[0][i];
}
};
//
// Polar decomposition,
// "Computing the Polar Decomposition with Applications", Nicholas J. Higham, 1986.
//
static inline int PolarDecompose( const btMatrix3x3& m,btMatrix3x3& q,btMatrix3x3& s)
{
static const btPolarDecomposition polar;
return polar.decompose(m, q, s);
}
//
// btSoftColliders
//
struct btSoftColliders
{
//
// ClusterBase
//
struct ClusterBase : btDbvt::ICollide
{
btScalar erp;
btScalar idt;
btScalar m_margin;
btScalar friction;
btScalar threshold;
ClusterBase()
{
erp =(btScalar)1;
idt =0;
m_margin =0;
friction =0;
threshold =(btScalar)0;
}
bool SolveContact( const btGjkEpaSolver2::sResults& res,
btSoftBody::Body ba,const btSoftBody::Body bb,
btSoftBody::CJoint& joint)
{
if(res.distance<m_margin)
{
btVector3 norm = res.normal;
norm.normalize();//is it necessary?
const btVector3 ra=res.witnesses[0]-ba.xform().getOrigin();
const btVector3 rb=res.witnesses[1]-bb.xform().getOrigin();
const btVector3 va=ba.velocity(ra);
const btVector3 vb=bb.velocity(rb);
const btVector3 vrel=va-vb;
const btScalar rvac=btDot(vrel,norm);
btScalar depth=res.distance-m_margin;
// printf("depth=%f\n",depth);
const btVector3 iv=norm*rvac;
const btVector3 fv=vrel-iv;
joint.m_bodies[0] = ba;
joint.m_bodies[1] = bb;
joint.m_refs[0] = ra*ba.xform().getBasis();
joint.m_refs[1] = rb*bb.xform().getBasis();
joint.m_rpos[0] = ra;
joint.m_rpos[1] = rb;
joint.m_cfm = 1;
joint.m_erp = 1;
joint.m_life = 0;
joint.m_maxlife = 0;
joint.m_split = 1;
joint.m_drift = depth*norm;
joint.m_normal = norm;
// printf("normal=%f,%f,%f\n",res.normal.getX(),res.normal.getY(),res.normal.getZ());
joint.m_delete = false;
joint.m_friction = fv.length2()<(rvac*friction*rvac*friction)?1:friction;
joint.m_massmatrix = ImpulseMatrix( ba.invMass(),ba.invWorldInertia(),joint.m_rpos[0],
bb.invMass(),bb.invWorldInertia(),joint.m_rpos[1]);
return(true);
}
return(false);
}
};
//
// CollideCL_RS
//
struct CollideCL_RS : ClusterBase
{
btSoftBody* psb;
const btCollisionObjectWrapper* m_colObjWrap;
void Process(const btDbvtNode* leaf)
{
btSoftBody::Cluster* cluster=(btSoftBody::Cluster*)leaf->data;
btSoftClusterCollisionShape cshape(cluster);
const btConvexShape* rshape=(const btConvexShape*)m_colObjWrap->getCollisionShape();
///don't collide an anchored cluster with a static/kinematic object
if(m_colObjWrap->getCollisionObject()->isStaticOrKinematicObject() && cluster->m_containsAnchor)
return;
btGjkEpaSolver2::sResults res;
if(btGjkEpaSolver2::SignedDistance( &cshape,btTransform::getIdentity(),
rshape,m_colObjWrap->getWorldTransform(),
btVector3(1,0,0),res))
{
btSoftBody::CJoint joint;
if(SolveContact(res,cluster,m_colObjWrap->getCollisionObject(),joint))//prb,joint))
{
btSoftBody::CJoint* pj=new(btAlignedAlloc(sizeof(btSoftBody::CJoint),16)) btSoftBody::CJoint();
*pj=joint;psb->m_joints.push_back(pj);
if(m_colObjWrap->getCollisionObject()->isStaticOrKinematicObject())
{
pj->m_erp *= psb->m_cfg.kSKHR_CL;
pj->m_split *= psb->m_cfg.kSK_SPLT_CL;
}
else
{
pj->m_erp *= psb->m_cfg.kSRHR_CL;
pj->m_split *= psb->m_cfg.kSR_SPLT_CL;
}
}
}
}
void ProcessColObj(btSoftBody* ps,const btCollisionObjectWrapper* colObWrap)
{
psb = ps;
m_colObjWrap = colObWrap;
idt = ps->m_sst.isdt;
m_margin = m_colObjWrap->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin();
///Bullet rigid body uses multiply instead of minimum to determine combined friction. Some customization would be useful.
friction = btMin(psb->m_cfg.kDF,m_colObjWrap->getCollisionObject()->getFriction());
btVector3 mins;
btVector3 maxs;
ATTRIBUTE_ALIGNED16(btDbvtVolume) volume;
colObWrap->getCollisionShape()->getAabb(colObWrap->getWorldTransform(),mins,maxs);
volume=btDbvtVolume::FromMM(mins,maxs);
volume.Expand(btVector3(1,1,1)*m_margin);
ps->m_cdbvt.collideTV(ps->m_cdbvt.m_root,volume,*this);
}
};
//
// CollideCL_SS
//
struct CollideCL_SS : ClusterBase
{
btSoftBody* bodies[2];
void Process(const btDbvtNode* la,const btDbvtNode* lb)
{
btSoftBody::Cluster* cla=(btSoftBody::Cluster*)la->data;
btSoftBody::Cluster* clb=(btSoftBody::Cluster*)lb->data;
bool connected=false;
if ((bodies[0]==bodies[1])&&(bodies[0]->m_clusterConnectivity.size()))
{
connected = bodies[0]->m_clusterConnectivity[cla->m_clusterIndex+bodies[0]->m_clusters.size()*clb->m_clusterIndex];
}
if (!connected)
{
btSoftClusterCollisionShape csa(cla);
btSoftClusterCollisionShape csb(clb);
btGjkEpaSolver2::sResults res;
if(btGjkEpaSolver2::SignedDistance( &csa,btTransform::getIdentity(),
&csb,btTransform::getIdentity(),
cla->m_com-clb->m_com,res))
{
btSoftBody::CJoint joint;
if(SolveContact(res,cla,clb,joint))
{
btSoftBody::CJoint* pj=new(btAlignedAlloc(sizeof(btSoftBody::CJoint),16)) btSoftBody::CJoint();
*pj=joint;bodies[0]->m_joints.push_back(pj);
pj->m_erp *= btMax(bodies[0]->m_cfg.kSSHR_CL,bodies[1]->m_cfg.kSSHR_CL);
pj->m_split *= (bodies[0]->m_cfg.kSS_SPLT_CL+bodies[1]->m_cfg.kSS_SPLT_CL)/2;
}
}
} else
{
static int count=0;
count++;
//printf("count=%d\n",count);
}
}
void ProcessSoftSoft(btSoftBody* psa,btSoftBody* psb)
{
idt = psa->m_sst.isdt;
//m_margin = (psa->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin())/2;
m_margin = (psa->getCollisionShape()->getMargin()+psb->getCollisionShape()->getMargin());
friction = btMin(psa->m_cfg.kDF,psb->m_cfg.kDF);
bodies[0] = psa;
bodies[1] = psb;
psa->m_cdbvt.collideTT(psa->m_cdbvt.m_root,psb->m_cdbvt.m_root,*this);
}
};
//
// CollideSDF_RS
//
struct CollideSDF_RS : btDbvt::ICollide
{
void Process(const btDbvtNode* leaf)
{
btSoftBody::Node* node=(btSoftBody::Node*)leaf->data;
DoNode(*node);
}
void DoNode(btSoftBody::Node& n) const
{
const btScalar m=n.m_im>0?dynmargin:stamargin;
btSoftBody::RContact c;
if( (!n.m_battach)&&
psb->checkContact(m_colObj1Wrap,n.m_x,m,c.m_cti))
{
const btScalar ima=n.m_im;
const btScalar imb= m_rigidBody? m_rigidBody->getInvMass() : 0.f;
const btScalar ms=ima+imb;
if(ms>0)
{
const btTransform& wtr=m_rigidBody?m_rigidBody->getWorldTransform() : m_colObj1Wrap->getCollisionObject()->getWorldTransform();
static const btMatrix3x3 iwiStatic(0,0,0,0,0,0,0,0,0);
const btMatrix3x3& iwi=m_rigidBody?m_rigidBody->getInvInertiaTensorWorld() : iwiStatic;
const btVector3 ra=n.m_x-wtr.getOrigin();
const btVector3 va=m_rigidBody ? m_rigidBody->getVelocityInLocalPoint(ra)*psb->m_sst.sdt : btVector3(0,0,0);
const btVector3 vb=n.m_x-n.m_q;
const btVector3 vr=vb-va;
const btScalar dn=btDot(vr,c.m_cti.m_normal);
const btVector3 fv=vr-c.m_cti.m_normal*dn;
const btScalar fc=psb->m_cfg.kDF*m_colObj1Wrap->getCollisionObject()->getFriction();
c.m_node = &n;
c.m_c0 = ImpulseMatrix(psb->m_sst.sdt,ima,imb,iwi,ra);
c.m_c1 = ra;
c.m_c2 = ima*psb->m_sst.sdt;
c.m_c3 = fv.length2()<(dn*fc*dn*fc)?0:1-fc;
c.m_c4 = m_colObj1Wrap->getCollisionObject()->isStaticOrKinematicObject()?psb->m_cfg.kKHR:psb->m_cfg.kCHR;
psb->m_rcontacts.push_back(c);
if (m_rigidBody)
m_rigidBody->activate();
}
}
}
btSoftBody* psb;
const btCollisionObjectWrapper* m_colObj1Wrap;
btRigidBody* m_rigidBody;
btScalar dynmargin;
btScalar stamargin;
};
//
// CollideVF_SS
//
struct CollideVF_SS : btDbvt::ICollide
{
void Process(const btDbvtNode* lnode,
const btDbvtNode* lface)
{
btSoftBody::Node* node=(btSoftBody::Node*)lnode->data;
btSoftBody::Face* face=(btSoftBody::Face*)lface->data;
btVector3 o=node->m_x;
btVector3 p;
btScalar d=SIMD_INFINITY;
ProjectOrigin( face->m_n[0]->m_x-o,
face->m_n[1]->m_x-o,
face->m_n[2]->m_x-o,
p,d);
const btScalar m=mrg+(o-node->m_q).length()*2;
if(d<(m*m))
{
const btSoftBody::Node* n[]={face->m_n[0],face->m_n[1],face->m_n[2]};
const btVector3 w=BaryCoord(n[0]->m_x,n[1]->m_x,n[2]->m_x,p+o);
const btScalar ma=node->m_im;
btScalar mb=BaryEval(n[0]->m_im,n[1]->m_im,n[2]->m_im,w);
if( (n[0]->m_im<=0)||
(n[1]->m_im<=0)||
(n[2]->m_im<=0))
{
mb=0;
}
const btScalar ms=ma+mb;
if(ms>0)
{
btSoftBody::SContact c;
c.m_normal = p/-btSqrt(d);
c.m_margin = m;
c.m_node = node;
c.m_face = face;
c.m_weights = w;
c.m_friction = btMax(psb[0]->m_cfg.kDF,psb[1]->m_cfg.kDF);
c.m_cfm[0] = ma/ms*psb[0]->m_cfg.kSHR;
c.m_cfm[1] = mb/ms*psb[1]->m_cfg.kSHR;
psb[0]->m_scontacts.push_back(c);
}
}
}
btSoftBody* psb[2];
btScalar mrg;
};
};
#endif //_BT_SOFT_BODY_INTERNALS_H

View File

@ -0,0 +1,134 @@
/*
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.
*/
#include "btSoftBodyRigidBodyCollisionConfiguration.h"
#include "btSoftRigidCollisionAlgorithm.h"
#include "btSoftBodyConcaveCollisionAlgorithm.h"
#include "btSoftSoftCollisionAlgorithm.h"
#include "LinearMath/btPoolAllocator.h"
#define ENABLE_SOFTBODY_CONCAVE_COLLISIONS 1
btSoftBodyRigidBodyCollisionConfiguration::btSoftBodyRigidBodyCollisionConfiguration(const btDefaultCollisionConstructionInfo& constructionInfo)
:btDefaultCollisionConfiguration(constructionInfo)
{
void* mem;
mem = btAlignedAlloc(sizeof(btSoftSoftCollisionAlgorithm::CreateFunc),16);
m_softSoftCreateFunc = new(mem) btSoftSoftCollisionAlgorithm::CreateFunc;
mem = btAlignedAlloc(sizeof(btSoftRigidCollisionAlgorithm::CreateFunc),16);
m_softRigidConvexCreateFunc = new(mem) btSoftRigidCollisionAlgorithm::CreateFunc;
mem = btAlignedAlloc(sizeof(btSoftRigidCollisionAlgorithm::CreateFunc),16);
m_swappedSoftRigidConvexCreateFunc = new(mem) btSoftRigidCollisionAlgorithm::CreateFunc;
m_swappedSoftRigidConvexCreateFunc->m_swapped=true;
#ifdef ENABLE_SOFTBODY_CONCAVE_COLLISIONS
mem = btAlignedAlloc(sizeof(btSoftBodyConcaveCollisionAlgorithm::CreateFunc),16);
m_softRigidConcaveCreateFunc = new(mem) btSoftBodyConcaveCollisionAlgorithm::CreateFunc;
mem = btAlignedAlloc(sizeof(btSoftBodyConcaveCollisionAlgorithm::CreateFunc),16);
m_swappedSoftRigidConcaveCreateFunc = new(mem) btSoftBodyConcaveCollisionAlgorithm::SwappedCreateFunc;
m_swappedSoftRigidConcaveCreateFunc->m_swapped=true;
#endif
//replace pool by a new one, with potential larger size
if (m_ownsCollisionAlgorithmPool && m_collisionAlgorithmPool)
{
int curElemSize = m_collisionAlgorithmPool->getElementSize();
///calculate maximum element size, big enough to fit any collision algorithm in the memory pool
int maxSize0 = sizeof(btSoftSoftCollisionAlgorithm);
int maxSize1 = sizeof(btSoftRigidCollisionAlgorithm);
int maxSize2 = sizeof(btSoftBodyConcaveCollisionAlgorithm);
int collisionAlgorithmMaxElementSize = btMax(maxSize0,maxSize1);
collisionAlgorithmMaxElementSize = btMax(collisionAlgorithmMaxElementSize,maxSize2);
if (collisionAlgorithmMaxElementSize > curElemSize)
{
m_collisionAlgorithmPool->~btPoolAllocator();
btAlignedFree(m_collisionAlgorithmPool);
void* mem = btAlignedAlloc(sizeof(btPoolAllocator),16);
m_collisionAlgorithmPool = new(mem) btPoolAllocator(collisionAlgorithmMaxElementSize,constructionInfo.m_defaultMaxCollisionAlgorithmPoolSize);
}
}
}
btSoftBodyRigidBodyCollisionConfiguration::~btSoftBodyRigidBodyCollisionConfiguration()
{
m_softSoftCreateFunc->~btCollisionAlgorithmCreateFunc();
btAlignedFree( m_softSoftCreateFunc);
m_softRigidConvexCreateFunc->~btCollisionAlgorithmCreateFunc();
btAlignedFree( m_softRigidConvexCreateFunc);
m_swappedSoftRigidConvexCreateFunc->~btCollisionAlgorithmCreateFunc();
btAlignedFree( m_swappedSoftRigidConvexCreateFunc);
#ifdef ENABLE_SOFTBODY_CONCAVE_COLLISIONS
m_softRigidConcaveCreateFunc->~btCollisionAlgorithmCreateFunc();
btAlignedFree( m_softRigidConcaveCreateFunc);
m_swappedSoftRigidConcaveCreateFunc->~btCollisionAlgorithmCreateFunc();
btAlignedFree( m_swappedSoftRigidConcaveCreateFunc);
#endif
}
///creation of soft-soft and soft-rigid, and otherwise fallback to base class implementation
btCollisionAlgorithmCreateFunc* btSoftBodyRigidBodyCollisionConfiguration::getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1)
{
///try to handle the softbody interactions first
if ((proxyType0 == SOFTBODY_SHAPE_PROXYTYPE ) && (proxyType1==SOFTBODY_SHAPE_PROXYTYPE))
{
return m_softSoftCreateFunc;
}
///softbody versus convex
if (proxyType0 == SOFTBODY_SHAPE_PROXYTYPE && btBroadphaseProxy::isConvex(proxyType1))
{
return m_softRigidConvexCreateFunc;
}
///convex versus soft body
if (btBroadphaseProxy::isConvex(proxyType0) && proxyType1 == SOFTBODY_SHAPE_PROXYTYPE )
{
return m_swappedSoftRigidConvexCreateFunc;
}
#ifdef ENABLE_SOFTBODY_CONCAVE_COLLISIONS
///softbody versus convex
if (proxyType0 == SOFTBODY_SHAPE_PROXYTYPE && btBroadphaseProxy::isConcave(proxyType1))
{
return m_softRigidConcaveCreateFunc;
}
///convex versus soft body
if (btBroadphaseProxy::isConcave(proxyType0) && proxyType1 == SOFTBODY_SHAPE_PROXYTYPE )
{
return m_swappedSoftRigidConcaveCreateFunc;
}
#endif
///fallback to the regular rigid collision shape
return btDefaultCollisionConfiguration::getCollisionAlgorithmCreateFunc(proxyType0,proxyType1);
}

View File

@ -0,0 +1,48 @@
/*
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_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION
#define BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION
#include "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h"
class btVoronoiSimplexSolver;
class btGjkEpaPenetrationDepthSolver;
///btSoftBodyRigidBodyCollisionConfiguration add softbody interaction on top of btDefaultCollisionConfiguration
class btSoftBodyRigidBodyCollisionConfiguration : public btDefaultCollisionConfiguration
{
//default CreationFunctions, filling the m_doubleDispatch table
btCollisionAlgorithmCreateFunc* m_softSoftCreateFunc;
btCollisionAlgorithmCreateFunc* m_softRigidConvexCreateFunc;
btCollisionAlgorithmCreateFunc* m_swappedSoftRigidConvexCreateFunc;
btCollisionAlgorithmCreateFunc* m_softRigidConcaveCreateFunc;
btCollisionAlgorithmCreateFunc* m_swappedSoftRigidConcaveCreateFunc;
public:
btSoftBodyRigidBodyCollisionConfiguration(const btDefaultCollisionConstructionInfo& constructionInfo = btDefaultCollisionConstructionInfo());
virtual ~btSoftBodyRigidBodyCollisionConfiguration();
///creation of soft-soft and soft-rigid, and otherwise fallback to base class implementation
virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1);
};
#endif //BT_SOFTBODY_RIGIDBODY_COLLISION_CONFIGURATION

View File

@ -0,0 +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

View File

@ -0,0 +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
{
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(bool bMove = true) = 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 *, const struct btCollisionObjectWrapper* ) = 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

@ -0,0 +1,367 @@
/*
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.
*/
#include "btSoftMultiBodyDynamicsWorld.h"
#include "LinearMath/btQuickprof.h"
//softbody & helpers
#include "BulletSoftBody/btSoftBody.h"
#include "BulletSoftBody/btSoftBodyHelpers.h"
#include "BulletSoftBody/btSoftBodySolvers.h"
#include "BulletSoftBody/btDefaultSoftBodySolver.h"
#include "LinearMath/btSerializer.h"
btSoftMultiBodyDynamicsWorld::btSoftMultiBodyDynamicsWorld(
btDispatcher* dispatcher,
btBroadphaseInterface* pairCache,
btMultiBodyConstraintSolver* constraintSolver,
btCollisionConfiguration* collisionConfiguration,
btSoftBodySolver *softBodySolver ) :
btMultiBodyDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration),
m_softBodySolver( softBodySolver ),
m_ownsSolver(false)
{
if( !m_softBodySolver )
{
void* ptr = btAlignedAlloc(sizeof(btDefaultSoftBodySolver),16);
m_softBodySolver = new(ptr) btDefaultSoftBodySolver();
m_ownsSolver = true;
}
m_drawFlags = fDrawFlags::Std;
m_drawNodeTree = true;
m_drawFaceTree = false;
m_drawClusterTree = false;
m_sbi.m_broadphase = pairCache;
m_sbi.m_dispatcher = dispatcher;
m_sbi.m_sparsesdf.Initialize();
m_sbi.m_sparsesdf.Reset();
m_sbi.air_density = (btScalar)1.2;
m_sbi.water_density = 0;
m_sbi.water_offset = 0;
m_sbi.water_normal = btVector3(0,0,0);
m_sbi.m_gravity.setValue(0,-10,0);
m_sbi.m_sparsesdf.Initialize();
}
btSoftMultiBodyDynamicsWorld::~btSoftMultiBodyDynamicsWorld()
{
if (m_ownsSolver)
{
m_softBodySolver->~btSoftBodySolver();
btAlignedFree(m_softBodySolver);
}
}
void btSoftMultiBodyDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
{
btDiscreteDynamicsWorld::predictUnconstraintMotion( timeStep );
{
BT_PROFILE("predictUnconstraintMotionSoftBody");
m_softBodySolver->predictMotion( float(timeStep) );
}
}
void btSoftMultiBodyDynamicsWorld::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" );
}
btDiscreteDynamicsWorld::internalSingleStepSimulation( timeStep );
///solve soft bodies constraints
solveSoftBodiesConstraints( timeStep );
//self collisions
for ( int i=0;i<m_softBodies.size();i++)
{
btSoftBody* psb=(btSoftBody*)m_softBodies[i];
psb->defaultCollisionHandler(psb);
}
///update soft bodies
m_softBodySolver->updateSoftBodies( );
// End solver-wise simulation step
// ///////////////////////////////
}
void btSoftMultiBodyDynamicsWorld::solveSoftBodiesConstraints( btScalar timeStep )
{
BT_PROFILE("solveSoftConstraints");
if(m_softBodies.size())
{
btSoftBody::solveClusters(m_softBodies);
}
// Solve constraints solver-wise
m_softBodySolver->solveConstraints( timeStep * m_softBodySolver->getTimeScale() );
}
void btSoftMultiBodyDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask)
{
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);
}
void btSoftMultiBodyDynamicsWorld::removeSoftBody(btSoftBody* body)
{
m_softBodies.remove(body);
btCollisionWorld::removeCollisionObject(body);
}
void btSoftMultiBodyDynamicsWorld::removeCollisionObject(btCollisionObject* collisionObject)
{
btSoftBody* body = btSoftBody::upcast(collisionObject);
if (body)
removeSoftBody(body);
else
btDiscreteDynamicsWorld::removeCollisionObject(collisionObject);
}
void btSoftMultiBodyDynamicsWorld::debugDrawWorld()
{
btDiscreteDynamicsWorld::debugDrawWorld();
if (getDebugDrawer())
{
int i;
for ( i=0;i<this->m_softBodies.size();i++)
{
btSoftBody* psb=(btSoftBody*)this->m_softBodies[i];
if (getDebugDrawer() && (getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe)))
{
btSoftBodyHelpers::DrawFrame(psb,m_debugDrawer);
btSoftBodyHelpers::Draw(psb,m_debugDrawer,m_drawFlags);
}
if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb))
{
if(m_drawNodeTree) btSoftBodyHelpers::DrawNodeTree(psb,m_debugDrawer);
if(m_drawFaceTree) btSoftBodyHelpers::DrawFaceTree(psb,m_debugDrawer);
if(m_drawClusterTree) btSoftBodyHelpers::DrawClusterTree(psb,m_debugDrawer);
}
}
}
}
struct btSoftSingleRayCallback : public btBroadphaseRayCallback
{
btVector3 m_rayFromWorld;
btVector3 m_rayToWorld;
btTransform m_rayFromTrans;
btTransform m_rayToTrans;
btVector3 m_hitNormal;
const btSoftMultiBodyDynamicsWorld* m_world;
btCollisionWorld::RayResultCallback& m_resultCallback;
btSoftSingleRayCallback(const btVector3& rayFromWorld,const btVector3& rayToWorld,const btSoftMultiBodyDynamicsWorld* world,btCollisionWorld::RayResultCallback& resultCallback)
:m_rayFromWorld(rayFromWorld),
m_rayToWorld(rayToWorld),
m_world(world),
m_resultCallback(resultCallback)
{
m_rayFromTrans.setIdentity();
m_rayFromTrans.setOrigin(m_rayFromWorld);
m_rayToTrans.setIdentity();
m_rayToTrans.setOrigin(m_rayToWorld);
btVector3 rayDir = (rayToWorld-rayFromWorld);
rayDir.normalize ();
///what about division by zero? --> just set rayDirection[i] to INF/1e30
m_rayDirectionInverse[0] = rayDir[0] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[0];
m_rayDirectionInverse[1] = rayDir[1] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[1];
m_rayDirectionInverse[2] = rayDir[2] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[2];
m_signs[0] = m_rayDirectionInverse[0] < 0.0;
m_signs[1] = m_rayDirectionInverse[1] < 0.0;
m_signs[2] = m_rayDirectionInverse[2] < 0.0;
m_lambda_max = rayDir.dot(m_rayToWorld-m_rayFromWorld);
}
virtual bool process(const btBroadphaseProxy* proxy)
{
///terminate further ray tests, once the closestHitFraction reached zero
if (m_resultCallback.m_closestHitFraction == btScalar(0.f))
return false;
btCollisionObject* collisionObject = (btCollisionObject*)proxy->m_clientObject;
//only perform raycast if filterMask matches
if(m_resultCallback.needsCollision(collisionObject->getBroadphaseHandle()))
{
//RigidcollisionObject* collisionObject = ctrl->GetRigidcollisionObject();
//btVector3 collisionObjectAabbMin,collisionObjectAabbMax;
#if 0
#ifdef RECALCULATE_AABB
btVector3 collisionObjectAabbMin,collisionObjectAabbMax;
collisionObject->getCollisionShape()->getAabb(collisionObject->getWorldTransform(),collisionObjectAabbMin,collisionObjectAabbMax);
#else
//getBroadphase()->getAabb(collisionObject->getBroadphaseHandle(),collisionObjectAabbMin,collisionObjectAabbMax);
const btVector3& collisionObjectAabbMin = collisionObject->getBroadphaseHandle()->m_aabbMin;
const btVector3& collisionObjectAabbMax = collisionObject->getBroadphaseHandle()->m_aabbMax;
#endif
#endif
//btScalar hitLambda = m_resultCallback.m_closestHitFraction;
//culling already done by broadphase
//if (btRayAabb(m_rayFromWorld,m_rayToWorld,collisionObjectAabbMin,collisionObjectAabbMax,hitLambda,m_hitNormal))
{
m_world->rayTestSingle(m_rayFromTrans,m_rayToTrans,
collisionObject,
collisionObject->getCollisionShape(),
collisionObject->getWorldTransform(),
m_resultCallback);
}
}
return true;
}
};
void btSoftMultiBodyDynamicsWorld::rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const
{
BT_PROFILE("rayTest");
/// use the broadphase to accelerate the search for objects, based on their aabb
/// and for each object with ray-aabb overlap, perform an exact ray test
btSoftSingleRayCallback rayCB(rayFromWorld,rayToWorld,this,resultCallback);
#ifndef USE_BRUTEFORCE_RAYBROADPHASE
m_broadphasePairCache->rayTest(rayFromWorld,rayToWorld,rayCB);
#else
for (int i=0;i<this->getNumCollisionObjects();i++)
{
rayCB.process(m_collisionObjects[i]->getBroadphaseHandle());
}
#endif //USE_BRUTEFORCE_RAYBROADPHASE
}
void btSoftMultiBodyDynamicsWorld::rayTestSingle(const btTransform& rayFromTrans,const btTransform& rayToTrans,
btCollisionObject* collisionObject,
const btCollisionShape* collisionShape,
const btTransform& colObjWorldTransform,
RayResultCallback& resultCallback)
{
if (collisionShape->isSoftBody()) {
btSoftBody* softBody = btSoftBody::upcast(collisionObject);
if (softBody) {
btSoftBody::sRayCast softResult;
if (softBody->rayTest(rayFromTrans.getOrigin(), rayToTrans.getOrigin(), softResult))
{
if (softResult.fraction<= resultCallback.m_closestHitFraction)
{
btCollisionWorld::LocalShapeInfo shapeInfo;
shapeInfo.m_shapePart = 0;
shapeInfo.m_triangleIndex = softResult.index;
// get the normal
btVector3 rayDir = rayToTrans.getOrigin() - rayFromTrans.getOrigin();
btVector3 normal=-rayDir;
normal.normalize();
if (softResult.feature == btSoftBody::eFeature::Face)
{
normal = softBody->m_faces[softResult.index].m_normal;
if (normal.dot(rayDir) > 0) {
// normal always point toward origin of the ray
normal = -normal;
}
}
btCollisionWorld::LocalRayResult rayResult
(collisionObject,
&shapeInfo,
normal,
softResult.fraction);
bool normalInWorldSpace = true;
resultCallback.addSingleResult(rayResult,normalInWorldSpace);
}
}
}
}
else {
btCollisionWorld::rayTestSingle(rayFromTrans,rayToTrans,collisionObject,collisionShape,colObjWorldTransform,resultCallback);
}
}
void btSoftMultiBodyDynamicsWorld::serializeSoftBodies(btSerializer* serializer)
{
int i;
//serialize all collision objects
for (i=0;i<m_collisionObjects.size();i++)
{
btCollisionObject* colObj = m_collisionObjects[i];
if (colObj->getInternalType() & btCollisionObject::CO_SOFT_BODY)
{
int len = colObj->calculateSerializeBufferSize();
btChunk* chunk = serializer->allocate(len,1);
const char* structType = colObj->serialize(chunk->m_oldPtr, serializer);
serializer->finalizeChunk(chunk,structType,BT_SOFTBODY_CODE,colObj);
}
}
}
void btSoftMultiBodyDynamicsWorld::serialize(btSerializer* serializer)
{
serializer->startSerialization();
serializeDynamicsWorldInfo( serializer);
serializeSoftBodies(serializer);
serializeRigidBodies(serializer);
serializeCollisionObjects(serializer);
serializer->finishSerialization();
}

View File

@ -0,0 +1,110 @@
/*
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_MULTIBODY_DYNAMICS_WORLD_H
#define BT_SOFT_MULTIBODY_DYNAMICS_WORLD_H
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
#include "BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.h"
#include "BulletSoftBody/btSoftBody.h"
#ifndef BT_SOFT_RIGID_DYNAMICS_WORLD_H
typedef btAlignedObjectArray<btSoftBody*> btSoftBodyArray;
#endif
class btSoftBodySolver;
class btSoftMultiBodyDynamicsWorld : public btMultiBodyDynamicsWorld
{
btSoftBodyArray m_softBodies;
int m_drawFlags;
bool m_drawNodeTree;
bool m_drawFaceTree;
bool m_drawClusterTree;
btSoftBodyWorldInfo m_sbi;
///Solver classes that encapsulate multiple soft bodies for solving
btSoftBodySolver *m_softBodySolver;
bool m_ownsSolver;
protected:
virtual void predictUnconstraintMotion(btScalar timeStep);
virtual void internalSingleStepSimulation( btScalar timeStep);
void solveSoftBodiesConstraints( btScalar timeStep );
void serializeSoftBodies(btSerializer* serializer);
public:
btSoftMultiBodyDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btMultiBodyConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver = 0 );
virtual ~btSoftMultiBodyDynamicsWorld();
virtual void debugDrawWorld();
void addSoftBody(btSoftBody* body, int collisionFilterGroup=btBroadphaseProxy::DefaultFilter, int collisionFilterMask=btBroadphaseProxy::AllFilter);
void removeSoftBody(btSoftBody* body);
///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btDiscreteDynamicsWorld::removeCollisionObject
virtual void removeCollisionObject(btCollisionObject* collisionObject);
int getDrawFlags() const { return(m_drawFlags); }
void setDrawFlags(int f) { m_drawFlags=f; }
btSoftBodyWorldInfo& getWorldInfo()
{
return m_sbi;
}
const btSoftBodyWorldInfo& getWorldInfo() const
{
return m_sbi;
}
virtual btDynamicsWorldType getWorldType() const
{
return BT_SOFT_MULTIBODY_DYNAMICS_WORLD;
}
btSoftBodyArray& getSoftBodyArray()
{
return m_softBodies;
}
const btSoftBodyArray& getSoftBodyArray() const
{
return m_softBodies;
}
virtual void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const;
/// rayTestSingle performs a raycast call and calls the resultCallback. It is used internally by rayTest.
/// In a future implementation, we consider moving the ray test as a virtual method in btCollisionShape.
/// This allows more customization.
static void rayTestSingle(const btTransform& rayFromTrans,const btTransform& rayToTrans,
btCollisionObject* collisionObject,
const btCollisionShape* collisionShape,
const btTransform& colObjWorldTransform,
RayResultCallback& resultCallback);
virtual void serialize(btSerializer* serializer);
};
#endif //BT_SOFT_MULTIBODY_DYNAMICS_WORLD_H

View File

@ -0,0 +1,86 @@
/*
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.
*/
#include "btSoftRigidCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btSphereShape.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "btSoftBody.h"
#include "BulletSoftBody/btSoftBodySolvers.h"
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
///TODO: include all the shapes that the softbody can collide with
///alternatively, implement special case collision algorithms (just like for rigid collision shapes)
//#include <stdio.h>
btSoftRigidCollisionAlgorithm::btSoftRigidCollisionAlgorithm(btPersistentManifold* /*mf*/,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* ,const btCollisionObjectWrapper* , bool isSwapped)
: btCollisionAlgorithm(ci),
//m_ownManifold(false),
//m_manifoldPtr(mf),
m_isSwapped(isSwapped)
{
}
btSoftRigidCollisionAlgorithm::~btSoftRigidCollisionAlgorithm()
{
//m_softBody->m_overlappingRigidBodies.remove(m_rigidCollisionObject);
/*if (m_ownManifold)
{
if (m_manifoldPtr)
m_dispatcher->releaseManifold(m_manifoldPtr);
}
*/
}
#include <stdio.h>
void btSoftRigidCollisionAlgorithm::processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
(void)dispatchInfo;
(void)resultOut;
//printf("btSoftRigidCollisionAlgorithm\n");
// const btCollisionObjectWrapper* softWrap = m_isSwapped?body1Wrap:body0Wrap;
// const btCollisionObjectWrapper* rigidWrap = m_isSwapped?body0Wrap:body1Wrap;
btSoftBody* softBody = m_isSwapped? (btSoftBody*)body1Wrap->getCollisionObject() : (btSoftBody*)body0Wrap->getCollisionObject();
const btCollisionObjectWrapper* rigidCollisionObjectWrap = m_isSwapped? body0Wrap : body1Wrap;
if (softBody->m_collisionDisabledObjects.findLinearSearch(rigidCollisionObjectWrap->getCollisionObject())==softBody->m_collisionDisabledObjects.size())
{
softBody->getSoftBodySolver()->processCollision(softBody, rigidCollisionObjectWrap);
}
}
btScalar btSoftRigidCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* col0,btCollisionObject* col1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
(void)resultOut;
(void)dispatchInfo;
(void)col0;
(void)col1;
//not yet
return btScalar(1.);
}

View File

@ -0,0 +1,75 @@
/*
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_RIGID_COLLISION_ALGORITHM_H
#define BT_SOFT_RIGID_COLLISION_ALGORITHM_H
#include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
class btPersistentManifold;
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "LinearMath/btVector3.h"
class btSoftBody;
/// btSoftRigidCollisionAlgorithm provides collision detection between btSoftBody and btRigidBody
class btSoftRigidCollisionAlgorithm : public btCollisionAlgorithm
{
// bool m_ownManifold;
// btPersistentManifold* m_manifoldPtr;
//btSoftBody* m_softBody;
//btCollisionObject* m_rigidCollisionObject;
///for rigid versus soft (instead of soft versus rigid), we use this swapped boolean
bool m_isSwapped;
public:
btSoftRigidCollisionAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* col0,const btCollisionObjectWrapper* col1Wrap, bool isSwapped);
virtual ~btSoftRigidCollisionAlgorithm();
virtual void processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
virtual btScalar calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
virtual void getAllContactManifolds(btManifoldArray& manifoldArray)
{
//we don't add any manifolds
}
struct CreateFunc :public btCollisionAlgorithmCreateFunc
{
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(btSoftRigidCollisionAlgorithm));
if (!m_swapped)
{
return new(mem) btSoftRigidCollisionAlgorithm(0,ci,body0Wrap,body1Wrap,false);
} else
{
return new(mem) btSoftRigidCollisionAlgorithm(0,ci,body0Wrap,body1Wrap,true);
}
}
};
};
#endif //BT_SOFT_RIGID_COLLISION_ALGORITHM_H

View File

@ -0,0 +1,367 @@
/*
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.
*/
#include "btSoftRigidDynamicsWorld.h"
#include "LinearMath/btQuickprof.h"
//softbody & helpers
#include "btSoftBody.h"
#include "btSoftBodyHelpers.h"
#include "btSoftBodySolvers.h"
#include "btDefaultSoftBodySolver.h"
#include "LinearMath/btSerializer.h"
btSoftRigidDynamicsWorld::btSoftRigidDynamicsWorld(
btDispatcher* dispatcher,
btBroadphaseInterface* pairCache,
btConstraintSolver* constraintSolver,
btCollisionConfiguration* collisionConfiguration,
btSoftBodySolver *softBodySolver ) :
btDiscreteDynamicsWorld(dispatcher,pairCache,constraintSolver,collisionConfiguration),
m_softBodySolver( softBodySolver ),
m_ownsSolver(false)
{
if( !m_softBodySolver )
{
void* ptr = btAlignedAlloc(sizeof(btDefaultSoftBodySolver),16);
m_softBodySolver = new(ptr) btDefaultSoftBodySolver();
m_ownsSolver = true;
}
m_drawFlags = fDrawFlags::Std;
m_drawNodeTree = true;
m_drawFaceTree = false;
m_drawClusterTree = false;
m_sbi.m_broadphase = pairCache;
m_sbi.m_dispatcher = dispatcher;
m_sbi.m_sparsesdf.Initialize();
m_sbi.m_sparsesdf.Reset();
m_sbi.air_density = (btScalar)1.2;
m_sbi.water_density = 0;
m_sbi.water_offset = 0;
m_sbi.water_normal = btVector3(0,0,0);
m_sbi.m_gravity.setValue(0,-10,0);
m_sbi.m_sparsesdf.Initialize();
}
btSoftRigidDynamicsWorld::~btSoftRigidDynamicsWorld()
{
if (m_ownsSolver)
{
m_softBodySolver->~btSoftBodySolver();
btAlignedFree(m_softBodySolver);
}
}
void btSoftRigidDynamicsWorld::predictUnconstraintMotion(btScalar timeStep)
{
btDiscreteDynamicsWorld::predictUnconstraintMotion( timeStep );
{
BT_PROFILE("predictUnconstraintMotionSoftBody");
m_softBodySolver->predictMotion( float(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" );
}
btDiscreteDynamicsWorld::internalSingleStepSimulation( timeStep );
///solve soft bodies constraints
solveSoftBodiesConstraints( timeStep );
//self collisions
for ( int i=0;i<m_softBodies.size();i++)
{
btSoftBody* psb=(btSoftBody*)m_softBodies[i];
psb->defaultCollisionHandler(psb);
}
///update soft bodies
m_softBodySolver->updateSoftBodies( );
// End solver-wise simulation step
// ///////////////////////////////
}
void btSoftRigidDynamicsWorld::solveSoftBodiesConstraints( btScalar timeStep )
{
BT_PROFILE("solveSoftConstraints");
if(m_softBodies.size())
{
btSoftBody::solveClusters(m_softBodies);
}
// Solve constraints solver-wise
m_softBodySolver->solveConstraints( timeStep * m_softBodySolver->getTimeScale() );
}
void btSoftRigidDynamicsWorld::addSoftBody(btSoftBody* body, int collisionFilterGroup, int collisionFilterMask)
{
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);
}
void btSoftRigidDynamicsWorld::removeSoftBody(btSoftBody* body)
{
m_softBodies.remove(body);
btCollisionWorld::removeCollisionObject(body);
}
void btSoftRigidDynamicsWorld::removeCollisionObject(btCollisionObject* collisionObject)
{
btSoftBody* body = btSoftBody::upcast(collisionObject);
if (body)
removeSoftBody(body);
else
btDiscreteDynamicsWorld::removeCollisionObject(collisionObject);
}
void btSoftRigidDynamicsWorld::debugDrawWorld()
{
btDiscreteDynamicsWorld::debugDrawWorld();
if (getDebugDrawer())
{
int i;
for ( i=0;i<this->m_softBodies.size();i++)
{
btSoftBody* psb=(btSoftBody*)this->m_softBodies[i];
if (getDebugDrawer() && (getDebugDrawer()->getDebugMode() & (btIDebugDraw::DBG_DrawWireframe)))
{
btSoftBodyHelpers::DrawFrame(psb,m_debugDrawer);
btSoftBodyHelpers::Draw(psb,m_debugDrawer,m_drawFlags);
}
if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb))
{
if(m_drawNodeTree) btSoftBodyHelpers::DrawNodeTree(psb,m_debugDrawer);
if(m_drawFaceTree) btSoftBodyHelpers::DrawFaceTree(psb,m_debugDrawer);
if(m_drawClusterTree) btSoftBodyHelpers::DrawClusterTree(psb,m_debugDrawer);
}
}
}
}
struct btSoftSingleRayCallback : public btBroadphaseRayCallback
{
btVector3 m_rayFromWorld;
btVector3 m_rayToWorld;
btTransform m_rayFromTrans;
btTransform m_rayToTrans;
btVector3 m_hitNormal;
const btSoftRigidDynamicsWorld* m_world;
btCollisionWorld::RayResultCallback& m_resultCallback;
btSoftSingleRayCallback(const btVector3& rayFromWorld,const btVector3& rayToWorld,const btSoftRigidDynamicsWorld* world,btCollisionWorld::RayResultCallback& resultCallback)
:m_rayFromWorld(rayFromWorld),
m_rayToWorld(rayToWorld),
m_world(world),
m_resultCallback(resultCallback)
{
m_rayFromTrans.setIdentity();
m_rayFromTrans.setOrigin(m_rayFromWorld);
m_rayToTrans.setIdentity();
m_rayToTrans.setOrigin(m_rayToWorld);
btVector3 rayDir = (rayToWorld-rayFromWorld);
rayDir.normalize ();
///what about division by zero? --> just set rayDirection[i] to INF/1e30
m_rayDirectionInverse[0] = rayDir[0] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[0];
m_rayDirectionInverse[1] = rayDir[1] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[1];
m_rayDirectionInverse[2] = rayDir[2] == btScalar(0.0) ? btScalar(1e30) : btScalar(1.0) / rayDir[2];
m_signs[0] = m_rayDirectionInverse[0] < 0.0;
m_signs[1] = m_rayDirectionInverse[1] < 0.0;
m_signs[2] = m_rayDirectionInverse[2] < 0.0;
m_lambda_max = rayDir.dot(m_rayToWorld-m_rayFromWorld);
}
virtual bool process(const btBroadphaseProxy* proxy)
{
///terminate further ray tests, once the closestHitFraction reached zero
if (m_resultCallback.m_closestHitFraction == btScalar(0.f))
return false;
btCollisionObject* collisionObject = (btCollisionObject*)proxy->m_clientObject;
//only perform raycast if filterMask matches
if(m_resultCallback.needsCollision(collisionObject->getBroadphaseHandle()))
{
//RigidcollisionObject* collisionObject = ctrl->GetRigidcollisionObject();
//btVector3 collisionObjectAabbMin,collisionObjectAabbMax;
#if 0
#ifdef RECALCULATE_AABB
btVector3 collisionObjectAabbMin,collisionObjectAabbMax;
collisionObject->getCollisionShape()->getAabb(collisionObject->getWorldTransform(),collisionObjectAabbMin,collisionObjectAabbMax);
#else
//getBroadphase()->getAabb(collisionObject->getBroadphaseHandle(),collisionObjectAabbMin,collisionObjectAabbMax);
const btVector3& collisionObjectAabbMin = collisionObject->getBroadphaseHandle()->m_aabbMin;
const btVector3& collisionObjectAabbMax = collisionObject->getBroadphaseHandle()->m_aabbMax;
#endif
#endif
//btScalar hitLambda = m_resultCallback.m_closestHitFraction;
//culling already done by broadphase
//if (btRayAabb(m_rayFromWorld,m_rayToWorld,collisionObjectAabbMin,collisionObjectAabbMax,hitLambda,m_hitNormal))
{
m_world->rayTestSingle(m_rayFromTrans,m_rayToTrans,
collisionObject,
collisionObject->getCollisionShape(),
collisionObject->getWorldTransform(),
m_resultCallback);
}
}
return true;
}
};
void btSoftRigidDynamicsWorld::rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const
{
BT_PROFILE("rayTest");
/// use the broadphase to accelerate the search for objects, based on their aabb
/// and for each object with ray-aabb overlap, perform an exact ray test
btSoftSingleRayCallback rayCB(rayFromWorld,rayToWorld,this,resultCallback);
#ifndef USE_BRUTEFORCE_RAYBROADPHASE
m_broadphasePairCache->rayTest(rayFromWorld,rayToWorld,rayCB);
#else
for (int i=0;i<this->getNumCollisionObjects();i++)
{
rayCB.process(m_collisionObjects[i]->getBroadphaseHandle());
}
#endif //USE_BRUTEFORCE_RAYBROADPHASE
}
void btSoftRigidDynamicsWorld::rayTestSingle(const btTransform& rayFromTrans,const btTransform& rayToTrans,
btCollisionObject* collisionObject,
const btCollisionShape* collisionShape,
const btTransform& colObjWorldTransform,
RayResultCallback& resultCallback)
{
if (collisionShape->isSoftBody()) {
btSoftBody* softBody = btSoftBody::upcast(collisionObject);
if (softBody) {
btSoftBody::sRayCast softResult;
if (softBody->rayTest(rayFromTrans.getOrigin(), rayToTrans.getOrigin(), softResult))
{
if (softResult.fraction<= resultCallback.m_closestHitFraction)
{
btCollisionWorld::LocalShapeInfo shapeInfo;
shapeInfo.m_shapePart = 0;
shapeInfo.m_triangleIndex = softResult.index;
// get the normal
btVector3 rayDir = rayToTrans.getOrigin() - rayFromTrans.getOrigin();
btVector3 normal=-rayDir;
normal.normalize();
if (softResult.feature == btSoftBody::eFeature::Face)
{
normal = softBody->m_faces[softResult.index].m_normal;
if (normal.dot(rayDir) > 0) {
// normal always point toward origin of the ray
normal = -normal;
}
}
btCollisionWorld::LocalRayResult rayResult
(collisionObject,
&shapeInfo,
normal,
softResult.fraction);
bool normalInWorldSpace = true;
resultCallback.addSingleResult(rayResult,normalInWorldSpace);
}
}
}
}
else {
btCollisionWorld::rayTestSingle(rayFromTrans,rayToTrans,collisionObject,collisionShape,colObjWorldTransform,resultCallback);
}
}
void btSoftRigidDynamicsWorld::serializeSoftBodies(btSerializer* serializer)
{
int i;
//serialize all collision objects
for (i=0;i<m_collisionObjects.size();i++)
{
btCollisionObject* colObj = m_collisionObjects[i];
if (colObj->getInternalType() & btCollisionObject::CO_SOFT_BODY)
{
int len = colObj->calculateSerializeBufferSize();
btChunk* chunk = serializer->allocate(len,1);
const char* structType = colObj->serialize(chunk->m_oldPtr, serializer);
serializer->finalizeChunk(chunk,structType,BT_SOFTBODY_CODE,colObj);
}
}
}
void btSoftRigidDynamicsWorld::serialize(btSerializer* serializer)
{
serializer->startSerialization();
serializeDynamicsWorldInfo( serializer);
serializeSoftBodies(serializer);
serializeRigidBodies(serializer);
serializeCollisionObjects(serializer);
serializer->finishSerialization();
}

View File

@ -0,0 +1,107 @@
/*
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_RIGID_DYNAMICS_WORLD_H
#define BT_SOFT_RIGID_DYNAMICS_WORLD_H
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
#include "btSoftBody.h"
typedef btAlignedObjectArray<btSoftBody*> btSoftBodyArray;
class btSoftBodySolver;
class btSoftRigidDynamicsWorld : public btDiscreteDynamicsWorld
{
btSoftBodyArray m_softBodies;
int m_drawFlags;
bool m_drawNodeTree;
bool m_drawFaceTree;
bool m_drawClusterTree;
btSoftBodyWorldInfo m_sbi;
///Solver classes that encapsulate multiple soft bodies for solving
btSoftBodySolver *m_softBodySolver;
bool m_ownsSolver;
protected:
virtual void predictUnconstraintMotion(btScalar timeStep);
virtual void internalSingleStepSimulation( btScalar timeStep);
void solveSoftBodiesConstraints( btScalar timeStep );
void serializeSoftBodies(btSerializer* serializer);
public:
btSoftRigidDynamicsWorld(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver, btCollisionConfiguration* collisionConfiguration, btSoftBodySolver *softBodySolver = 0 );
virtual ~btSoftRigidDynamicsWorld();
virtual void debugDrawWorld();
void addSoftBody(btSoftBody* body, int collisionFilterGroup=btBroadphaseProxy::DefaultFilter, int collisionFilterMask=btBroadphaseProxy::AllFilter);
void removeSoftBody(btSoftBody* body);
///removeCollisionObject will first check if it is a rigid body, if so call removeRigidBody otherwise call btDiscreteDynamicsWorld::removeCollisionObject
virtual void removeCollisionObject(btCollisionObject* collisionObject);
int getDrawFlags() const { return(m_drawFlags); }
void setDrawFlags(int f) { m_drawFlags=f; }
btSoftBodyWorldInfo& getWorldInfo()
{
return m_sbi;
}
const btSoftBodyWorldInfo& getWorldInfo() const
{
return m_sbi;
}
virtual btDynamicsWorldType getWorldType() const
{
return BT_SOFT_RIGID_DYNAMICS_WORLD;
}
btSoftBodyArray& getSoftBodyArray()
{
return m_softBodies;
}
const btSoftBodyArray& getSoftBodyArray() const
{
return m_softBodies;
}
virtual void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, RayResultCallback& resultCallback) const;
/// rayTestSingle performs a raycast call and calls the resultCallback. It is used internally by rayTest.
/// In a future implementation, we consider moving the ray test as a virtual method in btCollisionShape.
/// This allows more customization.
static void rayTestSingle(const btTransform& rayFromTrans,const btTransform& rayToTrans,
btCollisionObject* collisionObject,
const btCollisionShape* collisionShape,
const btTransform& colObjWorldTransform,
RayResultCallback& resultCallback);
virtual void serialize(btSerializer* serializer);
};
#endif //BT_SOFT_RIGID_DYNAMICS_WORLD_H

View File

@ -0,0 +1,48 @@
/*
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.
*/
#include "btSoftSoftCollisionAlgorithm.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletSoftBody/btSoftBodySolvers.h"
#include "btSoftBody.h"
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
#define USE_PERSISTENT_CONTACTS 1
btSoftSoftCollisionAlgorithm::btSoftSoftCollisionAlgorithm(btPersistentManifold* /*mf*/,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* /*obj0*/,const btCollisionObjectWrapper* /*obj1*/)
: btCollisionAlgorithm(ci)
//m_ownManifold(false),
//m_manifoldPtr(mf)
{
}
btSoftSoftCollisionAlgorithm::~btSoftSoftCollisionAlgorithm()
{
}
void btSoftSoftCollisionAlgorithm::processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& /*dispatchInfo*/,btManifoldResult* /*resultOut*/)
{
btSoftBody* soft0 = (btSoftBody*)body0Wrap->getCollisionObject();
btSoftBody* soft1 = (btSoftBody*)body1Wrap->getCollisionObject();
soft0->getSoftBodySolver()->processCollision(soft0, soft1);
}
btScalar btSoftSoftCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* /*body0*/,btCollisionObject* /*body1*/,const btDispatcherInfo& /*dispatchInfo*/,btManifoldResult* /*resultOut*/)
{
//not yet
return 1.f;
}

View File

@ -0,0 +1,69 @@
/*
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_SOFT_COLLISION_ALGORITHM_H
#define BT_SOFT_SOFT_COLLISION_ALGORITHM_H
#include "BulletCollision/BroadphaseCollision/btCollisionAlgorithm.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/BroadphaseCollision/btDispatcher.h"
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
class btPersistentManifold;
class btSoftBody;
///collision detection between two btSoftBody shapes
class btSoftSoftCollisionAlgorithm : public btCollisionAlgorithm
{
bool m_ownManifold;
btPersistentManifold* m_manifoldPtr;
// btSoftBody* m_softBody0;
// btSoftBody* m_softBody1;
public:
btSoftSoftCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci)
: btCollisionAlgorithm(ci) {}
virtual void processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
virtual btScalar calculateTimeOfImpact(btCollisionObject* body0,btCollisionObject* body1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut);
virtual void getAllContactManifolds(btManifoldArray& manifoldArray)
{
if (m_manifoldPtr && m_ownManifold)
manifoldArray.push_back(m_manifoldPtr);
}
btSoftSoftCollisionAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap);
virtual ~btSoftSoftCollisionAlgorithm();
struct CreateFunc :public btCollisionAlgorithmCreateFunc
{
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
{
int bbsize = sizeof(btSoftSoftCollisionAlgorithm);
void* ptr = ci.m_dispatcher1->allocateCollisionAlgorithm(bbsize);
return new(ptr) btSoftSoftCollisionAlgorithm(0,ci,body0Wrap,body1Wrap);
}
};
};
#endif //BT_SOFT_SOFT_COLLISION_ALGORITHM_H

View File

@ -0,0 +1,319 @@
/*
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.
*/
///btSparseSdf implementation by Nathanael Presson
#ifndef BT_SPARSE_SDF_H
#define BT_SPARSE_SDF_H
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
// Modified Paul Hsieh hash
template <const int DWORDLEN>
unsigned int HsiehHash(const void* pdata)
{
const unsigned short* data=(const unsigned short*)pdata;
unsigned hash=DWORDLEN<<2,tmp;
for(int i=0;i<DWORDLEN;++i)
{
hash += data[0];
tmp = (data[1]<<11)^hash;
hash = (hash<<16)^tmp;
data += 2;
hash += hash>>11;
}
hash^=hash<<3;hash+=hash>>5;
hash^=hash<<4;hash+=hash>>17;
hash^=hash<<25;hash+=hash>>6;
return(hash);
}
template <const int CELLSIZE>
struct btSparseSdf
{
//
// Inner types
//
struct IntFrac
{
int b;
int i;
btScalar f;
};
struct Cell
{
btScalar d[CELLSIZE+1][CELLSIZE+1][CELLSIZE+1];
int c[3];
int puid;
unsigned hash;
const btCollisionShape* pclient;
Cell* next;
};
//
// Fields
//
btAlignedObjectArray<Cell*> cells;
btScalar voxelsz;
int puid;
int ncells;
int m_clampCells;
int nprobes;
int nqueries;
//
// Methods
//
//
void Initialize(int hashsize=2383, int clampCells = 256*1024)
{
//avoid a crash due to running out of memory, so clamp the maximum number of cells allocated
//if this limit is reached, the SDF is reset (at the cost of some performance during the reset)
m_clampCells = clampCells;
cells.resize(hashsize,0);
Reset();
}
//
void Reset()
{
for(int i=0,ni=cells.size();i<ni;++i)
{
Cell* pc=cells[i];
cells[i]=0;
while(pc)
{
Cell* pn=pc->next;
delete pc;
pc=pn;
}
}
voxelsz =0.25;
puid =0;
ncells =0;
nprobes =1;
nqueries =1;
}
//
void GarbageCollect(int lifetime=256)
{
const int life=puid-lifetime;
for(int i=0;i<cells.size();++i)
{
Cell*& root=cells[i];
Cell* pp=0;
Cell* pc=root;
while(pc)
{
Cell* pn=pc->next;
if(pc->puid<life)
{
if(pp) pp->next=pn; else root=pn;
delete pc;pc=pp;--ncells;
}
pp=pc;pc=pn;
}
}
//printf("GC[%d]: %d cells, PpQ: %f\r\n",puid,ncells,nprobes/(btScalar)nqueries);
nqueries=1;
nprobes=1;
++puid; ///@todo: Reset puid's when int range limit is reached */
/* else setup a priority list... */
}
//
int RemoveReferences(btCollisionShape* pcs)
{
int refcount=0;
for(int i=0;i<cells.size();++i)
{
Cell*& root=cells[i];
Cell* pp=0;
Cell* pc=root;
while(pc)
{
Cell* pn=pc->next;
if(pc->pclient==pcs)
{
if(pp) pp->next=pn; else root=pn;
delete pc;pc=pp;++refcount;
}
pp=pc;pc=pn;
}
}
return(refcount);
}
//
btScalar Evaluate( const btVector3& x,
const btCollisionShape* shape,
btVector3& normal,
btScalar margin)
{
/* Lookup cell */
const btVector3 scx=x/voxelsz;
const IntFrac ix=Decompose(scx.x());
const IntFrac iy=Decompose(scx.y());
const IntFrac iz=Decompose(scx.z());
const unsigned h=Hash(ix.b,iy.b,iz.b,shape);
Cell*& root=cells[static_cast<int>(h%cells.size())];
Cell* c=root;
++nqueries;
while(c)
{
++nprobes;
if( (c->hash==h) &&
(c->c[0]==ix.b) &&
(c->c[1]==iy.b) &&
(c->c[2]==iz.b) &&
(c->pclient==shape))
{ break; }
else
{ c=c->next; }
}
if(!c)
{
++nprobes;
++ncells;
//int sz = sizeof(Cell);
if (ncells>m_clampCells)
{
static int numResets=0;
numResets++;
// printf("numResets=%d\n",numResets);
Reset();
}
c=new Cell();
c->next=root;root=c;
c->pclient=shape;
c->hash=h;
c->c[0]=ix.b;c->c[1]=iy.b;c->c[2]=iz.b;
BuildCell(*c);
}
c->puid=puid;
/* Extract infos */
const int o[]={ ix.i,iy.i,iz.i};
const btScalar d[]={ c->d[o[0]+0][o[1]+0][o[2]+0],
c->d[o[0]+1][o[1]+0][o[2]+0],
c->d[o[0]+1][o[1]+1][o[2]+0],
c->d[o[0]+0][o[1]+1][o[2]+0],
c->d[o[0]+0][o[1]+0][o[2]+1],
c->d[o[0]+1][o[1]+0][o[2]+1],
c->d[o[0]+1][o[1]+1][o[2]+1],
c->d[o[0]+0][o[1]+1][o[2]+1]};
/* Normal */
#if 1
const btScalar gx[]={ d[1]-d[0],d[2]-d[3],
d[5]-d[4],d[6]-d[7]};
const btScalar gy[]={ d[3]-d[0],d[2]-d[1],
d[7]-d[4],d[6]-d[5]};
const btScalar gz[]={ d[4]-d[0],d[5]-d[1],
d[7]-d[3],d[6]-d[2]};
normal.setX(Lerp( Lerp(gx[0],gx[1],iy.f),
Lerp(gx[2],gx[3],iy.f),iz.f));
normal.setY(Lerp( Lerp(gy[0],gy[1],ix.f),
Lerp(gy[2],gy[3],ix.f),iz.f));
normal.setZ(Lerp( Lerp(gz[0],gz[1],ix.f),
Lerp(gz[2],gz[3],ix.f),iy.f));
normal = normal.normalized();
#else
normal = btVector3(d[1]-d[0],d[3]-d[0],d[4]-d[0]).normalized();
#endif
/* Distance */
const btScalar d0=Lerp(Lerp(d[0],d[1],ix.f),
Lerp(d[3],d[2],ix.f),iy.f);
const btScalar d1=Lerp(Lerp(d[4],d[5],ix.f),
Lerp(d[7],d[6],ix.f),iy.f);
return(Lerp(d0,d1,iz.f)-margin);
}
//
void BuildCell(Cell& c)
{
const btVector3 org=btVector3( (btScalar)c.c[0],
(btScalar)c.c[1],
(btScalar)c.c[2]) *
CELLSIZE*voxelsz;
for(int k=0;k<=CELLSIZE;++k)
{
const btScalar z=voxelsz*k+org.z();
for(int j=0;j<=CELLSIZE;++j)
{
const btScalar y=voxelsz*j+org.y();
for(int i=0;i<=CELLSIZE;++i)
{
const btScalar x=voxelsz*i+org.x();
c.d[i][j][k]=DistanceToShape( btVector3(x,y,z),
c.pclient);
}
}
}
}
//
static inline btScalar DistanceToShape(const btVector3& x,
const btCollisionShape* shape)
{
btTransform unit;
unit.setIdentity();
if(shape->isConvex())
{
btGjkEpaSolver2::sResults res;
const btConvexShape* csh=static_cast<const btConvexShape*>(shape);
return(btGjkEpaSolver2::SignedDistance(x,0,csh,unit,res));
}
return(0);
}
//
static inline IntFrac Decompose(btScalar x)
{
/* That one need a lot of improvements... */
/* Remove test, faster floor... */
IntFrac r;
x/=CELLSIZE;
const int o=x<0?(int)(-x+1):0;
x+=o;r.b=(int)x;
const btScalar k=(x-r.b)*CELLSIZE;
r.i=(int)k;r.f=k-r.i;r.b-=o;
return(r);
}
//
static inline btScalar Lerp(btScalar a,btScalar b,btScalar t)
{
return(a+(b-a)*t);
}
//
static inline unsigned int Hash(int x,int y,int z,const btCollisionShape* shape)
{
struct btS
{
int x,y,z;
void* p;
};
btS myset;
myset.x=x;myset.y=y;myset.z=z;myset.p=(void*)shape;
const void* ptr = &myset;
unsigned int result = HsiehHash<sizeof(btS)/4> (ptr);
return result;
}
};
#endif //BT_SPARSE_SDF_H

View File

@ -0,0 +1,11 @@
project "BulletSoftBody"
kind "StaticLib"
includedirs {
"..",
}
files {
"**.cpp",
"**.h"
}