Can't get objects to collide

Atekon
Posts: 3
Joined: Sun Dec 19, 2010 9:05 pm

Can't get objects to collide

Post by Atekon »

Hey,

I'm still a newbie with bullet and can't get it to perform collisions between different objects. I mean, they collide with the ground but not against each other.

I've followed the tutorial from the wiki (the Hello World one) and just added another object from a higher point (and drawed it on the screen)

I'll post the code here and if someone could explain me what i'm missing i'd be very thankfull since I've been trying to solve this for a week or two.

Code: Select all

#include <iostream>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include <time.h>
#include <GL/glut.h>
#include <btBulletDynamicsCommon.h>

using namespace std;

typedef struct{
	btAlignedObjectArray<btCollisionShape*>	collisionShapes;
	btBroadphaseInterface* broadphase;
	btDefaultCollisionConfiguration* collisionConfiguration;
	btCollisionDispatcher* dispatcher;
	btSequentialImpulseConstraintSolver* solver;
	btDiscreteDynamicsWorld* dynamicsWorld;
	btCollisionShape* groundShape;
	btCollisionShape* fallShape;
	btCollisionShape* fallShape2;
	btDefaultMotionState* groundMotionState;
	btRigidBody* groundRigidBody;
	btDefaultMotionState* fallMotionState;
	btScalar mass;
	btVector3 fallInertia;
	btRigidBody* fallRigidBody;

	btDefaultMotionState* fallMotionState2;
	btScalar mass2;
	btVector3 fallInertia2;
	btRigidBody* fallRigidBody2;

}Bullet;

typedef struct {
  Bullet      ph;

  GLfloat y;
  GLfloat y2;
}Modelo;

Modelo m;

void Init(void)
{

	srand( (unsigned)time(NULL));
    
	glClearColor(0.0, 0.0, 0.0, 0.0);

  //Bullet initializations
	m.ph.collisionConfiguration = new btDefaultCollisionConfiguration();

	m.ph.broadphase = new btDbvtBroadphase();
	
    m.ph.dispatcher = new btCollisionDispatcher(m.ph.collisionConfiguration);
 
	m.ph.solver = new btSequentialImpulseConstraintSolver;
 
	m.ph.dynamicsWorld = new btDiscreteDynamicsWorld(m.ph.dispatcher,m.ph.broadphase,m.ph.solver,m.ph.collisionConfiguration);
 
	m.ph.dynamicsWorld->setGravity(btVector3(0,-10,0));
 
 
	m.ph.groundShape = new btStaticPlaneShape(btVector3(0,1,0),1);

	m.ph.collisionShapes.push_back(m.ph.groundShape);
 
	m.ph.fallShape = new btBoxShape(btVector3(1.*1,1.*1,1.*1));//new btSphereShape(1);
 
	m.ph.collisionShapes.push_back(m.ph.fallShape);

	m.ph.fallShape2 = new btBoxShape(btVector3(1.*1,1.*1,1.*1));//new btSphereShape(1);
 
	m.ph.collisionShapes.push_back(m.ph.fallShape2);

    m.ph.groundMotionState = new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),btVector3(0,-1,0)));
    btRigidBody::btRigidBodyConstructionInfo
            groundRigidBodyCI(0,m.ph.groundMotionState,m.ph.groundShape,btVector3(0,0,0));
    m.ph.groundRigidBody = new btRigidBody(groundRigidBodyCI);
    m.ph.dynamicsWorld->addRigidBody(m.ph.groundRigidBody);
 
 
    m.ph.fallMotionState =
            new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),btVector3(0,50,0)));
    m.ph.mass = 1.f;
    m.ph.fallInertia = btVector3(0,0,0);

    m.ph.fallShape->calculateLocalInertia(m.ph.mass,m.ph.fallInertia);
	btRigidBody::btRigidBodyConstructionInfo fallRigidBodyCI(m.ph.mass,m.ph.fallMotionState,m.ph.fallShape,m.ph.fallInertia);
    m.ph.fallRigidBody = new btRigidBody(fallRigidBodyCI);

	btTransform trans;
	trans.setIdentity();

	btVector3 pos;
	pos.setValue(0,50,0);
	trans.setOrigin(pos);

	m.ph.fallRigidBody->setWorldTransform(trans);
	m.ph.fallRigidBody->setActivationState(ACTIVE_TAG);
    m.ph.dynamicsWorld->addRigidBody(m.ph.fallRigidBody);

	m.y=50;

	m.ph.fallMotionState2 =
            new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),btVector3(0,150,0)));
    m.ph.mass2 = 1.f;
    m.ph.fallInertia2 = btVector3(0,0,0);
    m.ph.fallShape2->calculateLocalInertia(m.ph.mass2,m.ph.fallInertia2);
	btRigidBody::btRigidBodyConstructionInfo fallRigidBodyCI2(m.ph.mass2,m.ph.fallMotionState2,m.ph.fallShape2,m.ph.fallInertia2);
    m.ph.fallRigidBody2 = new btRigidBody(fallRigidBodyCI2);

	trans.setIdentity();

	pos.setValue(0,150,0);
	trans.setOrigin(pos);

	m.ph.fallRigidBody2->setWorldTransform(trans);
	m.ph.fallRigidBody2->setActivationState(ACTIVE_TAG);

    m.ph.dynamicsWorld->addRigidBody(m.ph.fallRigidBody2);


	m.y2=150;

  glEnable(GL_POINT_SMOOTH);
  glEnable(GL_LINE_SMOOTH);
  glEnable(GL_POLYGON_SMOOTH);
  glEnable(GL_DEPTH_TEST);
  //glutIgnoreKeyRepeat(GL_TRUE);

}

