add SoftDemo examples

add example description for all examples (with word-wrap)
add the VoronoiFractureDemo, note that the collision are disabled after breaking constraints.
add optional GwenOpenGLTest, to make it easier to see Gwen user interface features.
This commit is contained in:
erwin coumans
2015-04-27 18:35:07 -07:00
parent 619833ee00
commit 27227e5e4a
45 changed files with 8357 additions and 61 deletions

View File

@@ -0,0 +1,819 @@
/*
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.
*/
/*
Voronoi fracture and shatter code and demo copyright (c) 2011 Alain Ducharme
- Reset scene (press spacebar) to generate new random voronoi shattered cuboids
- Check console for total time required to: compute and mesh all 3D shards, calculate volumes and centers of mass and create rigid bodies
- Modify VORONOIPOINTS define below to change number of potential voronoi shards
- Note that demo's visual cracks between voronoi shards are NOT present in the internally generated voronoi mesh!
*/
//Number of random voronoi points to generate for shattering
#define VORONOIPOINTS 100
//maximum number of objects (and allow user to shoot additional boxes)
#define MAX_PROXIES (2048)
#define BREAKING_THRESHOLD 3
#define CONVEX_MARGIN 0.04
static int useMpr = 0;
#include "VoronoiFractureDemo.h"
///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
#include "btBulletDynamicsCommon.h"
#include <stdio.h> //printf debugging
static bool useGenericConstraint = false;
#include "btConvexConvexMprAlgorithm.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btConvexHullComputer.h"
#include "LinearMath/btQuaternion.h"
#include <set>
#include <time.h>
class btBroadphaseInterface;
class btCollisionShape;
class btOverlappingPairCache;
class btCollisionDispatcher;
class btConstraintSolver;
struct btCollisionAlgorithmCreateFunc;
class btDefaultCollisionConfiguration;
#include "../CommonInterfaces/CommonRigidBodyBase.h"
class VoronoiFractureDemo : public CommonRigidBodyBase
{
//keep the collision shapes, for deletion/cleanup
btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
btBroadphaseInterface* m_broadphase;
btCollisionDispatcher* m_dispatcher;
btConstraintSolver* m_solver;
btDefaultCollisionConfiguration* m_collisionConfiguration;
btClock m_perfmTimer;
public:
VoronoiFractureDemo(struct GUIHelperInterface* helper)
:CommonRigidBodyBase(helper)
{
srand((unsigned)time(NULL)); // Seed it...
}
virtual ~VoronoiFractureDemo()
{
btAssert(m_dynamicsWorld==0);
}
void initPhysics();
void exitPhysics();
//virtual void renderme();
void getVerticesInsidePlanes(const btAlignedObjectArray<btVector3>& planes, btAlignedObjectArray<btVector3>& verticesOut, std::set<int>& planeIndicesOut);
void voronoiBBShatter(const btAlignedObjectArray<btVector3>& points, const btVector3& bbmin, const btVector3& bbmax, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity);
void voronoiConvexHullShatter(const btAlignedObjectArray<btVector3>& points, const btAlignedObjectArray<btVector3>& verts, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity);
//virtual void clientMoveAndDisplay();
//virtual void displayCallback();
//virtual void clientResetScene();
//virtual void keyboardCallback(unsigned char key, int x, int y);
void attachFixedConstraints();
};
void VoronoiFractureDemo::attachFixedConstraints()
{
btAlignedObjectArray<btRigidBody*> bodies;
int numManifolds = m_dynamicsWorld->getDispatcher()->getNumManifolds();
for (int i=0;i<numManifolds;i++)
{
btPersistentManifold* manifold = m_dynamicsWorld->getDispatcher()->getManifoldByIndexInternal(i);
if (!manifold->getNumContacts())
continue;
btScalar minDist = 1e30f;
int minIndex = -1;
for (int v=0;v<manifold->getNumContacts();v++)
{
if (minDist >manifold->getContactPoint(v).getDistance())
{
minDist = manifold->getContactPoint(v).getDistance();
minIndex = v;
}
}
if (minDist>0.)
continue;
btCollisionObject* colObj0 = (btCollisionObject*)manifold->getBody0();
btCollisionObject* colObj1 = (btCollisionObject*)manifold->getBody1();
// int tag0 = (colObj0)->getIslandTag();
// int tag1 = (colObj1)->getIslandTag();
btRigidBody* body0 = btRigidBody::upcast(colObj0);
btRigidBody* body1 = btRigidBody::upcast(colObj1);
if (bodies.findLinearSearch(body0)==bodies.size())
bodies.push_back(body0);
if (bodies.findLinearSearch(body1)==bodies.size())
bodies.push_back(body1);
if (body0 && body1)
{
if (!colObj0->isStaticOrKinematicObject() && !colObj1->isStaticOrKinematicObject())
{
if (body0->checkCollideWithOverride(body1))
{
{
btTransform trA,trB;
trA.setIdentity();
trB.setIdentity();
btVector3 contactPosWorld = manifold->getContactPoint(minIndex).m_positionWorldOnA;
btTransform globalFrame;
globalFrame.setIdentity();
globalFrame.setOrigin(contactPosWorld);
trA = body0->getWorldTransform().inverse()*globalFrame;
trB = body1->getWorldTransform().inverse()*globalFrame;
float totalMass = 1.f/body0->getInvMass() + 1.f/body1->getInvMass();
if (useGenericConstraint)
{
btGeneric6DofConstraint* dof6 = new btGeneric6DofConstraint(*body0,*body1,trA,trB,true);
dof6->setOverrideNumSolverIterations(30);
dof6->setBreakingImpulseThreshold(BREAKING_THRESHOLD*totalMass);
for (int i=0;i<6;i++)
dof6->setLimit(i,0,0);
m_dynamicsWorld->addConstraint(dof6,true);
} else
{
btFixedConstraint* fixed = new btFixedConstraint(*body0,*body1,trA,trB);
fixed->setBreakingImpulseThreshold(BREAKING_THRESHOLD*totalMass);
fixed ->setOverrideNumSolverIterations(30);
m_dynamicsWorld->addConstraint(fixed,true);
}
}
}
}
}
}
for (int i=0;i<bodies.size();i++)
{
m_dynamicsWorld->removeRigidBody(bodies[i]);
m_dynamicsWorld->addRigidBody(bodies[i]);
}
}
/*
void VoronoiFractureDemo::keyboardCallback(unsigned char key, int x, int y)
{
if (key == 'g')
{
attachFixedConstraints();
}else
{
PlatformDemoApplication::keyboardCallback(key,x,y);
}
}
*/
void VoronoiFractureDemo::getVerticesInsidePlanes(const btAlignedObjectArray<btVector3>& planes, btAlignedObjectArray<btVector3>& verticesOut, std::set<int>& planeIndicesOut)
{
// Based on btGeometryUtil.cpp (Gino van den Bergen / Erwin Coumans)
verticesOut.resize(0);
planeIndicesOut.clear();
const int numPlanes = planes.size();
int i, j, k, l;
for (i=0;i<numPlanes;i++)
{
const btVector3& N1 = planes[i];
for (j=i+1;j<numPlanes;j++)
{
const btVector3& N2 = planes[j];
btVector3 n1n2 = N1.cross(N2);
if (n1n2.length2() > btScalar(0.0001))
{
for (k=j+1;k<numPlanes;k++)
{
const btVector3& N3 = planes[k];
btVector3 n2n3 = N2.cross(N3);
btVector3 n3n1 = N3.cross(N1);
if ((n2n3.length2() > btScalar(0.0001)) && (n3n1.length2() > btScalar(0.0001) ))
{
btScalar quotient = (N1.dot(n2n3));
if (btFabs(quotient) > btScalar(0.0001))
{
btVector3 potentialVertex = (n2n3 * N1[3] + n3n1 * N2[3] + n1n2 * N3[3]) * (btScalar(-1.) / quotient);
for (l=0; l<numPlanes; l++)
{
const btVector3& NP = planes[l];
if (btScalar(NP.dot(potentialVertex))+btScalar(NP[3]) > btScalar(0.000001))
break;
}
if (l == numPlanes)
{
// vertex (three plane intersection) inside all planes
verticesOut.push_back(potentialVertex);
planeIndicesOut.insert(i);
planeIndicesOut.insert(j);
planeIndicesOut.insert(k);
}
}
}
}
}
}
}
}
static btVector3 curVoronoiPoint;
struct pointCmp
{
bool operator()(const btVector3& p1, const btVector3& p2) const
{
float v1 = (p1-curVoronoiPoint).length2();
float v2 = (p2-curVoronoiPoint).length2();
bool result0 = v1 < v2;
//bool result1 = ((btScalar)(p1-curVoronoiPoint).length2()) < ((btScalar)(p2-curVoronoiPoint).length2());
//apparently result0 is not always result1, because extended precision used in registered is different from precision when values are stored in memory
return result0;
}
};
void VoronoiFractureDemo::voronoiBBShatter(const btAlignedObjectArray<btVector3>& points, const btVector3& bbmin, const btVector3& bbmax, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity) {
// points define voronoi cells in world space (avoid duplicates)
// bbmin & bbmax = bounding box min and max in local space
// bbq & bbt = bounding box quaternion rotation and translation
// matDensity = Material density for voronoi shard mass calculation
btVector3 bbvx = quatRotate(bbq, btVector3(1.0, 0.0, 0.0));
btVector3 bbvy = quatRotate(bbq, btVector3(0.0, 1.0, 0.0));
btVector3 bbvz = quatRotate(bbq, btVector3(0.0, 0.0, 1.0));
btQuaternion bbiq = bbq.inverse();
btConvexHullComputer* convexHC = new btConvexHullComputer();
btAlignedObjectArray<btVector3> vertices;
btVector3 rbb, nrbb;
btScalar nlength, maxDistance, distance;
btAlignedObjectArray<btVector3> sortedVoronoiPoints;
sortedVoronoiPoints.copyFromArray(points);
btVector3 normal, plane;
btAlignedObjectArray<btVector3> planes;
std::set<int> planeIndices;
std::set<int>::iterator planeIndicesIter;
int numplaneIndices;
int cellnum = 0;
int i, j, k;
int numpoints = points.size();
for (i=0; i < numpoints ;i++) {
curVoronoiPoint = points[i];
btVector3 icp = quatRotate(bbiq, curVoronoiPoint - bbt);
rbb = icp - bbmax;
nrbb = bbmin - icp;
planes.resize(6);
planes[0] = bbvx; planes[0][3] = rbb.x();
planes[1] = bbvy; planes[1][3] = rbb.y();
planes[2] = bbvz; planes[2][3] = rbb.z();
planes[3] = -bbvx; planes[3][3] = nrbb.x();
planes[4] = -bbvy; planes[4][3] = nrbb.y();
planes[5] = -bbvz; planes[5][3] = nrbb.z();
maxDistance = SIMD_INFINITY;
sortedVoronoiPoints.heapSort(pointCmp());
for (j=1; j < numpoints; j++) {
normal = sortedVoronoiPoints[j] - curVoronoiPoint;
nlength = normal.length();
if (nlength > maxDistance)
break;
plane = normal.normalized();
plane[3] = -nlength / btScalar(2.);
planes.push_back(plane);
getVerticesInsidePlanes(planes, vertices, planeIndices);
if (vertices.size() == 0)
break;
numplaneIndices = planeIndices.size();
if (numplaneIndices != planes.size()) {
planeIndicesIter = planeIndices.begin();
for (k=0; k < numplaneIndices; k++) {
if (k != *planeIndicesIter)
planes[k] = planes[*planeIndicesIter];
planeIndicesIter++;
}
planes.resize(numplaneIndices);
}
maxDistance = vertices[0].length();
for (k=1; k < vertices.size(); k++) {
distance = vertices[k].length();
if (maxDistance < distance)
maxDistance = distance;
}
maxDistance *= btScalar(2.);
}
if (vertices.size() == 0)
continue;
// Clean-up voronoi convex shard vertices and generate edges & faces
convexHC->compute(&vertices[0].getX(), sizeof(btVector3), vertices.size(),CONVEX_MARGIN,0.0);
// At this point we have a complete 3D voronoi shard mesh contained in convexHC
// Calculate volume and center of mass (Stan Melax volume integration)
int numFaces = convexHC->faces.size();
int v0, v1, v2; // Triangle vertices
btScalar volume = btScalar(0.);
btVector3 com(0., 0., 0.);
for (j=0; j < numFaces; j++) {
const btConvexHullComputer::Edge* edge = &convexHC->edges[convexHC->faces[j]];
v0 = edge->getSourceVertex();
v1 = edge->getTargetVertex();
edge = edge->getNextEdgeOfFace();
v2 = edge->getTargetVertex();
while (v2 != v0) {
// Counter-clockwise triangulated voronoi shard mesh faces (v0-v1-v2) and edges here...
btScalar vol = convexHC->vertices[v0].triple(convexHC->vertices[v1], convexHC->vertices[v2]);
volume += vol;
com += vol * (convexHC->vertices[v0] + convexHC->vertices[v1] + convexHC->vertices[v2]);
edge = edge->getNextEdgeOfFace();
v1 = v2;
v2 = edge->getTargetVertex();
}
}
com /= volume * btScalar(4.);
volume /= btScalar(6.);
// Shift all vertices relative to center of mass
int numVerts = convexHC->vertices.size();
for (j=0; j < numVerts; j++)
{
convexHC->vertices[j] -= com;
}
// Note:
// At this point convex hulls contained in convexHC should be accurate (line up flush with other pieces, no cracks),
// ...however Bullet Physics rigid bodies demo visualizations appear to produce some visible cracks.
// Use the mesh in convexHC for visual display or to perform boolean operations with.
// Create Bullet Physics rigid body shards
btCollisionShape* shardShape = new btConvexHullShape(&(convexHC->vertices[0].getX()), convexHC->vertices.size());
shardShape->setMargin(CONVEX_MARGIN); // for this demo; note convexHC has optional margin parameter for this
m_collisionShapes.push_back(shardShape);
btTransform shardTransform;
shardTransform.setIdentity();
shardTransform.setOrigin(curVoronoiPoint + com); // Shard's adjusted location
btDefaultMotionState* shardMotionState = new btDefaultMotionState(shardTransform);
btScalar shardMass(volume * matDensity);
btVector3 shardInertia(0.,0.,0.);
shardShape->calculateLocalInertia(shardMass, shardInertia);
btRigidBody::btRigidBodyConstructionInfo shardRBInfo(shardMass, shardMotionState, shardShape, shardInertia);
btRigidBody* shardBody = new btRigidBody(shardRBInfo);
m_dynamicsWorld->addRigidBody(shardBody);
cellnum ++;
}
printf("Generated %d voronoi btRigidBody shards\n", cellnum);
}
void VoronoiFractureDemo::voronoiConvexHullShatter(const btAlignedObjectArray<btVector3>& points, const btAlignedObjectArray<btVector3>& verts, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity) {
// points define voronoi cells in world space (avoid duplicates)
// verts = source (convex hull) mesh vertices in local space
// bbq & bbt = source (convex hull) mesh quaternion rotation and translation
// matDensity = Material density for voronoi shard mass calculation
btConvexHullComputer* convexHC = new btConvexHullComputer();
btAlignedObjectArray<btVector3> vertices, chverts;
btVector3 rbb, nrbb;
btScalar nlength, maxDistance, distance;
btAlignedObjectArray<btVector3> sortedVoronoiPoints;
sortedVoronoiPoints.copyFromArray(points);
btVector3 normal, plane;
btAlignedObjectArray<btVector3> planes, convexPlanes;
std::set<int> planeIndices;
std::set<int>::iterator planeIndicesIter;
int numplaneIndices;
int cellnum = 0;
int i, j, k;
// Convert verts to world space and get convexPlanes
int numverts = verts.size();
chverts.resize(verts.size());
for (i=0; i < numverts ;i++) {
chverts[i] = quatRotate(bbq, verts[i]) + bbt;
}
//btGeometryUtil::getPlaneEquationsFromVertices(chverts, convexPlanes);
// Using convexHullComputer faster than getPlaneEquationsFromVertices for large meshes...
convexHC->compute(&chverts[0].getX(), sizeof(btVector3), numverts, 0.0, 0.0);
int numFaces = convexHC->faces.size();
int v0, v1, v2; // vertices
for (i=0; i < numFaces; i++) {
const btConvexHullComputer::Edge* edge = &convexHC->edges[convexHC->faces[i]];
v0 = edge->getSourceVertex();
v1 = edge->getTargetVertex();
edge = edge->getNextEdgeOfFace();
v2 = edge->getTargetVertex();
plane = (convexHC->vertices[v1]-convexHC->vertices[v0]).cross(convexHC->vertices[v2]-convexHC->vertices[v0]).normalize();
plane[3] = -plane.dot(convexHC->vertices[v0]);
convexPlanes.push_back(plane);
}
const int numconvexPlanes = convexPlanes.size();
int numpoints = points.size();
for (i=0; i < numpoints ;i++) {
curVoronoiPoint = points[i];
planes.copyFromArray(convexPlanes);
for (j=0; j < numconvexPlanes ;j++) {
planes[j][3] += planes[j].dot(curVoronoiPoint);
}
maxDistance = SIMD_INFINITY;
sortedVoronoiPoints.heapSort(pointCmp());
for (j=1; j < numpoints; j++) {
normal = sortedVoronoiPoints[j] - curVoronoiPoint;
nlength = normal.length();
if (nlength > maxDistance)
break;
plane = normal.normalized();
plane[3] = -nlength / btScalar(2.);
planes.push_back(plane);
getVerticesInsidePlanes(planes, vertices, planeIndices);
if (vertices.size() == 0)
break;
numplaneIndices = planeIndices.size();
if (numplaneIndices != planes.size()) {
planeIndicesIter = planeIndices.begin();
for (k=0; k < numplaneIndices; k++) {
if (k != *planeIndicesIter)
planes[k] = planes[*planeIndicesIter];
planeIndicesIter++;
}
planes.resize(numplaneIndices);
}
maxDistance = vertices[0].length();
for (k=1; k < vertices.size(); k++) {
distance = vertices[k].length();
if (maxDistance < distance)
maxDistance = distance;
}
maxDistance *= btScalar(2.);
}
if (vertices.size() == 0)
continue;
// Clean-up voronoi convex shard vertices and generate edges & faces
convexHC->compute(&vertices[0].getX(), sizeof(btVector3), vertices.size(),0.0,0.0);
// At this point we have a complete 3D voronoi shard mesh contained in convexHC
// Calculate volume and center of mass (Stan Melax volume integration)
numFaces = convexHC->faces.size();
btScalar volume = btScalar(0.);
btVector3 com(0., 0., 0.);
for (j=0; j < numFaces; j++) {
const btConvexHullComputer::Edge* edge = &convexHC->edges[convexHC->faces[j]];
v0 = edge->getSourceVertex();
v1 = edge->getTargetVertex();
edge = edge->getNextEdgeOfFace();
v2 = edge->getTargetVertex();
while (v2 != v0) {
// Counter-clockwise triangulated voronoi shard mesh faces (v0-v1-v2) and edges here...
btScalar vol = convexHC->vertices[v0].triple(convexHC->vertices[v1], convexHC->vertices[v2]);
volume += vol;
com += vol * (convexHC->vertices[v0] + convexHC->vertices[v1] + convexHC->vertices[v2]);
edge = edge->getNextEdgeOfFace();
v1 = v2;
v2 = edge->getTargetVertex();
}
}
com /= volume * btScalar(4.);
volume /= btScalar(6.);
// Shift all vertices relative to center of mass
int numVerts = convexHC->vertices.size();
for (j=0; j < numVerts; j++)
{
convexHC->vertices[j] -= com;
}
// Note:
// At this point convex hulls contained in convexHC should be accurate (line up flush with other pieces, no cracks),
// ...however Bullet Physics rigid bodies demo visualizations appear to produce some visible cracks.
// Use the mesh in convexHC for visual display or to perform boolean operations with.
// Create Bullet Physics rigid body shards
btCollisionShape* shardShape = new btConvexHullShape(&(convexHC->vertices[0].getX()), convexHC->vertices.size());
shardShape->setMargin(CONVEX_MARGIN); // for this demo; note convexHC has optional margin parameter for this
m_collisionShapes.push_back(shardShape);
btTransform shardTransform;
shardTransform.setIdentity();
shardTransform.setOrigin(curVoronoiPoint + com); // Shard's adjusted location
btDefaultMotionState* shardMotionState = new btDefaultMotionState(shardTransform);
btScalar shardMass(volume * matDensity);
btVector3 shardInertia(0.,0.,0.);
shardShape->calculateLocalInertia(shardMass, shardInertia);
btRigidBody::btRigidBodyConstructionInfo shardRBInfo(shardMass, shardMotionState, shardShape, shardInertia);
btRigidBody* shardBody = new btRigidBody(shardRBInfo);
m_dynamicsWorld->addRigidBody(shardBody);
cellnum ++;
}
printf("Generated %d voronoi btRigidBody shards\n", cellnum);
}
/*
void VoronoiFractureDemo::clientMoveAndDisplay()
{
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
//simple dynamics world doesn't handle fixed-time-stepping
float ms = getDeltaTimeMicroseconds();
///step the simulation
if (m_dynamicsWorld)
{
m_dynamicsWorld->stepSimulation(1. / 60., 0);// ms / 1000000.f);
//optional but useful: debug drawing
m_dynamicsWorld->debugDrawWorld();
}
renderme();
glFlush();
swapBuffers();
}
*/
/*
void VoronoiFractureDemo::displayCallback(void) {
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
renderme();
//optional but useful: debug drawing to detect problems
if (m_dynamicsWorld)
m_dynamicsWorld->debugDrawWorld();
glFlush();
swapBuffers();
}
*/
/*
void VoronoiFractureDemo::renderme()
{
DemoApplication::renderme();
char buf[124];
int lineWidth = 200;
int xStart = m_glutScreenWidth - lineWidth;
if (useMpr)
{
sprintf(buf, "Using GJK+MPR");
}
else
{
sprintf(buf, "Using GJK+EPA");
}
GLDebugDrawString(xStart, 20, buf);
}
*/
void VoronoiFractureDemo::initPhysics()
{
srand(13);
useGenericConstraint = !useGenericConstraint;
printf("useGenericConstraint = %d\n", useGenericConstraint);
///collision configuration contains default setup for memory, collision setup
m_collisionConfiguration = new btDefaultCollisionConfiguration();
//m_collisionConfiguration->setConvexConvexMultipointIterations();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
useMpr = 1 - useMpr;
if (useMpr)
{
printf("using GJK+MPR convex-convex collision detection\n");
btConvexConvexMprAlgorithm::CreateFunc* cf = new btConvexConvexMprAlgorithm::CreateFunc;
m_dispatcher->registerCollisionCreateFunc(CONVEX_HULL_SHAPE_PROXYTYPE, CONVEX_HULL_SHAPE_PROXYTYPE, cf);
m_dispatcher->registerCollisionCreateFunc(CONVEX_HULL_SHAPE_PROXYTYPE, BOX_SHAPE_PROXYTYPE, cf);
m_dispatcher->registerCollisionCreateFunc(BOX_SHAPE_PROXYTYPE, CONVEX_HULL_SHAPE_PROXYTYPE, cf);
}
else
{
printf("using default (GJK+EPA) convex-convex collision detection\n");
}
m_broadphase = new btDbvtBroadphase();
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
m_solver = sol;
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
m_dynamicsWorld->getSolverInfo().m_splitImpulse = true;
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
m_dynamicsWorld->setGravity(btVector3(0,-10,0));
///create a few basic rigid bodies
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(50.),btScalar(50.)));
// btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
m_collisionShapes.push_back(groundShape);
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(0,-50,0));
//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
{
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
groundShape->calculateLocalInertia(mass,localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
//add the body to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
{
btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(10.),btScalar(8.),btScalar(1.)));
btScalar mass(0.);
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
groundShape->calculateLocalInertia(mass,localInertia);
groundTransform.setOrigin(btVector3(0,0,0));
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass,myMotionState,groundShape,localInertia);
btRigidBody* body = new btRigidBody(rbInfo);
//add the body to the dynamics world
m_dynamicsWorld->addRigidBody(body);
}
// ==> Voronoi Shatter Basic Demo: Random Cuboid
// Random size cuboid (defined by bounding box max and min)
btVector3 bbmax(btScalar(rand() / btScalar(RAND_MAX)) * 12. +0.5, btScalar(rand() / btScalar(RAND_MAX)) * 1. +0.5, btScalar(rand() / btScalar(RAND_MAX)) * 1. +0.5);
btVector3 bbmin = -bbmax;
// Place it 10 units above ground
btVector3 bbt(0,15,0);
// Use an arbitrary material density for shards (should be consitent/relative with/to rest of RBs in world)
btScalar matDensity = 1;
// Using random rotation
btQuaternion bbq(btScalar(rand() / btScalar(RAND_MAX)) * 2. -1.,btScalar(rand() / btScalar(RAND_MAX)) * 2. -1.,btScalar(rand() / btScalar(RAND_MAX)) * 2. -1.,btScalar(rand() / btScalar(RAND_MAX)) * 2. -1.);
bbq.normalize();
// Generate random points for voronoi cells
btAlignedObjectArray<btVector3> points;
btVector3 point;
btVector3 diff = bbmax - bbmin;
for (int i=0; i < VORONOIPOINTS; i++) {
// Place points within box area (points are in world coordinates)
point = quatRotate(bbq, btVector3(btScalar(rand() / btScalar(RAND_MAX)) * diff.x() -diff.x()/2., btScalar(rand() / btScalar(RAND_MAX)) * diff.y() -diff.y()/2., btScalar(rand() / btScalar(RAND_MAX)) * diff.z() -diff.z()/2.)) + bbt;
points.push_back(point);
}
m_perfmTimer.reset();
voronoiBBShatter(points, bbmin, bbmax, bbq, bbt, matDensity);
printf("Total Time: %f seconds\n", m_perfmTimer.getTimeMilliseconds()/1000.);
for (int i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
obj->getCollisionShape()->setMargin(CONVEX_MARGIN+0.01);
}
m_dynamicsWorld->performDiscreteCollisionDetection();
for (int i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
obj->getCollisionShape()->setMargin(CONVEX_MARGIN);
}
attachFixedConstraints();
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
}
void VoronoiFractureDemo::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
int i;
//remove all constraints
for (i=m_dynamicsWorld->getNumConstraints()-1;i>=0;i--)
{
btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
m_dynamicsWorld->removeConstraint(constraint);
delete constraint;
}
//remove the rigidbodies from the dynamics world and delete them
for (i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
{
delete body->getMotionState();
}
m_dynamicsWorld->removeCollisionObject( obj );
delete obj;
}
//delete collision shapes
for (int j=0;j<m_collisionShapes.size();j++)
{
btCollisionShape* shape = m_collisionShapes[j];
delete shape;
}
m_collisionShapes.clear();
delete m_dynamicsWorld;
m_dynamicsWorld = 0;
delete m_solver;
m_solver=0;
delete m_broadphase;
m_broadphase=0;
delete m_dispatcher;
m_dispatcher=0;
delete m_collisionConfiguration;
m_collisionConfiguration=0;
}
/*
static DemoApplication* Create()
{
VoronoiFractureDemo* demo = new VoronoiFractureDemo;
demo->myinit();
demo->initPhysics();
return demo;
}
*/
ExampleInterface* VoronoiFractureCreateFunc(PhysicsInterface* pint, GUIHelperInterface* helper, int option)
{
return new VoronoiFractureDemo(helper);
}

