Issue with box shapes glitching into each other

Post Reply
macsforme
Posts: 4
Joined: Mon Sep 25, 2017 7:06 am

Issue with box shapes glitching into each other

Post by macsforme »

Here is a video that illustrates the issue I'm experiencing: https://youtu.be/7_qCwILE7fE

I am trying to replicate the physics of BZFlag in a test program using Bullet. The world objects in BZFlag are very simple (mostly just boxes and pyramids), but there is a lot of overlap between the objects to make more complicated shapes (for example, three boxes may be overlaid and rotated to form a hexagon). I have the tank (driven by the player) represented by a btBoxShape. The tank can drive forward or backward, and rotate around the Y (up) axis. The movement is very simple... there is no momentum, inertia, friction, etc.

Because the movement is so simple, right now I do movement by doing setLinearVelocity() and setAngularVelocity() on the tank's rigid body, and then stepping the simulation. I called setAngularFactor(0.0, 1.0, 0.0) on the tank's rigid body to make sure it stays straight up, called forceActivationState(DISABLE_DEACTIVATION) on the tank's rigid body so it doesn't fall asleep, and set friction on the tank's rigid body to 0.0 so the tank moves directly in the direction I set. This seems to work well for the most part.

The issue I am running into is that the tank will occasionally glitch into the other boxes in the world (which are also represented by a btBoxShape). I usually see this when the tank is right up against a box but pointing into it at about a 45 degree angle, so when they come in contact the tank hugs the side of the box and slides along it. This seems to happen whether the boxes in the world are standalone or there are multiple boxes in a cluster.

I tried changing the world boxes to a btConvexHullShape, and while this does solve the issue of the tank box and the world boxes glitching into each other, it creates another issue where if the tank box crosses the area where two world boxes overlap, the tank is bounced up into the air a short distance.

I read the diagram in the Bullet manual under "Collision Shapes," which seemed to suggest that you would not use a btBoxShape for non-moving objects. However, it seems to me that using the most simple representation of an object (a box) would save CPU cycles. Is there a reason why you shouldn't use simple collision shapes like btBoxShape, btSphereShape, etc. for non-moving objects?

I did try a few things to solve the issue based on other forum posts I found. I thought it was possibly an issue with the boxes being too thin, so I tried scaling all of the objects by various factors, and I tried calling setMargin(MAX_MARGIN) on every collision shape in the world, but neither of those had an impact. I also tried decreasing the delay between steps, which did make the glitching less noticeable once I got up into the hundreds of steps per second, but I would really like to keep the step rate around the default. I also tried to determine if the glitching happens when the delta T passed to stepSimulation() varies significantly from the average, which is possible but I wasn't able to tell conclusively when I was watching both. I also tried pulling the tank position from the rigid body with getCenterOfMassTransform() versus getWorldTransform(), but I didn't see a significant difference.

Any ideas on how to stop the two box shapes from glitching into each other?

Here is my code for reference if it would help:

Code: Select all

#ifndef PHYSICS_HPP
#define PHYSICS_HPP

#include <btBulletDynamicsCommon.h>
#include <chrono>
#include <memory>
#include <vector>

#include "MatrixMath.hpp"

#define TANK_WIDTH 2.8f
#define TANK_HEIGHT 2.05f
#define TANK_LENGTH 6.0f

#define TANK_MUZZLE_HEIGHT 1.57f

#define GRAVITY -9.8f

#define TANK_JUMP_VELOCITY 19.0f
#define TANK_LINEAR_VELOCITY 25.0f
#define TANK_ANGULAR_VELOCITY 45.0f

class Physics {
protected:
  static btDefaultCollisionConfiguration collisionConfiguration;
  static btCollisionDispatcher dispatcher;
  
  static btDbvtBroadphase overlappingPairCache;

  static btSequentialImpulseConstraintSolver solver;

  static btDiscreteDynamicsWorld dynamicsWorld;

  static std::vector<btCollisionShape*> collisionShapes; // tracking for memory cleanup
  
  static btRigidBody *tankRigidBody; // tracking only