/**************************************
***  callbacks de janela/desenho    ***
**************************************/

// CALLBACK PARA REDIMENSIONAR JANELA

void Reshape(int width, int height)
{
  // glViewport(botom, left, width, height)
  // define parte da janela a ser utilizada pelo OpenGL

  glViewport(0, 0, (GLint) width, (GLint) height);
  

  // Matriz Projeccao
  // Matriz onde se define como o mundo e apresentado na janela
  glMatrixMode(GL_PROJECTION);
  glLoadIdentity();

  // gluOrtho2D(left,right,bottom,top); 
  // projeccao ortogonal 2D, com profundidade (Z) entre -1 e 1

  gluPerspective(80,(GLfloat)width/height,1,100);

  //if(estado.ortho)
  //{
  //  if (width < height)
  //     glOrtho(-20, 20, -20*(GLdouble)height/width, 20*(GLdouble)height/width,-100,100);
  //  else
  //     glOrtho(-20*(GLdouble)width/height, 20*(GLdouble)width/height,-20, 20, -100,100);
  //}
  //else
  //  gluPerspective(estado.camera.fov,(GLfloat)width/height,1,100);

  glMatrixMode(GL_MODELVIEW);
}

void desenhaPoligono(GLfloat a[], GLfloat b[], GLfloat c[], GLfloat  d[], GLfloat cor[])
{
	//draws polygon
  glBegin(GL_POLYGON);
    glColor3fv(cor);
    glVertex3fv(a);
    glVertex3fv(b);
    glVertex3fv(c);
    glVertex3fv(d);
  glEnd();
}

void desenhaChao(GLfloat dimensao)
{
	//draws ground
  glBegin(GL_POLYGON);
	glTranslatef(0,1,0);
    glVertex3f(dimensao,0,dimensao);
    glVertex3f(-dimensao,0,dimensao);
    glVertex3f(-dimensao,0,-dimensao);
    glVertex3f(dimensao,0,-dimensao);
  glEnd();

}