View File

@@ -0,0 +1,21 @@
/*
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 VORONOI_FRACTURE_DEMO_H
#define VORONOI_FRACTURE_DEMO_H
class ExampleInterface* VoronoiFractureCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option);
#endif //VORONOI_FRACTURE_DEMO_H

View File

@@ -0,0 +1,288 @@
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2014 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 "btConvexConvexMprAlgorithm.h"
//#include <stdio.h>
#include "BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseInterface.h"
#include "BulletCollision/CollisionDispatch/btCollisionObject.h"
#include "BulletCollision/CollisionShapes/btConvexShape.h"
#include "BulletCollision/CollisionShapes/btTriangleShape.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionDispatch/btManifoldResult.h"
#include "BulletCollision/NarrowPhaseCollision/btConvexPenetrationDepthSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btContinuousConvexCollision.h"
#include "BulletCollision/NarrowPhaseCollision/btSubSimplexConvexCast.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkConvexCast.h"
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
#include "BulletCollision/CollisionShapes/btSphereShape.h"
#include "BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa2.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpaPenetrationDepthSolver.h"
#include "BulletCollision/NarrowPhaseCollision/btPolyhedralContactClipping.h"
#include "BulletCollision/CollisionDispatch/btCollisionObjectWrapper.h"
#include "BulletCollision/NarrowPhaseCollision/btComputeGjkEpaPenetration.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkEpa3.h"
#include "BulletCollision/NarrowPhaseCollision/btMprPenetration.h"
//this is just an internal debug variable to switch between GJK+MPR or GJK+EPA
bool gUseMprCollisionFunction = true;
btConvexConvexMprAlgorithm::CreateFunc::CreateFunc()
{
}
btConvexConvexMprAlgorithm::CreateFunc::~CreateFunc()
{
}
btConvexConvexMprAlgorithm::btConvexConvexMprAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
: btActivatingCollisionAlgorithm(ci,body0Wrap,body1Wrap),
m_ownManifold (false),
m_manifoldPtr(mf)
{
(void)body0Wrap;
(void)body1Wrap;
}
btConvexConvexMprAlgorithm::~btConvexConvexMprAlgorithm()
{
if (m_ownManifold)
{
if (m_manifoldPtr)
m_dispatcher->releaseManifold(m_manifoldPtr);
}
}
btVector3 btBulletShapeSupportFunc(const void* shapeAptr, const btVector3& dir, bool includeMargin)
{
btConvexShape* shape = (btConvexShape*) shapeAptr;
if (includeMargin)
{
return shape->localGetSupportingVertex(dir);
}
return shape->localGetSupportingVertexWithoutMargin(dir);
}
btVector3 btBulletShapeCenterFunc(const void* shapeAptr)
{
return btVector3(0,0,0);
}
struct btMprConvexWrap
{
const btConvexShape* m_convex;
btTransform m_worldTrans;
inline btScalar getMargin() const
{
return m_convex->getMargin();
}
inline btVector3 getObjectCenterInWorld() const
{
return m_worldTrans.getOrigin();
}
inline const btTransform& getWorldTransform() const
{
return m_worldTrans;
}
inline btVector3 getLocalSupportWithMargin(const btVector3& dir) const
{
return m_convex->localGetSupportingVertex(dir);
}
inline btVector3 getLocalSupportWithoutMargin(const btVector3& dir) const
{
return m_convex->localGetSupportingVertexWithoutMargin(dir);
}
};
struct btMyDistanceInfo
{
btVector3 m_pointOnA;
btVector3 m_pointOnB;
btVector3 m_normalBtoA;
btScalar m_distance;
};
//
// Convex-Convex collision algorithm
//
void btConvexConvexMprAlgorithm ::processCollision (const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
if (!m_manifoldPtr)
{
//swapped?
m_manifoldPtr = m_dispatcher->getNewManifold(body0Wrap->getCollisionObject(),body1Wrap->getCollisionObject());
m_ownManifold = true;
}
resultOut->setPersistentManifold(m_manifoldPtr);
//comment-out next line to test multi-contact generation
//resultOut->getPersistentManifold()->clearManifold();
const btConvexShape* min0 = static_cast<const btConvexShape*>(body0Wrap->getCollisionShape());
const btConvexShape* min1 = static_cast<const btConvexShape*>(body1Wrap->getCollisionShape());
btVector3 normalOnB;
btVector3 pointOnBWorld;
btGjkPairDetector::ClosestPointInput input;
btVoronoiSimplexSolver vs;
btGjkEpaPenetrationDepthSolver epa;
if (gUseMprCollisionFunction)
{
btMprConvexWrap a,b;
a.m_worldTrans = body0Wrap->getWorldTransform();
b.m_worldTrans = body1Wrap->getWorldTransform();
a.m_convex = (const btConvexShape*)body0Wrap->getCollisionShape();
b.m_convex = (const btConvexShape*)body1Wrap->getCollisionShape();
btVoronoiSimplexSolver simplexSolver;
simplexSolver.reset();
btGjkCollisionDescription colDesc;
btMyDistanceInfo distInfo;
int res = btComputeGjkDistance(a,b,colDesc,&distInfo);
if (res==0)
{
//printf("use GJK results in distance %f\n",distInfo.m_distance);
} else
{
btMprCollisionDescription mprDesc;
res = btComputeMprPenetration(a,b,mprDesc, &distInfo);
//printf("use MPR results in distance %f\n",distInfo.m_distance);
}
if (res == 0)
{
#if 0
printf("Dist=%f,normalOnB[%f,%f,%f],pA=[%f,%f,%f],pB[%f,%f,%f]\n",
distInfo.m_distance, distInfo.m_normalBtoA[0], distInfo.m_normalBtoA[1], distInfo.m_normalBtoA[2],
distInfo.m_pointOnA[0], distInfo.m_pointOnA[1], distInfo.m_pointOnA[2],
distInfo.m_pointOnB[0], distInfo.m_pointOnB[1], distInfo.m_pointOnB[2]);
#endif
if (distInfo.m_distance<=0)
{
resultOut->addContactPoint(distInfo.m_normalBtoA, distInfo.m_pointOnB, distInfo.m_distance);
}
//ASSERT_EQ(0,result);
//ASSERT_NEAR(btFabs(btScalar(i-z))-btScalar(j)-ssd.m_radiusB, distInfo.m_distance, abs_error);
//btVector3 computedA = distInfo.m_pointOnB+distInfo.m_distance*distInfo.m_normalBtoA;
//ASSERT_NEAR(computedA.x(),distInfo.m_pointOnA.x(),abs_error);
//ASSERT_NEAR(computedA.y(),distInfo.m_pointOnA.y(),abs_error);
//ASSERT_NEAR(computedA.z(),distInfo.m_pointOnA.z(),abs_error);
}
#if 0
btCollisionDescription colDesc;
colDesc.m_objA = min0;
colDesc.m_objB = min1;
colDesc.m_localSupportFuncA = &btBulletShapeSupportFunc;
colDesc.m_localSupportFuncB = &btBulletShapeSupportFunc;
colDesc.m_localOriginFuncA = &btBulletShapeCenterFunc;
colDesc.m_localOriginFuncB = &btBulletShapeCenterFunc;
colDesc.m_transformA = body0Wrap->getWorldTransform();
colDesc.m_transformB = body1Wrap->getWorldTransform();
colDesc.m_marginA = body0Wrap->getCollisionShape()->getMargin();
colDesc.m_marginB = body1Wrap->getCollisionShape()->getMargin();
btDistanceInfo distInfo;
//int result = btComputeGjkEpaPenetration(colDesc, &distInfo);
//int result = btComputeGjkEpaPenetration2(colDesc, &distInfo);
int result = btComputeMprPenetration(colDesc, &distInfo);
if (result==0)
{
resultOut->addContactPoint(distInfo.m_normalBtoA,distInfo.m_pointOnB,distInfo.m_distance);
}
//bool res = b3MprPenetration(pairIndex,bodyIndexA,bodyIndexB,cpuBodyBuf,convexData,collidable2,cpuVertices,sepAxis,hasSepAxis,depthOut,dirOut,posOut);
/*btCollisionDescription colDesc;
btDistanceInfo distInfo;
int btComputeGjkEpaPenetration(min0, min1, &colDesc, &distInfo);
*/
#endif
} else
{
btGjkPairDetector gjkPairDetector(min0,min1,&vs,&epa);//m_simplexSolver,m_pdSolver);
//TODO: if (dispatchInfo.m_useContinuous)
gjkPairDetector.setMinkowskiA(min0);
gjkPairDetector.setMinkowskiB(min1);
{
//if (dispatchInfo.m_convexMaxDistanceUseCPT)
//{
// input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() + m_manifoldPtr->getContactProcessingThreshold();
//} else
//{
input.m_maximumDistanceSquared = min0->getMargin() + min1->getMargin() + m_manifoldPtr->getContactBreakingThreshold();
// }
input.m_maximumDistanceSquared*= input.m_maximumDistanceSquared;
}
input.m_transformA = body0Wrap->getWorldTransform();
input.m_transformB = body1Wrap->getWorldTransform();
gjkPairDetector.getClosestPoints(input,*resultOut,dispatchInfo.m_debugDraw);
}
if (m_ownManifold)
{
resultOut->refreshContactPoints();
}
}
btScalar btConvexConvexMprAlgorithm::calculateTimeOfImpact(btCollisionObject* col0,btCollisionObject* col1,const btDispatcherInfo& dispatchInfo,btManifoldResult* resultOut)
{
(void)resultOut;
(void)dispatchInfo;
btAssert(0);
return 0;
}