  static std::chrono::steady_clock::time_point lastUpdate;

  static struct TankControl {
    bool turningRight{ };
    bool turningLeft{ };
    bool drivingForward{ };
    bool drivingBackward{ };

    bool jumping{ };
  } tankControl;
  
public:
  static void init();

  static void destroy();
  
  static void step();
  
  static Matrix getTankTransformation();
  static Vector getTankLinearVelocity();
  static Vector getTankAngularVelocity();
  
  static void turnTankRight(bool value) { tankControl.turningRight = value; }
  static void turnTankLeft(bool value) { tankControl.turningLeft = value; }
  static void driveTankForward(bool value) { tankControl.drivingForward = value; }
  static void driveTankBackward(bool value) { tankControl.drivingBackward = value; }
  static void jumpTank(bool value) { tankControl.jumping = value; }
};

#endif // PHYSICS_HPP

Code: Select all

#include "Physics.hpp"

#include "AngleConversions.hpp"
#include "VectorMath.hpp"
#include "World.hpp"

btDefaultCollisionConfiguration Physics::collisionConfiguration;
btCollisionDispatcher Physics::dispatcher(&collisionConfiguration);

btDbvtBroadphase Physics::overlappingPairCache;

btSequentialImpulseConstraintSolver Physics::solver;

btDiscreteDynamicsWorld Physics::dynamicsWorld(&Physics::dispatcher, &Physics::overlappingPairCache,
                                               &Physics::solver, &Physics::collisionConfiguration);

std::vector<btCollisionShape*> Physics::collisionShapes;

btRigidBody *Physics::tankRigidBody{ };

std::chrono::steady_clock::time_point Physics::lastUpdate;

Physics::TankControl Physics::tankControl;