void desenhaCubo()
{
	//draws cube
  GLfloat vertices[][3] = {  {-0.5,-0.5,-0.5}, 
                {0.5,-0.5,-0.5}, 
                {0.5,0.5,-0.5}, 
                {-0.5,0.5,-0.5}, 
                {-0.5,-0.5,0.5},  
                {0.5,-0.5,0.5}, 
                {0.5,0.5,0.5}, 
                {-0.5,0.5,0.5}};

  GLfloat cores[][3] = {{0.0,1.0,1.0},
                        {1.0,0.0,0.0},
                        {1.0,1.0,0.0}, 
                        {0.0,1.0,0.0}, 
                        {1.0,0.0,1.0}, 
                        {0.0,0.0,1.0}, 
                        {1.0,1.0,1.0}};

  desenhaPoligono(vertices[1],vertices[0],vertices[3],vertices[2],cores[0]);
  desenhaPoligono(vertices[2],vertices[3],vertices[7],vertices[6],cores[1]);
  desenhaPoligono(vertices[3],vertices[0],vertices[4],vertices[7],cores[2]);
  desenhaPoligono(vertices[6],vertices[5],vertices[1],vertices[2],cores[3]);
  desenhaPoligono(vertices[4],vertices[5],vertices[6],vertices[7],cores[4]);
  desenhaPoligono(vertices[5],vertices[4],vertices[0],vertices[1],cores[5]);
}

void Draw(void)
{
  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);

  glLoadIdentity();

  gluLookAt(0,2,25, \
            0,2,0,\
            0,1,0);

    glColor3f(0.5f,0.5f,0.5f);
	glPushMatrix();
		glTranslatef(0,1,0);
		desenhaChao(1000);
	glPopMatrix();
	glPushMatrix();
		glScalef(2,2,2);
		glTranslatef(0,m.y,0);
		desenhaCubo();
	glPopMatrix();
	glPushMatrix();
		glScalef(2,2,2);
		glTranslatef(0,m.y2,0);
		desenhaCubo();
	glPopMatrix();

   glFlush();
  /*if (estado.doubleBuffer)*/
    glutSwapBuffers();
}

void Timer(int value)
{
	 glutTimerFunc(10, Timer, 0);

	 m.ph.dynamicsWorld->stepSimulation(1/60.f);
	 //m.ph.dynamicsWorld->stepSimulation(1/60.f,10);
	 m.ph.dynamicsWorld->performDiscreteCollisionDetection();

	 int numManifolds = m.ph.dynamicsWorld->getDispatcher()->getNumManifolds();

		for (int i=0;i<numManifolds;i++)
		{
			btPersistentManifold* contactManifold =  m.ph.dynamicsWorld->getDispatcher()->getManifoldByIndexInternal(i);
			btCollisionObject* obA = static_cast<btCollisionObject*>(contactManifold->getBody0());
			btCollisionObject* obB = static_cast<btCollisionObject*>(contactManifold->getBody1());
	
			int numContacts = contactManifold->getNumContacts();
			for (int j=0;j<numContacts;j++)
			{
				btManifoldPoint& pt = contactManifold->getContactPoint(j);
				if (pt.getDistance()<0.f)
				{
					const btVector3& ptA = pt.getPositionWorldOnA();
					const btVector3& ptB = pt.getPositionWorldOnB();
					const btVector3& normalOnB = pt.m_normalWorldOnB;
					//completely making this up
					btRigidBody::upcast(obA)->applyCentralImpulse((btVector3) normalOnB*pt.getAppliedImpulse()*-1);
					btRigidBody::upcast(obB)->applyCentralImpulse((btVector3) normalOnB*pt.getAppliedImpulse());

				}
			}
		}


 
	 btTransform trans;
     m.ph.fallRigidBody->getMotionState()->getWorldTransform(trans);

     std::cout << "sphere height: " << trans.getOrigin().getY() << std::endl;

	 m.y = trans.getOrigin().getY();

	 m.ph.fallRigidBody2->getMotionState()->getWorldTransform(trans);

	 std::cout << "sphere height 2: " << trans.getOrigin().getY() << std::endl;

	 

	 m.y2 = trans.getOrigin().getY();
	 //redesenhar


	 glutPostRedisplay();
}

