1 /*
2 Bullet Continuous Collision Detection and Physics Library
3 Copyright (c) 2003-2006 Erwin Coumans  https://bulletphysics.org
4 
5 This software is provided 'as-is', without any express or implied warranty.
6 In no event will the authors be held liable for any damages arising from the use of this software.
7 Permission is granted to anyone to use this software for any purpose,
8 including commercial applications, and to alter it and redistribute it freely,
9 subject to the following restrictions:
10 
11 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.
12 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
13 3. This notice may not be removed or altered from any source distribution.
14 */
15 /*
16 Voronoi fracture and shatter code and demo copyright (c) 2011 Alain Ducharme
17   - Reset scene (press spacebar) to generate new random voronoi shattered cuboids
18   - Check console for total time required to: compute and mesh all 3D shards, calculate volumes and centers of mass and create rigid bodies
19   - Modify VORONOIPOINTS define below to change number of potential voronoi shards
20   - Note that demo's visual cracks between voronoi shards are NOT present in the internally generated voronoi mesh!
21 */
22 
23 //Number of random voronoi points to generate for shattering
24 #define VORONOIPOINTS 100
25 
26 //maximum number of objects (and allow user to shoot additional boxes)
27 #define MAX_PROXIES (2048)
28 #define BREAKING_THRESHOLD 3
29 #define CONVEX_MARGIN 0.04
30 static int useMpr = 0;
31 
32 #include "VoronoiFractureDemo.h"
33 
34 ///btBulletDynamicsCommon.h is the main Bullet include file, contains most common include files.
35 #include "btBulletDynamicsCommon.h"
36 #include <stdio.h>  //printf debugging
37 
38 static bool useGenericConstraint = false;
39 
40 #include "btConvexConvexMprAlgorithm.h"
41 
42 #include "LinearMath/btAlignedObjectArray.h"
43 #include "LinearMath/btConvexHullComputer.h"
44 #include "LinearMath/btQuaternion.h"
45 #include <set>
46 #include <time.h>
47 
48 class btBroadphaseInterface;
49 class btCollisionShape;
50 class btOverlappingPairCache;
51 class btCollisionDispatcher;
52 class btConstraintSolver;
53 struct btCollisionAlgorithmCreateFunc;
54 class btDefaultCollisionConfiguration;
55 
56 #include "../CommonInterfaces/CommonRigidBodyBase.h"
57 
58 class VoronoiFractureDemo : public CommonRigidBodyBase
59 {
60 	//keep the collision shapes, for deletion/cleanup
61 	btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
62 
63 	btBroadphaseInterface* m_broadphase;
64 
65 	btCollisionDispatcher* m_dispatcher;
66 
67 	btConstraintSolver* m_solver;
68 
69 	btDefaultCollisionConfiguration* m_collisionConfiguration;
70 
71 	btClock m_perfmTimer;
72 
73 public:
VoronoiFractureDemo(struct GUIHelperInterface * helper)74 	VoronoiFractureDemo(struct GUIHelperInterface* helper)
75 		: CommonRigidBodyBase(helper)
76 	{
77 		srand((unsigned)time(NULL));  // Seed it...
78 	}
~VoronoiFractureDemo()79 	virtual ~VoronoiFractureDemo()
80 	{
81 		btAssert(m_dynamicsWorld == 0);
82 	}
83 
84 	void initPhysics();
85 
86 	void exitPhysics();
87 
88 	//virtual void renderme();
89 
90 	void getVerticesInsidePlanes(const btAlignedObjectArray<btVector3>& planes, btAlignedObjectArray<btVector3>& verticesOut, std::set<int>& planeIndicesOut);
91 	void voronoiBBShatter(const btAlignedObjectArray<btVector3>& points, const btVector3& bbmin, const btVector3& bbmax, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity);
92 	void voronoiConvexHullShatter(const btAlignedObjectArray<btVector3>& points, const btAlignedObjectArray<btVector3>& verts, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity);
93 
94 	//virtual void clientMoveAndDisplay();
95 
96 	//virtual void displayCallback();
97 	//virtual void	clientResetScene();
98 
99 	//virtual void keyboardCallback(unsigned char key, int x, int y);
100 
101 	void attachFixedConstraints();
102 
resetCamera()103 	virtual void resetCamera()
104 	{
105 		float dist = 18;
106 		float pitch = -30;
107 		float yaw = 129;
108 		float targetPos[3] = {-1.5, 4.7, -2};
109 		m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
110 	}
111 };
112 
attachFixedConstraints()113 void VoronoiFractureDemo::attachFixedConstraints()
114 {
115 	btAlignedObjectArray<btRigidBody*> bodies;
116 
117 	int numManifolds = m_dynamicsWorld->getDispatcher()->getNumManifolds();
118 
119 	for (int i = 0; i < numManifolds; i++)
120 	{
121 		btPersistentManifold* manifold = m_dynamicsWorld->getDispatcher()->getManifoldByIndexInternal(i);
122 		if (!manifold->getNumContacts())
123 			continue;
124 
125 		btScalar minDist = 1e30f;
126 		int minIndex = -1;
127 		for (int v = 0; v < manifold->getNumContacts(); v++)
128 		{
129 			if (minDist > manifold->getContactPoint(v).getDistance())
130 			{
131 				minDist = manifold->getContactPoint(v).getDistance();
132 				minIndex = v;
133 			}
134 		}
135 		if (minDist > 0.)
136 			continue;
137 
138 		btCollisionObject* colObj0 = (btCollisionObject*)manifold->getBody0();
139 		btCollisionObject* colObj1 = (btCollisionObject*)manifold->getBody1();
140 		//	int tag0 = (colObj0)->getIslandTag();
141 		//		int tag1 = (colObj1)->getIslandTag();
142 		btRigidBody* body0 = btRigidBody::upcast(colObj0);
143 		btRigidBody* body1 = btRigidBody::upcast(colObj1);
144 		if (bodies.findLinearSearch(body0) == bodies.size())
145 			bodies.push_back(body0);
146 		if (bodies.findLinearSearch(body1) == bodies.size())
147 			bodies.push_back(body1);
148 
149 		if (body0 && body1)
150 		{
151 			if (!colObj0->isStaticOrKinematicObject() && !colObj1->isStaticOrKinematicObject())
152 			{
153 				if (body0->checkCollideWithOverride(body1))
154 				{
155 					{
156 						btTransform trA, trB;
157 						trA.setIdentity();
158 						trB.setIdentity();
159 						btVector3 contactPosWorld = manifold->getContactPoint(minIndex).m_positionWorldOnA;
160 						btTransform globalFrame;
161 						globalFrame.setIdentity();
162 						globalFrame.setOrigin(contactPosWorld);
163 
164 						trA = body0->getWorldTransform().inverse() * globalFrame;
165 						trB = body1->getWorldTransform().inverse() * globalFrame;
166 						float totalMass = 1.f / body0->getInvMass() + 1.f / body1->getInvMass();
167 
168 						if (useGenericConstraint)
169 						{
170 							btGeneric6DofConstraint* dof6 = new btGeneric6DofConstraint(*body0, *body1, trA, trB, true);
171 							dof6->setOverrideNumSolverIterations(30);
172 
173 							dof6->setBreakingImpulseThreshold(BREAKING_THRESHOLD * totalMass);
174 
175 							for (int i = 0; i < 6; i++)
176 								dof6->setLimit(i, 0, 0);
177 							m_dynamicsWorld->addConstraint(dof6, true);
178 						}
179 						else
180 						{
181 							btFixedConstraint* fixed = new btFixedConstraint(*body0, *body1, trA, trB);
182 							fixed->setBreakingImpulseThreshold(BREAKING_THRESHOLD * totalMass);
183 							fixed->setOverrideNumSolverIterations(30);
184 							m_dynamicsWorld->addConstraint(fixed, true);
185 						}
186 					}
187 				}
188 			}
189 		}
190 	}
191 
192 	for (int i = 0; i < bodies.size(); i++)
193 	{
194 		m_dynamicsWorld->removeRigidBody(bodies[i]);
195 		m_dynamicsWorld->addRigidBody(bodies[i]);
196 	}
197 }
198 /*
199 void VoronoiFractureDemo::keyboardCallback(unsigned char key, int x, int y)
200 {
201 	if (key == 'g')
202 	{
203 		attachFixedConstraints();
204 	}else
205 	{
206 		PlatformDemoApplication::keyboardCallback(key,x,y);
207 	}
208 }
209 */
210 
getVerticesInsidePlanes(const btAlignedObjectArray<btVector3> & planes,btAlignedObjectArray<btVector3> & verticesOut,std::set<int> & planeIndicesOut)211 void VoronoiFractureDemo::getVerticesInsidePlanes(const btAlignedObjectArray<btVector3>& planes, btAlignedObjectArray<btVector3>& verticesOut, std::set<int>& planeIndicesOut)
212 {
213 	// Based on btGeometryUtil.cpp (Gino van den Bergen / Erwin Coumans)
214 	verticesOut.resize(0);
215 	planeIndicesOut.clear();
216 	const int numPlanes = planes.size();
217 	int i, j, k, l;
218 	for (i = 0; i < numPlanes; i++)
219 	{
220 		const btVector3& N1 = planes[i];
221 		for (j = i + 1; j < numPlanes; j++)
222 		{
223 			const btVector3& N2 = planes[j];
224 			btVector3 n1n2 = N1.cross(N2);
225 			if (n1n2.length2() > btScalar(0.0001))
226 			{
227 				for (k = j + 1; k < numPlanes; k++)
228 				{
229 					const btVector3& N3 = planes[k];
230 					btVector3 n2n3 = N2.cross(N3);
231 					btVector3 n3n1 = N3.cross(N1);
232 					if ((n2n3.length2() > btScalar(0.0001)) && (n3n1.length2() > btScalar(0.0001)))
233 					{
234 						btScalar quotient = (N1.dot(n2n3));
235 						if (btFabs(quotient) > btScalar(0.0001))
236 						{
237 							btVector3 potentialVertex = (n2n3 * N1[3] + n3n1 * N2[3] + n1n2 * N3[3]) * (btScalar(-1.) / quotient);
238 							for (l = 0; l < numPlanes; l++)
239 							{
240 								const btVector3& NP = planes[l];
241 								if (btScalar(NP.dot(potentialVertex)) + btScalar(NP[3]) > btScalar(0.000001))
242 									break;
243 							}
244 							if (l == numPlanes)
245 							{
246 								// vertex (three plane intersection) inside all planes
247 								verticesOut.push_back(potentialVertex);
248 								planeIndicesOut.insert(i);
249 								planeIndicesOut.insert(j);
250 								planeIndicesOut.insert(k);
251 							}
252 						}
253 					}
254 				}
255 			}
256 		}
257 	}
258 }
259 
260 static btVector3 curVoronoiPoint;
261 
262 struct pointCmp
263 {
operator ()pointCmp264 	bool operator()(const btVector3& p1, const btVector3& p2) const
265 	{
266 		float v1 = (p1 - curVoronoiPoint).length2();
267 		float v2 = (p2 - curVoronoiPoint).length2();
268 		bool result0 = v1 < v2;
269 		//bool result1 = ((btScalar)(p1-curVoronoiPoint).length2()) < ((btScalar)(p2-curVoronoiPoint).length2());
270 		//apparently result0 is not always result1, because extended precision used in registered is different from precision when values are stored in memory
271 		return result0;
272 	}
273 };
274 
voronoiBBShatter(const btAlignedObjectArray<btVector3> & points,const btVector3 & bbmin,const btVector3 & bbmax,const btQuaternion & bbq,const btVector3 & bbt,btScalar matDensity)275 void VoronoiFractureDemo::voronoiBBShatter(const btAlignedObjectArray<btVector3>& points, const btVector3& bbmin, const btVector3& bbmax, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity)
276 {
277 	// points define voronoi cells in world space (avoid duplicates)
278 	// bbmin & bbmax = bounding box min and max in local space
279 	// bbq & bbt = bounding box quaternion rotation and translation
280 	// matDensity = Material density for voronoi shard mass calculation
281 	btVector3 bbvx = quatRotate(bbq, btVector3(1.0, 0.0, 0.0));
282 	btVector3 bbvy = quatRotate(bbq, btVector3(0.0, 1.0, 0.0));
283 	btVector3 bbvz = quatRotate(bbq, btVector3(0.0, 0.0, 1.0));
284 	btQuaternion bbiq = bbq.inverse();
285 	btConvexHullComputer* convexHC = new btConvexHullComputer();
286 	btAlignedObjectArray<btVector3> vertices;
287 	btVector3 rbb, nrbb;
288 	btScalar nlength, maxDistance, distance;
289 	btAlignedObjectArray<btVector3> sortedVoronoiPoints;
290 	sortedVoronoiPoints.copyFromArray(points);
291 	btVector3 normal, plane;
292 	btAlignedObjectArray<btVector3> planes;
293 	std::set<int> planeIndices;
294 	std::set<int>::iterator planeIndicesIter;
295 	int numplaneIndices;
296 	int cellnum = 0;
297 	int i, j, k;
298 
299 	int numpoints = points.size();
300 	for (i = 0; i < numpoints; i++)
301 	{
302 		curVoronoiPoint = points[i];
303 		btVector3 icp = quatRotate(bbiq, curVoronoiPoint - bbt);
304 		rbb = icp - bbmax;
305 		nrbb = bbmin - icp;
306 		planes.resize(6);
307 		planes[0] = bbvx;
308 		planes[0][3] = rbb.x();
309 		planes[1] = bbvy;
310 		planes[1][3] = rbb.y();
311 		planes[2] = bbvz;
312 		planes[2][3] = rbb.z();
313 		planes[3] = -bbvx;
314 		planes[3][3] = nrbb.x();
315 		planes[4] = -bbvy;
316 		planes[4][3] = nrbb.y();
317 		planes[5] = -bbvz;
318 		planes[5][3] = nrbb.z();
319 		maxDistance = SIMD_INFINITY;
320 		sortedVoronoiPoints.heapSort(pointCmp());
321 		for (j = 1; j < numpoints; j++)
322 		{
323 			normal = sortedVoronoiPoints[j] - curVoronoiPoint;
324 			nlength = normal.length();
325 			if (nlength > maxDistance)
326 				break;
327 			plane = normal.normalized();
328 			plane[3] = -nlength / btScalar(2.);
329 			planes.push_back(plane);
330 			getVerticesInsidePlanes(planes, vertices, planeIndices);
331 			if (vertices.size() == 0)
332 				break;
333 			numplaneIndices = planeIndices.size();
334 			if (numplaneIndices != planes.size())
335 			{
336 				planeIndicesIter = planeIndices.begin();
337 				for (k = 0; k < numplaneIndices; k++)
338 				{
339 					if (k != *planeIndicesIter)
340 						planes[k] = planes[*planeIndicesIter];
341 					planeIndicesIter++;
342 				}
343 				planes.resize(numplaneIndices);
344 			}
345 			maxDistance = vertices[0].length();
346 			for (k = 1; k < vertices.size(); k++)
347 			{
348 				distance = vertices[k].length();
349 				if (maxDistance < distance)
350 					maxDistance = distance;
351 			}
352 			maxDistance *= btScalar(2.);
353 		}
354 		if (vertices.size() == 0)
355 			continue;
356 
357 		// Clean-up voronoi convex shard vertices and generate edges & faces
358 		convexHC->compute(&vertices[0].getX(), sizeof(btVector3), vertices.size(), CONVEX_MARGIN, 0.0);
359 
360 		// At this point we have a complete 3D voronoi shard mesh contained in convexHC
361 
362 		// Calculate volume and center of mass (Stan Melax volume integration)
363 		int numFaces = convexHC->faces.size();
364 		int v0, v1, v2;  // Triangle vertices
365 		btScalar volume = btScalar(0.);
366 		btVector3 com(0., 0., 0.);
367 		for (j = 0; j < numFaces; j++)
368 		{
369 			const btConvexHullComputer::Edge* edge = &convexHC->edges[convexHC->faces[j]];
370 			v0 = edge->getSourceVertex();
371 			v1 = edge->getTargetVertex();
372 			edge = edge->getNextEdgeOfFace();
373 			v2 = edge->getTargetVertex();
374 			while (v2 != v0)
375 			{
376 				// Counter-clockwise triangulated voronoi shard mesh faces (v0-v1-v2) and edges here...
377 				btScalar vol = convexHC->vertices[v0].triple(convexHC->vertices[v1], convexHC->vertices[v2]);
378 				volume += vol;
379 				com += vol * (convexHC->vertices[v0] + convexHC->vertices[v1] + convexHC->vertices[v2]);
380 				edge = edge->getNextEdgeOfFace();
381 				v1 = v2;
382 				v2 = edge->getTargetVertex();
383 			}
384 		}
385 		com /= volume * btScalar(4.);
386 		volume /= btScalar(6.);
387 
388 		// Shift all vertices relative to center of mass
389 		int numVerts = convexHC->vertices.size();
390 		for (j = 0; j < numVerts; j++)
391 		{
392 			convexHC->vertices[j] -= com;
393 		}
394 
395 		// Note:
396 		// At this point convex hulls contained in convexHC should be accurate (line up flush with other pieces, no cracks),
397 		// ...however Bullet Physics rigid bodies demo visualizations appear to produce some visible cracks.
398 		// Use the mesh in convexHC for visual display or to perform boolean operations with.
399 
400 		// Create Bullet Physics rigid body shards
401 		btCollisionShape* shardShape = new btConvexHullShape(&(convexHC->vertices[0].getX()), convexHC->vertices.size());
402 		shardShape->setMargin(CONVEX_MARGIN);  // for this demo; note convexHC has optional margin parameter for this
403 		m_collisionShapes.push_back(shardShape);
404 		btTransform shardTransform;
405 		shardTransform.setIdentity();
406 		shardTransform.setOrigin(curVoronoiPoint + com);  // Shard's adjusted location
407 		btDefaultMotionState* shardMotionState = new btDefaultMotionState(shardTransform);
408 		btScalar shardMass(volume * matDensity);
409 		btVector3 shardInertia(0., 0., 0.);
410 		shardShape->calculateLocalInertia(shardMass, shardInertia);
411 		btRigidBody::btRigidBodyConstructionInfo shardRBInfo(shardMass, shardMotionState, shardShape, shardInertia);
412 		btRigidBody* shardBody = new btRigidBody(shardRBInfo);
413 		m_dynamicsWorld->addRigidBody(shardBody);
414 
415 		cellnum++;
416 	}
417 	printf("Generated %d voronoi btRigidBody shards\n", cellnum);
418 }
419 
voronoiConvexHullShatter(const btAlignedObjectArray<btVector3> & points,const btAlignedObjectArray<btVector3> & verts,const btQuaternion & bbq,const btVector3 & bbt,btScalar matDensity)420 void VoronoiFractureDemo::voronoiConvexHullShatter(const btAlignedObjectArray<btVector3>& points, const btAlignedObjectArray<btVector3>& verts, const btQuaternion& bbq, const btVector3& bbt, btScalar matDensity)
421 {
422 	// points define voronoi cells in world space (avoid duplicates)
423 	// verts = source (convex hull) mesh vertices in local space
424 	// bbq & bbt = source (convex hull) mesh quaternion rotation and translation
425 	// matDensity = Material density for voronoi shard mass calculation
426 	btConvexHullComputer* convexHC = new btConvexHullComputer();
427 	btAlignedObjectArray<btVector3> vertices, chverts;
428 	btVector3 rbb, nrbb;
429 	btScalar nlength, maxDistance, distance;
430 	btAlignedObjectArray<btVector3> sortedVoronoiPoints;
431 	sortedVoronoiPoints.copyFromArray(points);
432 	btVector3 normal, plane;
433 	btAlignedObjectArray<btVector3> planes, convexPlanes;
434 	std::set<int> planeIndices;
435 	std::set<int>::iterator planeIndicesIter;
436 	int numplaneIndices;
437 	int cellnum = 0;
438 	int i, j, k;
439 
440 	// Convert verts to world space and get convexPlanes
441 	int numverts = verts.size();
442 	chverts.resize(verts.size());
443 	for (i = 0; i < numverts; i++)
444 	{
445 		chverts[i] = quatRotate(bbq, verts[i]) + bbt;
446 	}
447 	//btGeometryUtil::getPlaneEquationsFromVertices(chverts, convexPlanes);
448 	// Using convexHullComputer faster than getPlaneEquationsFromVertices for large meshes...
449 	convexHC->compute(&chverts[0].getX(), sizeof(btVector3), numverts, 0.0, 0.0);
450 	int numFaces = convexHC->faces.size();
451 	int v0, v1, v2;  // vertices
452 	for (i = 0; i < numFaces; i++)
453 	{
454 		const btConvexHullComputer::Edge* edge = &convexHC->edges[convexHC->faces[i]];
455 		v0 = edge->getSourceVertex();
456 		v1 = edge->getTargetVertex();
457 		edge = edge->getNextEdgeOfFace();
458 		v2 = edge->getTargetVertex();
459 		plane = (convexHC->vertices[v1] - convexHC->vertices[v0]).cross(convexHC->vertices[v2] - convexHC->vertices[v0]).normalize();
460 		plane[3] = -plane.dot(convexHC->vertices[v0]);
461 		convexPlanes.push_back(plane);
462 	}
463 	const int numconvexPlanes = convexPlanes.size();
464 
465 	int numpoints = points.size();
466 	for (i = 0; i < numpoints; i++)
467 	{
468 		curVoronoiPoint = points[i];
469 		planes.copyFromArray(convexPlanes);
470 		for (j = 0; j < numconvexPlanes; j++)
471 		{
472 			planes[j][3] += planes[j].dot(curVoronoiPoint);
473 		}
474 		maxDistance = SIMD_INFINITY;
475 		sortedVoronoiPoints.heapSort(pointCmp());
476 		for (j = 1; j < numpoints; j++)
477 		{
478 			normal = sortedVoronoiPoints[j] - curVoronoiPoint;
479 			nlength = normal.length();
480 			if (nlength > maxDistance)
481 				break;
482 			plane = normal.normalized();
483 			plane[3] = -nlength / btScalar(2.);
484 			planes.push_back(plane);
485 			getVerticesInsidePlanes(planes, vertices, planeIndices);
486 			if (vertices.size() == 0)
487 				break;
488 			numplaneIndices = planeIndices.size();
489 			if (numplaneIndices != planes.size())
490 			{
491 				planeIndicesIter = planeIndices.begin();
492 				for (k = 0; k < numplaneIndices; k++)
493 				{
494 					if (k != *planeIndicesIter)
495 						planes[k] = planes[*planeIndicesIter];
496 					planeIndicesIter++;
497 				}
498 				planes.resize(numplaneIndices);
499 			}
500 			maxDistance = vertices[0].length();
501 			for (k = 1; k < vertices.size(); k++)
502 			{
503 				distance = vertices[k].length();
504 				if (maxDistance < distance)
505 					maxDistance = distance;
506 			}
507 			maxDistance *= btScalar(2.);
508 		}
509 		if (vertices.size() == 0)
510 			continue;
511 
512 		// Clean-up voronoi convex shard vertices and generate edges & faces
513 		convexHC->compute(&vertices[0].getX(), sizeof(btVector3), vertices.size(), 0.0, 0.0);
514 
515 		// At this point we have a complete 3D voronoi shard mesh contained in convexHC
516 
517 		// Calculate volume and center of mass (Stan Melax volume integration)
518 		numFaces = convexHC->faces.size();
519 		btScalar volume = btScalar(0.);
520 		btVector3 com(0., 0., 0.);
521 		for (j = 0; j < numFaces; j++)
522 		{
523 			const btConvexHullComputer::Edge* edge = &convexHC->edges[convexHC->faces[j]];
524 			v0 = edge->getSourceVertex();
525 			v1 = edge->getTargetVertex();
526 			edge = edge->getNextEdgeOfFace();
527 			v2 = edge->getTargetVertex();
528 			while (v2 != v0)
529 			{
530 				// Counter-clockwise triangulated voronoi shard mesh faces (v0-v1-v2) and edges here...
531 				btScalar vol = convexHC->vertices[v0].triple(convexHC->vertices[v1], convexHC->vertices[v2]);
532 				volume += vol;
533 				com += vol * (convexHC->vertices[v0] + convexHC->vertices[v1] + convexHC->vertices[v2]);
534 				edge = edge->getNextEdgeOfFace();
535 				v1 = v2;
536 				v2 = edge->getTargetVertex();
537 			}
538 		}
539 		com /= volume * btScalar(4.);
540 		volume /= btScalar(6.);
541 
542 		// Shift all vertices relative to center of mass
543 		int numVerts = convexHC->vertices.size();
544 		for (j = 0; j < numVerts; j++)
545 		{
546 			convexHC->vertices[j] -= com;
547 		}
548 
549 		// Note:
550 		// At this point convex hulls contained in convexHC should be accurate (line up flush with other pieces, no cracks),
551 		// ...however Bullet Physics rigid bodies demo visualizations appear to produce some visible cracks.
552 		// Use the mesh in convexHC for visual display or to perform boolean operations with.
553 
554 		// Create Bullet Physics rigid body shards
555 		btCollisionShape* shardShape = new btConvexHullShape(&(convexHC->vertices[0].getX()), convexHC->vertices.size());
556 		shardShape->setMargin(CONVEX_MARGIN);  // for this demo; note convexHC has optional margin parameter for this
557 		m_collisionShapes.push_back(shardShape);
558 		btTransform shardTransform;
559 		shardTransform.setIdentity();
560 		shardTransform.setOrigin(curVoronoiPoint + com);  // Shard's adjusted location
561 		btDefaultMotionState* shardMotionState = new btDefaultMotionState(shardTransform);
562 		btScalar shardMass(volume * matDensity);
563 		btVector3 shardInertia(0., 0., 0.);
564 		shardShape->calculateLocalInertia(shardMass, shardInertia);
565 		btRigidBody::btRigidBodyConstructionInfo shardRBInfo(shardMass, shardMotionState, shardShape, shardInertia);
566 		btRigidBody* shardBody = new btRigidBody(shardRBInfo);
567 		m_dynamicsWorld->addRigidBody(shardBody);
568 
569 		cellnum++;
570 	}
571 	printf("Generated %d voronoi btRigidBody shards\n", cellnum);
572 }
573 
574 /*
575 void VoronoiFractureDemo::clientMoveAndDisplay()
576 {
577 	glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
578 
579 	//simple dynamics world doesn't handle fixed-time-stepping
580 	float ms = getDeltaTimeMicroseconds();
581 
582 	///step the simulation
583 	if (m_dynamicsWorld)
584 	{
585 		m_dynamicsWorld->stepSimulation(1. / 60., 0);// ms / 1000000.f);
586 		//optional but useful: debug drawing
587 		m_dynamicsWorld->debugDrawWorld();
588 	}
589 
590 	renderme();
591 
592 	glFlush();
593 
594 	swapBuffers();
595 }
596 */
597 /*
598 void VoronoiFractureDemo::displayCallback(void) {
599 
600 	glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
601 
602 	renderme();
603 
604 	//optional but useful: debug drawing to detect problems
605 	if (m_dynamicsWorld)
606 		m_dynamicsWorld->debugDrawWorld();
607 
608 	glFlush();
609 	swapBuffers();
610 }
611 */
612 /*
613 void VoronoiFractureDemo::renderme()
614 {
615 	DemoApplication::renderme();
616 	char buf[124];
617 
618 	int lineWidth = 200;
619 	int xStart = m_glutScreenWidth - lineWidth;
620 
621 	if (useMpr)
622 	{
623 		sprintf(buf, "Using GJK+MPR");
624 	}
625 	else
626 	{
627 		sprintf(buf, "Using GJK+EPA");
628 	}
629 	GLDebugDrawString(xStart, 20, buf);
630 
631 }
632 */
633 
initPhysics()634 void VoronoiFractureDemo::initPhysics()
635 {
636 	m_guiHelper->setUpAxis(1);
637 
638 	srand(13);
639 	useGenericConstraint = !useGenericConstraint;
640 	printf("useGenericConstraint = %d\n", useGenericConstraint);
641 
642 	///collision configuration contains default setup for memory, collision setup
643 	m_collisionConfiguration = new btDefaultCollisionConfiguration();
644 	//m_collisionConfiguration->setConvexConvexMultipointIterations();
645 
646 	///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
647 	m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
648 
649 	useMpr = 1 - useMpr;
650 
651 	if (useMpr)
652 	{
653 		printf("using GJK+MPR convex-convex collision detection\n");
654 		btConvexConvexMprAlgorithm::CreateFunc* cf = new btConvexConvexMprAlgorithm::CreateFunc;
655 		m_dispatcher->registerCollisionCreateFunc(CONVEX_HULL_SHAPE_PROXYTYPE, CONVEX_HULL_SHAPE_PROXYTYPE, cf);
656 		m_dispatcher->registerCollisionCreateFunc(CONVEX_HULL_SHAPE_PROXYTYPE, BOX_SHAPE_PROXYTYPE, cf);
657 		m_dispatcher->registerCollisionCreateFunc(BOX_SHAPE_PROXYTYPE, CONVEX_HULL_SHAPE_PROXYTYPE, cf);
658 	}
659 	else
660 	{
661 		printf("using default (GJK+EPA) convex-convex collision detection\n");
662 	}
663 
664 	m_broadphase = new btDbvtBroadphase();
665 
666 	///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
667 	btSequentialImpulseConstraintSolver* sol = new btSequentialImpulseConstraintSolver;
668 	m_solver = sol;
669 
670 	m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher, m_broadphase, m_solver, m_collisionConfiguration);
671 	m_dynamicsWorld->getSolverInfo().m_splitImpulse = true;
672 
673 	m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
674 
675 	m_dynamicsWorld->setGravity(btVector3(0, -10, 0));
676 
677 	///create a few basic rigid bodies
678 	btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.), btScalar(50.), btScalar(50.)));
679 	//	btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),50);
680 
681 	m_collisionShapes.push_back(groundShape);
682 
683 	btTransform groundTransform;
684 	groundTransform.setIdentity();
685 	groundTransform.setOrigin(btVector3(0, -50, 0));
686 
687 	//We can also use DemoApplication::localCreateRigidBody, but for clarity it is provided here:
688 	{
689 		btScalar mass(0.);
690 
691 		//rigidbody is dynamic if and only if mass is non zero, otherwise static
692 		bool isDynamic = (mass != 0.f);
693 
694 		btVector3 localInertia(0, 0, 0);
695 		if (isDynamic)
696 			groundShape->calculateLocalInertia(mass, localInertia);
697 
698 		//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
699 		btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
700 		btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
701 		btRigidBody* body = new btRigidBody(rbInfo);
702 
703 		//add the body to the dynamics world
704 		m_dynamicsWorld->addRigidBody(body);
705 	}
706 
707 	{
708 		btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(10.), btScalar(8.), btScalar(1.)));
709 		btScalar mass(0.);
710 
711 		//rigidbody is dynamic if and only if mass is non zero, otherwise static
712 		bool isDynamic = (mass != 0.f);
713 
714 		btVector3 localInertia(0, 0, 0);
715 		if (isDynamic)
716 			groundShape->calculateLocalInertia(mass, localInertia);
717 		groundTransform.setOrigin(btVector3(0, 0, 0));
718 		//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
719 		btDefaultMotionState* myMotionState = new btDefaultMotionState(groundTransform);
720 		btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, groundShape, localInertia);
721 		btRigidBody* body = new btRigidBody(rbInfo);
722 
723 		//add the body to the dynamics world
724 		m_dynamicsWorld->addRigidBody(body);
725 	}
726 
727 	// ==> Voronoi Shatter Basic Demo: Random Cuboid
728 
729 	// Random size cuboid (defined by bounding box max and min)
730 	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);
731 	btVector3 bbmin = -bbmax;
732 	// Place it 10 units above ground
733 	btVector3 bbt(0, 15, 0);
734 	// Use an arbitrary material density for shards (should be consitent/relative with/to rest of RBs in world)
735 	btScalar matDensity = 1;
736 	// Using random rotation
737 	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.);
738 	bbq.normalize();
739 	// Generate random points for voronoi cells
740 	btAlignedObjectArray<btVector3> points;
741 	btVector3 point;
742 	btVector3 diff = bbmax - bbmin;
743 	for (int i = 0; i < VORONOIPOINTS; i++)
744 	{
745 		// Place points within box area (points are in world coordinates)
746 		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;
747 		points.push_back(point);
748 	}
749 	m_perfmTimer.reset();
750 	voronoiBBShatter(points, bbmin, bbmax, bbq, bbt, matDensity);
751 	printf("Total Time: %f seconds\n", m_perfmTimer.getTimeMilliseconds() / 1000.);
752 
753 	for (int i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
754 	{
755 		btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
756 		obj->getCollisionShape()->setMargin(CONVEX_MARGIN + 0.01);
757 	}
758 	m_dynamicsWorld->performDiscreteCollisionDetection();
759 
760 	for (int i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
761 	{
762 		btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
763 		obj->getCollisionShape()->setMargin(CONVEX_MARGIN);
764 	}
765 
766 	attachFixedConstraints();
767 
768 	m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
769 }
770 
exitPhysics()771 void VoronoiFractureDemo::exitPhysics()
772 {
773 	//cleanup in the reverse order of creation/initialization
774 
775 	int i;
776 	//remove all constraints
777 	for (i = m_dynamicsWorld->getNumConstraints() - 1; i >= 0; i--)
778 	{
779 		btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i);
780 		m_dynamicsWorld->removeConstraint(constraint);
781 		delete constraint;
782 	}
783 
784 	//remove the rigidbodies from the dynamics world and delete them
785 
786 	for (i = m_dynamicsWorld->getNumCollisionObjects() - 1; i >= 0; i--)
787 	{
788 		btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i];
789 		btRigidBody* body = btRigidBody::upcast(obj);
790 		if (body && body->getMotionState())
791 		{
792 			delete body->getMotionState();
793 		}
794 		m_dynamicsWorld->removeCollisionObject(obj);
795 		delete obj;
796 	}
797 
798 	//delete collision shapes
799 	for (int j = 0; j < m_collisionShapes.size(); j++)
800 	{
801 		btCollisionShape* shape = m_collisionShapes[j];
802 		delete shape;
803 	}
804 	m_collisionShapes.clear();
805 
806 	delete m_dynamicsWorld;
807 	m_dynamicsWorld = 0;
808 
809 	delete m_solver;
810 	m_solver = 0;
811 
812 	delete m_broadphase;
813 	m_broadphase = 0;
814 
815 	delete m_dispatcher;
816 	m_dispatcher = 0;
817 
818 	delete m_collisionConfiguration;
819 	m_collisionConfiguration = 0;
820 }
821 
822 /*
823 static DemoApplication* Create()
824 	{
825 		VoronoiFractureDemo* demo = new VoronoiFractureDemo;
826 		demo->myinit();
827 		demo->initPhysics();
828 		return demo;
829 	}
830 
831 */
832 
VoronoiFractureCreateFunc(struct CommonExampleOptions & options)833 CommonExampleInterface* VoronoiFractureCreateFunc(struct CommonExampleOptions& options)
834 {
835 	return new VoronoiFractureDemo(options.m_guiHelper);
836 }
837