View File

@@ -0,0 +1,87 @@
/*
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_CONVEX_CONVEX_MPR_ALGORITHM_H
#define BT_CONVEX_CONVEX_MPR_ALGORITHM_H
#include "BulletCollision/CollisionDispatch/btActivatingCollisionAlgorithm.h"
#include "BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
#include "BulletCollision/BroadphaseCollision/btBroadphaseProxy.h"
#include "BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h"
#include "BulletCollision/CollisionDispatch/btCollisionCreateFunc.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "LinearMath/btTransformUtil.h" //for btConvexSeparatingDistanceUtil
class btConvexPenetrationDepthSolver;
///Enabling USE_SEPDISTANCE_UTIL2 requires 100% reliable distance computation. However, when using large size ratios GJK can be imprecise
///so the distance is not conservative. In that case, enabling this USE_SEPDISTANCE_UTIL2 would result in failing/missing collisions.
///Either improve GJK for large size ratios (testing a 100 units versus a 0.1 unit object) or only enable the util
///for certain pairs that have a small size ratio
///The convexConvexAlgorithm collision algorithm implements time of impact, convex closest points and penetration depth calculations between two convex objects.
///Multiple contact points are calculated by perturbing the orientation of the smallest object orthogonal to the separating normal.
///This idea was described by Gino van den Bergen in this forum topic http://www.bulletphysics.com/Bullet/phpBB3/viewtopic.php?f=4&t=288&p=888#p888
class btConvexConvexMprAlgorithm : public btActivatingCollisionAlgorithm
{
bool m_ownManifold;
btPersistentManifold* m_manifoldPtr;
///cache separating vector to speedup collision detection
public:
btConvexConvexMprAlgorithm(btPersistentManifold* mf,const btCollisionAlgorithmConstructionInfo& ci,const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap);
virtual ~btConvexConvexMprAlgorithm();
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)
{
///should we use m_ownManifold to avoid adding duplicates?
if (m_manifoldPtr && m_ownManifold)
manifoldArray.push_back(m_manifoldPtr);
}
const btPersistentManifold* getManifold()
{
return m_manifoldPtr;
}
struct CreateFunc :public btCollisionAlgorithmCreateFunc
{
CreateFunc();
virtual ~CreateFunc();
virtual btCollisionAlgorithm* CreateCollisionAlgorithm(btCollisionAlgorithmConstructionInfo& ci, const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap)
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(btConvexConvexMprAlgorithm));
return new(mem) btConvexConvexMprAlgorithm(ci.m_manifold,ci,body0Wrap,body1Wrap);
}
};
};
#endif //BT_CONVEX_CONVEX_MPR_ALGORITHM_H