void End(void){
	
	m.ph.dynamicsWorld->removeRigidBody(m.ph.fallRigidBody);
	delete m.ph.fallRigidBody->getMotionState();
    delete m.ph.fallRigidBody;
 
	m.ph.dynamicsWorld->removeRigidBody(m.ph.groundRigidBody);
    delete m.ph.groundRigidBody->getMotionState();
    delete m.ph.groundRigidBody;
 
	for (int j=0;j<m.ph.collisionShapes.size();j++)
	{
		btCollisionShape* shape = m.ph.collisionShapes[j];
		delete shape;
	}
 
    delete m.ph.fallShape;
 
    delete m.ph.groundShape;
 
 
	delete m.ph.dynamicsWorld;
    delete m.ph.solver;
    delete m.ph.collisionConfiguration;
    delete m.ph.dispatcher;
    delete m.ph.broadphase;
}
 
int main (int argc, char **argv)
{
	glutInit(&argc, argv);
	glutInitWindowPosition(0, 0);
	glutInitWindowSize(640, 480);
	glutInitDisplayMode(GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH);

	if (glutCreateWindow("Exemplo") == GL_FALSE)
		exit(1);
	
	Init();

	  // callbacks de janelas/desenho
	  glutReshapeFunc(Reshape);
      glutDisplayFunc(Draw);



	glutTimerFunc(100,Timer,0);


	  // COMECAR...
  glutMainLoop();

  	End();

	cin.get();
    return 0;
}

Thanks in advance
lulzfish
Posts: 43
Joined: Mon Jan 03, 2011 4:26 pm

Re: Can't get objects to collide

Post by lulzfish »

I don't know if this is your issue, but you have setActivationState, which I've never needed to use. I would try commenting it out unless you're sure you need it for something.
Atekon
Posts: 3
Joined: Sun Dec 19, 2010 9:05 pm

Re: Can't get objects to collide

Post by Atekon »

thanks!

but that didn't work out =/ the second cube just ignores the first one...
winspear
Posts: 77
Joined: Thu Nov 26, 2009 6:32 pm

Re: Can't get objects to collide

Post by winspear »

One basic flaw in your drawing routine. You are not updating the position of the cubes and the ground with the transform obtained from bullet.


Here you go...

Code: Select all

#include <iostream>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <math.h>
#include <time.h>
#include <GL/glut.h>
#include <btBulletDynamicsCommon.h>

using namespace std;

typedef struct{
   btAlignedObjectArray<btCollisionShape*>   collisionShapes;
   btBroadphaseInterface* broadphase;
   btDefaultCollisionConfiguration* collisionConfiguration;
   btCollisionDispatcher* dispatcher;
   btSequentialImpulseConstraintSolver* solver;
   btDiscreteDynamicsWorld* dynamicsWorld;
   btCollisionShape* groundShape;
   btCollisionShape* fallShape;
   btCollisionShape* fallShape2;
   btDefaultMotionState* groundMotionState;
   btRigidBody* groundRigidBody;
   btDefaultMotionState* fallMotionState;
   btScalar mass;
   btVector3 fallInertia;
   btRigidBody* fallRigidBody;

   btDefaultMotionState* fallMotionState2;
   btScalar mass2;
   btVector3 fallInertia2;
   btRigidBody* fallRigidBody2;

}Bullet;

typedef struct {
  Bullet      ph;

  GLfloat y;
  GLfloat y2;
}Modelo;

Modelo m;