void Physics::init() {
  dynamicsWorld.setGravity(btVector3(0.0f, GRAVITY, 0.0f));

  // ground
  collisionShapes.push_back(new btStaticPlaneShape(btVector3(0.0f, 1.0f, 0.0f), 0.0f));
  
  btRigidBody::btRigidBodyConstructionInfo rigidBodyInfo(0.0f, nullptr, collisionShapes.back(),
                                                         btVector3(0.0f, 0.0f, 0.0f));

  dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));

  // back wall
  collisionShapes.push_back(new btStaticPlaneShape(btVector3(0.0f, 0.0f, -1.0f), -World::getSize().z / 2.0f));
  rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, nullptr, collisionShapes.back(),
                                                           btVector3(0.0f, 0.0f, 0.0f));
  dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
  
  // front wall
  collisionShapes.push_back(new btStaticPlaneShape(btVector3(0.0f, 0.0f, 1.0f), -World::getSize().z / 2.0f));
  rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, nullptr, collisionShapes.back(),
                                                           btVector3(0.0f, 0.0f, 0.0f));
  dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
  
  // left wall
  collisionShapes.push_back(new btStaticPlaneShape(btVector3(1.0f, 0.0f, 0.0f), -World::getSize().x / 2.0f));
  rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, nullptr, collisionShapes.back(),
                                                           btVector3(0.0f, 0.0f, 0.0f));
  dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
  
  // right wall
  collisionShapes.push_back(new btStaticPlaneShape(btVector3(-1.0f, 0.0f, 0.0f), -World::getSize().x / 2.0f));
  rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, nullptr, collisionShapes.back(),
                                                           btVector3(0.0f, 0.0f, 0.0f));
  dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));

  // rest of the world geometry
  for(const auto geometry : World::getGeometry()) {
    switch(geometry.type) {
      case World::Geometry::Type::Box:
      {
        // the box (option 1)
///*
        collisionShapes.push_back(new btBoxShape(btVector3(geometry.size.x / 2.0f, geometry.size.y / 2.0f,
                                                           geometry.size.z / 2.0f)));
//*/
/*
        // the box (option 2)
        btScalar boxPoints[8 * 3] {
          -geometry.size.x / 2.0f,
          -geometry.size.y / 2.0f,
          geometry.size.z / 2.0f,
          
          geometry.size.x / 2.0f,
          -geometry.size.y / 2.0f,
          geometry.size.z / 2.0f,
          
          geometry.size.x / 2.0f,
          -geometry.size.y / 2.0f,
          -geometry.size.z / 2.0f,
          
          -geometry.size.x / 2.0f,
          -geometry.size.y / 2.0f,
          -geometry.size.z / 2.0f,
          
          -geometry.size.x / 2.0f,
          geometry.size.y / 2.0f,
          geometry.size.z / 2.0f,
          
          geometry.size.x / 2.0f,
          geometry.size.y / 2.0f,
          geometry.size.z / 2.0f,
          
          geometry.size.x / 2.0f,
          geometry.size.y / 2.0f,
          -geometry.size.z / 2.0f,
          
          -geometry.size.x / 2.0f,
          geometry.size.y / 2.0f,
          -geometry.size.z / 2.0f
        };
        
        collisionShapes.push_back(new btConvexHullShape(boxPoints, 8, 3 * sizeof(btScalar)));
*/
        
        btTransform transform;
        transform.setIdentity();
        
        transform.setOrigin(btVector3(geometry.position.x, geometry.position.y + geometry.size.y / 2.0f,
                                      geometry.position.z));
        transform.setRotation(btQuaternion(btVector3(0.0f, 1.0f, 0.0f), radians(geometry.rotation)));

        rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, new btDefaultMotionState(transform),
                                                                 collisionShapes.back(),
                                                                 btVector3(0.0f, 0.0f, 0.0f));
        dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
        
        break;
      }

      case World::Geometry::Type::Pyramid:
      {
        btScalar pyramidPoints[5 * 3] {
          -geometry.size.x / 2.0f, // bottom left back
          geometry.size.y * (geometry.size.y < 0.0f ? -1.0f : 0.0f),
          geometry.size.z / 2.0f,

          geometry.size.x / 2.0f, // bottom right back
          geometry.size.y * (geometry.size.y < 0.0f ? -1.0f : 0.0f),
          geometry.size.z / 2.0f,
          
          geometry.size.x / 2.0f , // bottom right front
          geometry.size.y * (geometry.size.y < 0.0f ? -1.0f : 0.0f),
          -geometry.size.z / 2.0f,

          -geometry.size.x / 2.0f, // bottom left front
          geometry.size.y * (geometry.size.y < 0.0f ? -1.0f : 0.0f),
          -geometry.size.z / 2.0f,

          0.0f, // top
          geometry.size.y * (geometry.size.y < 0.0f ? 0.0f : 1.0f),
          0.0f
        };

        // the pyramid
        collisionShapes.push_back(new btConvexHullShape(pyramidPoints, 5, 3 * sizeof(btScalar)));

        btTransform transform;
        transform.setIdentity();
        
        transform.setOrigin(btVector3(geometry.position.x, geometry.position.y, geometry.position.z));
        transform.setRotation(btQuaternion(btVector3(0.0f, 1.0f, 0.0f), radians(geometry.rotation)));
        
        rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, new btDefaultMotionState(transform),
                                                                 collisionShapes.back(),
                                                                 btVector3(0.0f, 0.0f, 0.0f));
        dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
        
        break;
      }
      case World::Geometry::Type::Teleporter:
      {
        Vector lateralBorderOrigin = Vector(0.0f, 0.0f, geometry.size.z / 2.0f + geometry.border * 1.5f) *
            Matrix::rotate(Vector(0.0f, 1.0f, 0.0f), radians(geometry.rotation));

        // front border
        collisionShapes.push_back(new btBoxShape(btVector3(geometry.border / 2.0f,
                                                           geometry.size.y / 2.0f,
                                                           geometry.border / 2.0f)));
        
        btTransform transform;
        transform.setIdentity();
        
        transform.setOrigin(btVector3(geometry.position.x + lateralBorderOrigin.x,
                                      geometry.position.y + geometry.size.y / 2.0f,
                                      geometry.position.z + lateralBorderOrigin.z));
        transform.setRotation(btQuaternion(btVector3(0.0f, 1.0f, 0.0f), radians(geometry.rotation)));
        
        rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, new btDefaultMotionState(transform),
                                                                 collisionShapes.back(),
                                                                 btVector3(0.0f, 0.0f, 0.0f));
        dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
        
        // back border
        collisionShapes.push_back(new btBoxShape(btVector3(geometry.border / 2.0f,
                                                           geometry.size.y / 2.0f,
                                                           geometry.border / 2.0f)));
        
        transform.setIdentity();
        
        transform.setOrigin(btVector3(geometry.position.x - lateralBorderOrigin.x,
                                      geometry.position.y + geometry.size.y / 2.0f,
                                      geometry.position.z - lateralBorderOrigin.z));
        transform.setRotation(btQuaternion(btVector3(0.0f, 1.0f, 0.0f), radians(geometry.rotation)));
        
        rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, new btDefaultMotionState(transform),
                                                                 collisionShapes.back(),
                                                                 btVector3(0.0f, 0.0f, 0.0f));
        dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
        
        // top border
        collisionShapes.push_back(new btBoxShape(btVector3(geometry.border / 2.0f,
                                                           geometry.border / 2.0f,
                                                           (geometry.size.z + geometry.border * 4.0f) / 2.0f)));
        
        transform.setIdentity();
        
        transform.setOrigin(btVector3(geometry.position.x,
                                      geometry.position.y + geometry.size.y + geometry.border / 2.0f,
                                      geometry.position.z));
        transform.setRotation(btQuaternion(btVector3(0.0f, 1.0f, 0.0f), radians(geometry.rotation)));
        
        rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(0.0f, new btDefaultMotionState(transform),
                                                                 collisionShapes.back(),
                                                                 btVector3(0.0f, 0.0f, 0.0f));
        dynamicsWorld.addRigidBody(new btRigidBody(rigidBodyInfo));
        
        break;
      }
      default:
        throw std::string("Undefined geometry object found in world.");
    }
  }
  
  // tank
  collisionShapes.push_back(new btBoxShape(btVector3(TANK_WIDTH / 2.0f, TANK_HEIGHT/ 2.0f,
                                                     TANK_LENGTH / 2.0f)));

  rigidBodyInfo = btRigidBody::btRigidBodyConstructionInfo(1.0f,
      new btDefaultMotionState(btTransform(btMatrix3x3::getIdentity(),
                                           btVector3(0.0f, World::getSize().y, 0.0f))),
      collisionShapes.back(),
      btVector3(0.0f, 0.0f, 0.0f));
  
  tankRigidBody = new btRigidBody(rigidBodyInfo);

  tankRigidBody->setAngularFactor(btVector3(0.0f, 1.0f, 0.0f));
  tankRigidBody->setFriction(0.0f);
  tankRigidBody->forceActivationState(DISABLE_DEACTIVATION);

  dynamicsWorld.addRigidBody(tankRigidBody);

  lastUpdate = std::chrono::steady_clock::now();
}

