I'm new to Bullet and trying to integrating it into my code base as the physics system. I'm currently using OpenGL as the graphics api and have an input controller that drives player movement on the horizontal plane. I'm trying to use Bullet to take my GL scene information verbatim to build triangle mesh shapes for use in collision detection and use the Kinematic Controller for handling the CD. My GL scene data has a per-instance transform that transforms the data from model space (from external files) to world positions.
Being new to bullet, I'm not having a lot of luck having my view position stop when it hits anything, and from my stepping through the bt lib I cannot adequately say that I've hit/penetrated any objects. Any help you guys could help would be much appreciated. I'm basically looking to use this for a simple FPS demo, but using triangle mesh data and not BSP data as in the CharacterDemo example.
Thanks,
shw
PS. If I'm totally off, please feel free to offer other ways I can accomplish this.
Code: Select all
#pragma comment(lib, "BulletCollision.lib")
#include <vector>
#include "physicsmgr.h"
#include "graphicstypes.h"
// Bullet Headers ////////////////////
// Collision
#include "BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h"
#include "BulletCollision/CollisionDispatch/btCollisionDispatcher.h"
#include "BulletCollision/CollisionDispatch/btGhostObject.h"
//#include "BulletCollision/BroadphaseCollision/btDbvtBroadphase.h"
#include "BulletCollision/BroadphaseCollision/btAxisSweep3.h"
#include "BulletCollision/CollisionShapes/btBoxShape.h"
#include "BulletCollision/CollisionShapes/btCapsuleShape.h"
#include "BulletCollision/CollisionShapes/btTriangleMesh.h"
#include "BulletCollision/CollisionShapes/btConvexTriangleMeshShape.h"
#include "BulletCollision/CollisionShapes/btBvhTriangleMeshShape.h"
// Dynamics
#include "BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.h"
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
#include "BulletDynamics/Character/btKinematicCharacterController.h"
// Linear Math
#include "LinearMath/btDefaultMotionState.h"
#include "graphicstypes.h"
PhysicsMgr::PhysicsMgr() :
m_pCollisionConfiguration(NULL),
m_pBroadphase(NULL),
m_pDispatcher(NULL),
m_pSolver(NULL),
m_pDynamicsWorld(NULL)
{
}
PhysicsMgr::~PhysicsMgr()
{
}
bool PhysicsMgr::Initialize()
{
///collision configuration contains default setup for memory, collision setup
m_pCollisionConfiguration = new btDefaultCollisionConfiguration();
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_pDispatcher = new btCollisionDispatcher( m_pCollisionConfiguration );
btVector3 worldAabbMin(-10000, -10000, -10000); //world size for broadphase.
btVector3 worldAabbMax(10000, 10000, 10000); //should probs be loaded from scene file to
m_pBroadphase = new btAxisSweep3(worldAabbMin, worldAabbMax);//, 2048);
m_pBroadphase->getOverlappingPairCache()->setInternalGhostPairCallback(new btGhostPairCallback());
///the default constraint solver. For parallel processing you can use a different solver (see Extras/BulletMultiThreaded)
m_pSolver = new btSequentialImpulseConstraintSolver();
m_pDynamicsWorld = new btDiscreteDynamicsWorld(m_pDispatcher, m_pBroadphase, m_pSolver, m_pCollisionConfiguration);
m_pDynamicsWorld->setGravity(btVector3(0.0f, 10.0f, 0.0f));
return true;
}
void PhysicsMgr::Shutdown()
{
}
void PhysicsMgr::Update(float deltaTime, Vector3& viewPos)
{
deltaTime = 0.0001f;
///set walkDirection for our character
btTransform xform;
xform = m_pGhostObject->getWorldTransform ();
btVector3 forwardDir = xform.getBasis()[2];
btVector3 upDir = xform.getBasis()[1];
btVector3 strafeDir = xform.getBasis()[0];
forwardDir.normalize ();
upDir.normalize ();
strafeDir.normalize ();
btVector3 walkDirection = btVector3(0.0, 0.0, 0.0);
btScalar walkVelocity = btScalar(1.1) * 4.0; // 4 km/h -> 1.1 m/s
btScalar walkSpeed = walkVelocity * deltaTime;
//if (gForward)
walkDirection += forwardDir;
m_pCharacter->setWalkDirection(walkDirection*walkSpeed);
m_pDynamicsWorld->stepSimulation( deltaTime * 1000.0f, 0 );
xform = m_pGhostObject->getWorldTransform ();
btVector3& v = xform.getOrigin();
viewPos.x() = v.x();
viewPos.y() = v.y();
viewPos.z() = v.z();
}
void PhysicsMgr::InitPlayer(Player& player)
{
btTransform transform;
transform.setIdentity();
//transform.setRotation( btQuaternion(btVector3(0.0f, 1.0f, 0.0f), 90.0f) );
transform.setOrigin( btVector3(0.0f,50.0f,0.0) );
m_pGhostObject = new btPairCachingGhostObject();
m_pGhostObject->setWorldTransform( transform );
m_pBroadphase->getOverlappingPairCache()->setInternalGhostPairCallback( new btGhostPairCallback() );
btScalar characterHeight = 2.0f;
btScalar characterWidth = 1.0f;
btConvexShape* capsule = new btCapsuleShape( characterWidth, characterHeight );
m_pGhostObject->setCollisionShape( capsule );
m_pGhostObject->setCollisionFlags( btCollisionObject::CF_CHARACTER_OBJECT );
btScalar stepHeight = btScalar(4.0f);
m_pCharacter = new btKinematicCharacterController( m_pGhostObject, capsule, stepHeight );
m_pDynamicsWorld->addCollisionObject( m_pGhostObject, btBroadphaseProxy::CharacterFilter, btBroadphaseProxy::StaticFilter|btBroadphaseProxy::DefaultFilter);
m_pDynamicsWorld->addAction( m_pCharacter );
}
void PhysicsMgr::AddShape(const Transform& transform, Mesh& mesh)
{
btTriangleMesh* pTriMesh = new btTriangleMesh();
btVector3 v[3];
for (size_t posIdx = 0; posIdx < mesh.positionIndexList.size(); )
{
for (size_t pointIdx = 0; pointIdx < 3; ++pointIdx, ++posIdx)
{
const size_t positionIndex = mesh.positionIndexList[ posIdx ];
const Vector3& pos = mesh.positionList[ positionIndex ];
v[ pointIdx ].setX( pos.asSingle.x );
v[ pointIdx ].setY( pos.asSingle.y );
v[ pointIdx ].setZ( pos.asSingle.z );
}
pTriMesh->addTriangle( v[0], v[1], v[2] );
}
ShapeInfo shapeInfo;
shapeInfo.pShape = new btBvhTriangleMeshShape( pTriMesh, false );
// Create Transform for Shape
btTransform bt;
bt.setIdentity();
bt.setRotation( btQuaternion(btVector3(1.0f, 0.0f, 0.0f), transform.rotation.asArray[0]) );
bt.setRotation( btQuaternion(btVector3(0.0f, 1.0f, 0.0f), transform.rotation.asArray[1]) );
bt.setRotation( btQuaternion(btVector3(0.0f, 0.0f, 1.0f), transform.rotation.asArray[2]) );
bt.setOrigin( btVector3(transform.translation.asArray[0], transform.translation.asArray[1], transform.translation.asArray[2]) );
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
btDefaultMotionState* pMotionState = new btDefaultMotionState( bt );
btScalar mass(0.0f);
btVector3 inertia(0.0f, 0.0f, 0.0f);
btRigidBody::btRigidBodyConstructionInfo rbInfo(mass, pMotionState, shapeInfo.pShape, inertia);
shapeInfo.pRigidBody = new btRigidBody( rbInfo );
//add the body to the dynamics world
m_pDynamicsWorld->addRigidBody( shapeInfo.pRigidBody );
}