void Init(void)
{

   srand( (unsigned)time(NULL));
   
   glClearColor(0.0, 0.0, 0.0, 0.0);

  //Bullet initializations
   m.ph.collisionConfiguration = new btDefaultCollisionConfiguration();
   m.ph.broadphase = new btDbvtBroadphase();
   m.ph.dispatcher = new btCollisionDispatcher(m.ph.collisionConfiguration);
   m.ph.solver = new btSequentialImpulseConstraintSolver;
   m.ph.dynamicsWorld = new btDiscreteDynamicsWorld(m.ph.dispatcher,m.ph.broadphase,m.ph.solver,m.ph.collisionConfiguration);
   m.ph.dynamicsWorld->setGravity(btVector3(0,-10,0));

   m.ph.groundShape = new btStaticPlaneShape(btVector3(0,1,0),1);
    m.ph.groundMotionState = new btDefaultMotionState(btTransform(btQuaternion(0,0,0,1),btVector3(0,-1,0)));
    btRigidBody::btRigidBodyConstructionInfo
    groundRigidBodyCI(0,m.ph.groundMotionState,m.ph.groundShape,btVector3(0,0,0));
    m.ph.groundRigidBody = new btRigidBody(groundRigidBodyCI);
    m.ph.dynamicsWorld->addRigidBody(m.ph.groundRigidBody);
   m.ph.collisionShapes.push_back(m.ph.groundShape);



   m.ph.fallShape = new btBoxShape(btVector3(1.*1,1.*1,1.*1));//new btSphereShape(1);


  	btTransform trans;
	trans.setIdentity();
	trans.setOrigin( btVector3(0,15,0) );
   m.ph.fallMotionState =new btDefaultMotionState(trans);
   m.ph.mass = 1.f;
   m.ph.fallInertia = btVector3(0,0,0);

   m.ph.fallShape->calculateLocalInertia(m.ph.mass,m.ph.fallInertia);
   btRigidBody::btRigidBodyConstructionInfo fallRigidBodyCI(m.ph.mass,m.ph.fallMotionState,m.ph.fallShape,m.ph.fallInertia);
   m.ph.fallRigidBody = new btRigidBody(m.ph.mass,m.ph.fallMotionState, m.ph.fallShape, m.ph.fallInertia  );

   m.ph.dynamicsWorld->addRigidBody(m.ph.fallRigidBody);

   m.ph.collisionShapes.push_back(m.ph.fallShape);


   m.ph.fallShape2 = new btBoxShape(btVector3(1.*1,1.*1,1.*1));//new btSphereShape(1);
   	btTransform trans2;
	trans2.setIdentity();
	trans2.setOrigin( btVector3(0,10,0) );

   m.ph.fallMotionState2 = new btDefaultMotionState(trans2);
   m.ph.mass2 = 1.f;
   m.ph.fallInertia2 = btVector3(0,0,0);
   m.ph.fallShape2->calculateLocalInertia(m.ph.mass2,m.ph.fallInertia2);
   btRigidBody::btRigidBodyConstructionInfo fallRigidBodyCI2(m.ph.mass2,m.ph.fallMotionState2,m.ph.fallShape2,m.ph.fallInertia2);
   m.ph.fallRigidBody2 = new btRigidBody(m.ph.mass2,m.ph.fallMotionState2,m.ph.fallShape2,m.ph.fallInertia2);


    m.ph.dynamicsWorld->addRigidBody(m.ph.fallRigidBody2);

      m.ph.collisionShapes.push_back(m.ph.fallShape2);


  glEnable(GL_POINT_SMOOTH);
  glEnable(GL_LINE_SMOOTH);
  glEnable(GL_POLYGON_SMOOTH);
  glEnable(GL_DEPTH_TEST);
  //glutIgnoreKeyRepeat(GL_TRUE);


}

/**************************************
***  callbacks de janela/desenho    ***
**************************************/

// CALLBACK PARA REDIMENSIONAR JANELA

