Ok been at it 3 days now i just don't get it
I need just simple code "a ball that collides with a mesh" i have looked at triangleMesh and looked at btGImpactMeshShape but all do the same thin objects don't collide with mesh it seem many people are asking this all over the net on different forums so has any one got any code i have convexHull working but as soon as i try to use another convex for map it becomes a primitive and gives square shape I just don't get it i have looked at demos too so need a simple code any c/c++/obj-c will do
void main(void){
//Code here and done
}
Many Thanks in advance
Ross.
Simple Code Required
-
- Site Admin
- Posts: 4221
- Joined: Sun Jun 26, 2005 6:43 pm
- Location: California, USA
Re: Simple Code Required
For a dynamic (moving) sphere you can add a btSphereShape to a btRigidBody. The best mesh shape type to represent the world environment that doesn't move (also known as static) is a btBvhTriangleMeshShape.
You need to set the setCcdMotionThreshold and setCcdSweptSphereRadius for small fast moving objects, to avoid missing collisions.
Also, for sphere rolling over a mesh, it is useful to set the rolling friction, so they come to rest eventually.
You need the latest Bullet trunk version (revision 2600 or later) from here: http://code.google.com/p/bullet/downloads/list
copy the code below over Bullet/Demos/ConcaveDemo/ConcavePhysicsDemo.cpp and compile/run.
Good luck,
Erwin
You need to set the setCcdMotionThreshold and setCcdSweptSphereRadius for small fast moving objects, to avoid missing collisions.
Also, for sphere rolling over a mesh, it is useful to set the rolling friction, so they come to rest eventually.
You need the latest Bullet trunk version (revision 2600 or later) from here: http://code.google.com/p/bullet/downloads/list
copy the code below over Bullet/Demos/ConcaveDemo/ConcavePhysicsDemo.cpp and compile/run.
Good luck,
Erwin
Code: Select all
/*
Bullet Continuous Collision Detection and Physics Library
Copyright (c) 2003-2012 Erwin Coumans http://bulletphysics.org
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 "btBulletDynamicsCommon.h"
#include "LinearMath/btIDebugDraw.h"
#include "GLDebugDrawer.h"
#include "ConcaveDemo.h"
#include "GL_ShapeDrawer.h"
#include "GlutStuff.h"
static btVector3* gVertices=0;
static int* gIndices=0;
static btBvhTriangleMeshShape* trimeshShape =0;
static btRigidBody* staticBody = 0;
static float waveheight = 5.f;
const float TRIANGLE_SIZE=8.f;
const int NUM_VERTS_X = 30;
const int NUM_VERTS_Y = 30;
const int totalVerts = NUM_VERTS_X*NUM_VERTS_Y;
void ConcaveDemo::setVertexPositions(float waveheight, float offset)
{
int i;
int j;
for ( i=0;i<NUM_VERTS_X;i++)
{
for (j=0;j<NUM_VERTS_Y;j++)
{
gVertices[i+j*NUM_VERTS_X].setValue((i-NUM_VERTS_X*0.5f)*TRIANGLE_SIZE,
//0.f,
waveheight*sinf((float)i+offset)*cosf((float)j+offset),
(j-NUM_VERTS_Y*0.5f)*TRIANGLE_SIZE);
}
}
}
void ConcaveDemo::keyboardCallback(unsigned char key, int x, int y)
{
DemoApplication::keyboardCallback(key,x,y);
}
void ConcaveDemo::initPhysics()
{
setCameraDistance(12.);
setTexturing(true);
setShadows(false);//true);
#define TRISIZE 10.f
///create the triangle mesh shape
int vertStride = sizeof(btVector3);
int indexStride = 3*sizeof(int);
const int totalTriangles = 2*(NUM_VERTS_X-1)*(NUM_VERTS_Y-1);
gVertices = new btVector3[totalVerts];
gIndices = new int[totalTriangles*3];
int i;
setVertexPositions(waveheight,0.f);
int index=0;
for ( i=0;i<NUM_VERTS_X-1;i++)
{
for (int j=0;j<NUM_VERTS_Y-1;j++)
{
gIndices[index++] = j*NUM_VERTS_X+i;
gIndices[index++] = j*NUM_VERTS_X+i+1;
gIndices[index++] = (j+1)*NUM_VERTS_X+i+1;
gIndices[index++] = j*NUM_VERTS_X+i;
gIndices[index++] = (j+1)*NUM_VERTS_X+i+1;
gIndices[index++] = (j+1)*NUM_VERTS_X+i;
}
}
m_indexVertexArrays = new btTriangleIndexVertexArray(totalTriangles,
gIndices,
indexStride,
totalVerts,(btScalar*) &gVertices[0].x(),vertStride);
bool useQuantizedAabbCompression = true;
trimeshShape = new btBvhTriangleMeshShape(m_indexVertexArrays,true);
btCollisionShape* groundShape = trimeshShape;
m_collisionConfiguration = new btDefaultCollisionConfiguration();
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
btVector3 worldMin(-1000,-1000,-1000);
btVector3 worldMax(1000,1000,1000);
m_broadphase = new btAxisSweep3(worldMin,worldMax);
m_solver = new btSequentialImpulseConstraintSolver();
m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration);
float mass = 0.f;
btTransform startTransform;
startTransform.setIdentity();
startTransform.setOrigin(btVector3(0,-2,0));
///create the triangle mesh
startTransform.setIdentity();
staticBody = localCreateRigidBody(mass, startTransform,groundShape);
staticBody->setRollingFriction(0.2);
///create some spheres
btCollisionShape* colShape = new btSphereShape(0.1);
///store the shapes so we can delete at restart/shutdown
m_collisionShapes.push_back(colShape);
{
for (int i=0;i<40;i++)
{
startTransform.setOrigin(btVector3(2,60+i*2,1));
btRigidBody* body = localCreateRigidBody(1, startTransform,colShape);
body->setCcdMotionThreshold(0.04);
body->setCcdSweptSphereRadius(0.08);
body->setFriction(0.9);
body->setRollingFriction(0.2);
}
}
}
void ConcaveDemo::clientMoveAndDisplay()
{
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
float dt = getDeltaTimeMicroseconds() * 0.000001f;
m_dynamicsWorld->stepSimulation(dt);
//optional but useful: debug drawing
m_dynamicsWorld->debugDrawWorld();
renderme();
glFlush();
swapBuffers();
}
void ConcaveDemo::displayCallback(void) {
glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
renderme();
//optional but useful: debug drawing
if (m_dynamicsWorld)
m_dynamicsWorld->debugDrawWorld();
glFlush();
swapBuffers();
}
void ConcaveDemo::exitPhysics()
{
//cleanup in the reverse order of creation/initialization
//remove the rigidbodies from the dynamics world and delete them
int i;
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;
}
//delete dynamics world
delete m_dynamicsWorld;
if (m_indexVertexArrays)
delete m_indexVertexArrays;
//delete solver
delete m_solver;
//delete broadphase
delete m_broadphase;
//delete dispatcher
delete m_dispatcher;
delete m_collisionConfiguration;
}
-
- Posts: 6
- Joined: Wed Sep 26, 2012 10:46 pm
Re: Simple Code Required
Thank you so much most helpful I'm on the right track now and now started creating and hole slew of games for iPhone is it ok to use BULLET Logo on splash screens and credits ?