void Physics::destroy() {
  while(dynamicsWorld.getNumCollisionObjects() > 0) {
    btCollisionObject *object = dynamicsWorld.getCollisionObjectArray()[0];
    btRigidBody *body = btRigidBody::upcast(object);

    if(body && body->getMotionState())
      delete body->getMotionState();
    
    dynamicsWorld.removeCollisionObject(object);
    
    delete object;
  }

  collisionShapes.clear();
}

void Physics::step() {
  // do tank movement
  static bool jumpCleared = false; // only jump once per press

  if(! tankControl.jumping)
    jumpCleared = true;
  
  btVector3 linearVelocity = btVector3(0.0f, tankRigidBody->getLinearVelocity().getY(), 0.0f);
  btVector3 angularVelocity(0.0f, 0.0f, 0.0f);

  if(tankControl.turningRight)
    angularVelocity += btVector3(0.0f, radians(TANK_ANGULAR_VELOCITY), 0.0f);
  if(tankControl.turningLeft)
    angularVelocity += btVector3(0.0f, radians(-TANK_ANGULAR_VELOCITY), 0.0f);
  if(tankControl.drivingForward && ! tankControl.drivingBackward)
    linearVelocity += tankRigidBody->getWorldTransform().getBasis().getColumn(2) * TANK_LINEAR_VELOCITY;
  if(tankControl.drivingBackward && ! tankControl.drivingForward)
    linearVelocity += tankRigidBody->getWorldTransform().getBasis().getColumn(2) * -TANK_LINEAR_VELOCITY / 2.0f;
  if(tankControl.jumping && jumpCleared) {
    linearVelocity += btVector3(0.0f, TANK_JUMP_VELOCITY, 0.0f);
    
    linearVelocity.setY(std::min(linearVelocity.getY(), TANK_JUMP_VELOCITY));

    jumpCleared = false;
  }
  
  tankRigidBody->setLinearVelocity(linearVelocity);
  tankRigidBody->setAngularVelocity(angularVelocity);

  // step the simulation
  auto now = std::chrono::steady_clock::now();
  
  float dt = std::chrono::duration_cast<std::chrono::duration<float>>(now - lastUpdate).count();

  dynamicsWorld.stepSimulation(dt);

  lastUpdate = now;
}