void Reshape(int width, int height)
{
  // glViewport(botom, left, width, height)
  // define parte da janela a ser utilizada pelo OpenGL

  glViewport(0, 0, (GLint) width, (GLint) height);
 

  // Matriz Projeccao
  // Matriz onde se define como o mundo e apresentado na janela
  glMatrixMode(GL_PROJECTION);
  glLoadIdentity();

  // gluOrtho2D(left,right,bottom,top);
  // projeccao ortogonal 2D, com profundidade (Z) entre -1 e 1

  gluPerspective(80,(GLfloat)width/height,1,100);

  //if(estado.ortho)
  //{
  //  if (width < height)
  //     glOrtho(-20, 20, -20*(GLdouble)height/width, 20*(GLdouble)height/width,-100,100);
  //  else
  //     glOrtho(-20*(GLdouble)width/height, 20*(GLdouble)width/height,-20, 20, -100,100);
  //}
  //else
  //  gluPerspective(estado.camera.fov,(GLfloat)width/height,1,100);

  glMatrixMode(GL_MODELVIEW);
}

void desenhaPoligono(GLfloat a[], GLfloat b[], GLfloat c[], GLfloat  d[], GLfloat cor[])
{
   //draws polygon
  glBegin(GL_POLYGON);
    glColor3fv(cor);
    glVertex3fv(a);
    glVertex3fv(b);
    glVertex3fv(c);
    glVertex3fv(d);
  glEnd();
}

void desenhaChao(GLfloat dimensao)
{
   //draws ground
  glBegin(GL_POLYGON);
   glTranslatef(0,1,0);
    glVertex3f(dimensao,0,dimensao);
    glVertex3f(-dimensao,0,dimensao);
    glVertex3f(-dimensao,0,-dimensao);
    glVertex3f(dimensao,0,-dimensao);
  glEnd();

}

void desenhaCubo()
{
   //draws cube
  GLfloat vertices[][3] = {  {-1.0,-1.0,-1.0},
                {1.0,-1.0,-1.0},
                {1.0,1.0,-1.0},
                {-1.0,1.0,-1.0},
                {-1.0,-1.0,1.0}, 
                {1.0,-1.0,1.0},
                {1.0,1.0,1.0},
                {-1.0,1.0,1.0}};

  GLfloat cores[][3] = {{0.0,1.0,1.0},
                        {1.0,0.0,0.0},
                        {1.0,1.0,0.0},
                        {0.0,1.0,0.0},
                        {1.0,0.0,1.0},
                        {0.0,0.0,1.0},
                        {1.0,1.0,1.0}};

  desenhaPoligono(vertices[1],vertices[0],vertices[3],vertices[2],cores[0]);
  desenhaPoligono(vertices[2],vertices[3],vertices[7],vertices[6],cores[1]);
  desenhaPoligono(vertices[3],vertices[0],vertices[4],vertices[7],cores[2]);
  desenhaPoligono(vertices[6],vertices[5],vertices[1],vertices[2],cores[3]);
  desenhaPoligono(vertices[4],vertices[5],vertices[6],vertices[7],cores[4]);
  desenhaPoligono(vertices[5],vertices[4],vertices[0],vertices[1],cores[5]);
}

void Draw(void)
{
  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);

  glLoadIdentity();

  gluLookAt(0,2,25, \
            0,2,0,\
            0,1,0);

    glColor3f(0.5f,0.5f,0.5f);
   glPushMatrix();
		btTransform m3trans;
		m3trans = m.ph.groundRigidBody->getWorldTransform();
		float m3[16];
		m3trans.getOpenGLMatrix(m3);
		glMultMatrixf(m3);
      desenhaChao(1000);
   glPopMatrix();
   glPushMatrix();
//      glScalef(2,2,2);
		btTransform m1trans;
		m1trans = m.ph.fallRigidBody->getWorldTransform();
		float m1[16];
		m1trans.getOpenGLMatrix(m1);
		glMultMatrixf(m1);
      desenhaCubo();
   glPopMatrix();
   glPushMatrix();
