Simulation Based on Gravity gets Stuck

kraythe
Posts: 9
Joined: Mon Aug 06, 2012 8:27 am

Simulation Based on Gravity gets Stuck

Post by kraythe »

I am sorry if this is a newbie question but I am a bullet newbie.

I have created a simulation that i want to control exclusively with moving gravity vectors. As the user rolls the device around the effective gravity vector changes and the idea is that the ball rolls around. The problem is that the ball keeps getting stuck in some state where no gravity vector can move it any direction. I would appreciate any clues at how I could resolve this.


First the setup of the dynamics world:

Code: Select all

- (btDiscreteDynamicsWorld *)dynamicsWorld {
   if (_dynamicsWorld == Nil) {
      // -- Initialize the Bullet Physics Dynamics World.
      btCollisionConfiguration *_collisionConfiguration = new btDefaultCollisionConfiguration();
      btCollisionDispatcher *_collisionDispatcher = new btCollisionDispatcher(_collisionConfiguration);
      btBroadphaseInterface *_overlappingPairCache = new btDbvtBroadphase();
      btSequentialImpulseConstraintSolver *_constraintSolver = new btSequentialImpulseConstraintSolver;
      _dynamicsWorld = new btDiscreteDynamicsWorld(_collisionDispatcher, _overlappingPairCache, _constraintSolver, _collisionConfiguration);
      _dynamicsWorld->setGravity(btVector3(0.0f, 0.0f, -1.0f)); // set neutral z gravity.

      // Set up the collision shape and planes
      btBoxShape *worldBoxShape = new btBoxShape(btVector3(btScalar(10.0f), btScalar(7.0f), btScalar(5.0f)));
      for (int i = 0; i < 6; i++) {
         // need to iterate through each of the planes in our box shape, moving them to the right collision positions.
         // Note that the creation of the shape above didnt create anything in the dynamics world. This will do that.
         btTransform groundTransform;
         groundTransform.setIdentity();
         groundTransform.setOrigin(btVector3(0, 0, 0));
         btVector4 planeEq;
         worldBoxShape->getPlaneEquation(planeEq, i);
         NSLog(@"plane = %f, %f, %f, %f", planeEq.getX(), planeEq.getY(), planeEq.getZ(), planeEq.getW());

         // Now we will create the collision shape for the boxes.
         btCollisionShape *groundShape = new btStaticPlaneShape(-planeEq, planeEq.getW());
         btScalar mass(0.0f);   //rigidbody is dynamic if and only if mass is non zero, otherwise static
         btVector3 localInertia(0, 0, 0); // Static elements have 0 inertia.
         //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 *sFloorPlaneBody = new btRigidBody(rbInfo);
         _dynamicsWorld->addRigidBody(sFloorPlaneBody); //add the body to the dynamics world
      }
      [self.ball addToDynamicsWorld:_dynamicsWorld];

   }
   return _dynamicsWorld;
}

And the setup of the ball in the dynamics world.

Code: Select all

- (void)addToDynamicsWorld:(btDiscreteDynamicsWorld *)dynamicsWorld {
   btTransform bodyTransform;
   bodyTransform.setIdentity();
   bodyTransform.setOrigin(btVector3(0, 0, 0));
   btCollisionShape *sphereShape = new btSphereShape(btScalar(1.0f));
   btScalar mass(self.mass);//positive mass means dynamic/moving  object
   btVector3 localInertia(0, 0, 0);
   sphereShape->calculateLocalInertia(mass, localInertia);
   NSLog(@"localIntertia = %f, %f, %f", localInertia.getX(), localInertia.getY(), localInertia.getZ());
   //using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
   btDefaultMotionState *myMotionState = new btDefaultMotionState(bodyTransform);
   btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, myMotionState, sphereShape, localInertia);
   _sphereBody = new btRigidBody(rbInfo);
   //most applications shouldn't disable deactivation, but for this demo it is better.
   //_sphereBody->setActivationState(DISABLE_DEACTIVATION);
   //add the body to the dynamics world
   dynamicsWorld->addRigidBody(_sphereBody);
}
On each update pulse from the OpenGL kit from iOS, it does the following:

Code: Select all

- (btVector3)calculateG {
   // TODO This will be placed with calls to CMMotionManager
   GLKVector3 touchPos = self.touchPosition;
   float viewport[4];
   glGetFloatv(GL_VIEWPORT, viewport);
   float halfWidth = viewport[2] / 2, halfHeight = (viewport[3] / 2);

   btVector3 result;
   if (GLKVector3AllEqualToScalar(touchPos, 0.0f)) result = btVector3(0, 0, 1);
   else if ((touchPos.x - halfWidth) > (halfWidth / 2)) result = btVector3(1, 0, -1).normalize();
   else if ((touchPos.x - halfWidth) < (-1 * halfWidth / 2)) result = btVector3(-1, 0, -1).normalize();
   else if ((touchPos.y - halfHeight) > (halfHeight / 2)) result = btVector3(0, -1, -1).normalize();
   else if ((touchPos.y - halfHeight) < (-1 * halfHeight / 2)) result = btVector3(0, 1, -1).normalize();
   else result = btVector3(0, 0, -1);

   return result * btScalar(9.8);
}

- (void)update {
   NSTimeInterval deltaTime = self.timeSinceLastUpdate;
   float scaling = 20.f;

   if (self.dynamicsWorld) {
      btVector3 g = [self calculateG];
      self.dynamicsWorld->setGravity(g);

      self.dynamicsWorld->stepSimulation(deltaTime, 2);//deltaTime);
      [self.ball updateUsingInterval:deltaTime];
   }
}
After this, the data for the ball is extracted, sent through the world transform and set as uniforms in the vertex shaders:

Code: Select all

- (void)updateUsingInterval:(NSTimeInterval)interval {
   btTransform transform = self.sphereBody->getCenterOfMassTransform();
   btVector3 velocity = self.sphereBody->getTurnVelocity();
   btVector3 position = transform.getOrigin();
   btQuaternion rotation = transform.getRotation();

   // Convert quaternion from bullet to GLK for sending to shader.
   GLKQuaternion glkRotation = GLKQuaternionMake(rotation.x(), rotation.y(), rotation.z(), rotation.w());
   GLKMatrix4 modelViewMatrix = GLKMatrix4MakeTranslation(position.x(), position.y(), position.z());
   modelViewMatrix = GLKMatrix4Multiply(modelViewMatrix, GLKMatrix4MakeWithQuaternion(glkRotation));
   modelViewMatrix = GLKMatrix4Multiply(self.viewController.baseModelView, modelViewMatrix);

   _normalMatrix = GLKMatrix3InvertAndTranspose(GLKMatrix4GetMatrix3(modelViewMatrix), NULL);
   _modelViewProjection = GLKMatrix4Multiply(self.viewController.projection, modelViewMatrix);
}