Matrix Physics::getTankTransformation() {
  auto rotation = tankRigidBody->getCenterOfMassTransform().getBasis();
  auto translation = tankRigidBody->getCenterOfMassTransform().getOrigin();
  
  // alternative?
//auto rotation = tankRigidBody->getWorldTransform().getBasis();
//auto translation = tankRigidBody->getWorldTransform().getOrigin();
  
  return Matrix(rotation[0][0], rotation[1][0], rotation[2][0], 0.0f,
                rotation[0][1], rotation[1][1], rotation[2][1], 0.0f,
                rotation[0][2], rotation[1][2], rotation[2][2], 0.0f,
                translation[0], translation[1] - TANK_HEIGHT / 2.0f, translation[2], 1.0f);
}

Vector Physics::getTankLinearVelocity() {
  const auto linearVelocity = tankRigidBody->getLinearVelocity();
  
  return Vector(linearVelocity.getX(), linearVelocity.getY(), linearVelocity.getZ());
}

Vector Physics::getTankAngularVelocity() {
  const auto angularVelocity = tankRigidBody->getAngularVelocity();
  
  return Vector(angularVelocity.getX(), angularVelocity.getY(), angularVelocity.getZ());
}
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: Issue with box shapes glitching into each other

Post by Erwin Coumans »

It is likely due to discontinuities in the contact normals.

Try using a btCapsuleShape instead and let us know if that helps.
macsforme
Posts: 4
Joined: Mon Sep 25, 2017 7:06 am

Re: Issue with box shapes glitching into each other

Post by macsforme »

Erwin Coumans wrote:It is likely due to discontinuities in the contact normals.

Try using a btCapsuleShape instead and let us know if that helps.
I don't think I fully understand your suggestion. Looking over btCapsuleShape, the constructor takes a radius and a height. The objects I am dealing with are both box-shaped (the tank, and the world boxes), and the collisions between the boxes are significant even at the edges/corners (i.e., if the tank jumping onto a box, and the sides collide first, the tank should fall back to earth). It seems like a btCapsuleShape, with the rounded caps, would introduce a lot of laxity into that behavior.
ktfh
Posts: 44
Joined: Thu Apr 14, 2016 3:44 pm

Re: Issue with box shapes glitching into each other

Post by ktfh »

I found vehicles are best simulated with a btMultiSphereShape that approximates the body, the rounded corners glance off walls and terrain better than cubes or the more angular convex hulls.
macsforme
Posts: 4
Joined: Mon Sep 25, 2017 7:06 am

Re: Issue with box shapes glitching into each other

Post by macsforme »

Is there no better way of doing this? I need box-on-box collisions, and the visible glitching in and out when I use btBoxShapes makes the result quite unpleasant.
Post Reply