//      glScalef(2,2,2);
		btTransform m2trans;
		m2trans = m.ph.fallRigidBody2->getWorldTransform();
		float m2[16];
		m2trans.getOpenGLMatrix(m2);
		glMultMatrixf(m2);
      desenhaCubo();
   glPopMatrix();

   glFlush();
  /*if (estado.doubleBuffer)*/
    glutSwapBuffers();
}

void Timer(int value)
{
    glutTimerFunc(10, Timer, 0);

    m.ph.dynamicsWorld->stepSimulation(1/60.f);
    //m.ph.dynamicsWorld->stepSimulation(1/60.f,10);
    m.ph.dynamicsWorld->performDiscreteCollisionDetection();

    int numManifolds = m.ph.dynamicsWorld->getDispatcher()->getNumManifolds();

      for (int i=0;i<numManifolds;i++)
      {
         btPersistentManifold* contactManifold =  m.ph.dynamicsWorld->getDispatcher()->getManifoldByIndexInternal(i);
         btCollisionObject* obA = static_cast<btCollisionObject*>(contactManifold->getBody0());
         btCollisionObject* obB = static_cast<btCollisionObject*>(contactManifold->getBody1());
   
         int numContacts = contactManifold->getNumContacts();
         for (int j=0;j<numContacts;j++)
         {
            btManifoldPoint& pt = contactManifold->getContactPoint(j);
            if (pt.getDistance()<0.f)
            {
               const btVector3& ptA = pt.getPositionWorldOnA();
               const btVector3& ptB = pt.getPositionWorldOnB();
               const btVector3& normalOnB = pt.m_normalWorldOnB;
               //completely making this up
               btRigidBody::upcast(obA)->applyCentralImpulse((btVector3) normalOnB*pt.getAppliedImpulse()*-1);
               btRigidBody::upcast(obB)->applyCentralImpulse((btVector3) normalOnB*pt.getAppliedImpulse());

            }
         }
      }



    btTransform trans;
     m.ph.fallRigidBody->getMotionState()->getWorldTransform(trans);

     std::cout << "sphere height: " << trans.getOrigin().getY() << std::endl;

    m.y = trans.getOrigin().getY();

    m.ph.fallRigidBody2->getMotionState()->getWorldTransform(trans);

    std::cout << "sphere height 2: " << trans.getOrigin().getY() << std::endl;

   

    m.y2 = trans.getOrigin().getY();
    //redesenhar


    glutPostRedisplay();
}

void End(void){
   
   m.ph.dynamicsWorld->removeRigidBody(m.ph.fallRigidBody);
   delete m.ph.fallRigidBody->getMotionState();
    delete m.ph.fallRigidBody;

   m.ph.dynamicsWorld->removeRigidBody(m.ph.groundRigidBody);
    delete m.ph.groundRigidBody->getMotionState();
    delete m.ph.groundRigidBody;

   for (int j=0;j<m.ph.collisionShapes.size();j++)
   {
      btCollisionShape* shape = m.ph.collisionShapes[j];
      delete shape;
   }

    delete m.ph.fallShape;

    delete m.ph.groundShape;


   delete m.ph.dynamicsWorld;
    delete m.ph.solver;
    delete m.ph.collisionConfiguration;
    delete m.ph.dispatcher;
    delete m.ph.broadphase;
}

int main (int argc, char **argv)
{
   glutInit(&argc, argv);
   glutInitWindowPosition(0, 0);
   glutInitWindowSize(640, 480);
   glutInitDisplayMode(GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH);

   if (glutCreateWindow("Exemplo") == GL_FALSE)
      exit(1);
   
   Init();

     // callbacks de janelas/desenho
     glutReshapeFunc(Reshape);
      glutDisplayFunc(Draw);



   glutTimerFunc(100,Timer,0);


     // COMECAR...
  glutMainLoop();

     End();

   cin.get();
    return 0;
}
Atekon
Posts: 3
Joined: Sun Dec 19, 2010 9:05 pm

Re: Can't get objects to collide

Post by Atekon »

wow!

Thanks! That did the trick!

You're a lifesaver winspear!