Made a working Bullet collision example

git-svn-id: https://openmw.svn.sourceforge.net/svnroot/openmw/trunk@47 ea6a568a-9f4f-0410-981a-c910a81bb256
pull/7/head
nkorslund 16 years ago
parent 1cfaeeb8fc
commit 5fad8ea459

@ -32,12 +32,23 @@ extern(C):
// Initialize the dynamic world. Returns non-zero if an error occurs.
int cpp_initBullet();
void cpp_timeStep(float delta);
void cpp_cleanupBullet();
// Warp the player to a specific location.
void cpp_movePlayer(float x, float y, float z);
// Request that the player moves in this direction
void cpp_setPlayerDir(float x, float y, float z);
// Get the current player position, after physics and collision have
// been applied.
void cpp_getPlayerPos(float *x, float *y, float *z);
// Insert a debug collision object
void cpp_insertBox(float x, float y, float z);
// Move the player's collision shape
int cpp_movePlayerCollision(float x, float y, float z,
float dx, float dy, float dz);
// Move the physics simulation 'delta' seconds forward in time
void cpp_timeStep(float delta);
// Deallocate objects
void cpp_cleanupBullet();

@ -1,196 +1,229 @@
#include "btBulletCollisionCommon.h"
#include "btBulletDynamicsCommon.h"
#include <iostream>
using namespace std;
btDefaultCollisionConfiguration* m_collisionConfiguration;
btCollisionDispatcher *m_dispatcher;
btBroadphaseInterface *m_broadphase;
//btSequentialImpulseConstraintSolver* m_solver;
//btDynamicsWorld *m_dynamicsWorld;
btCollisionWorld *m_collisionWorld;
//btCollisionObject* m_playerObject;
btConvexShape *playerShape;
extern "C" int32_t cpp_initBullet()
class CustomOverlappingPairCallback;
// System variables
btDefaultCollisionConfiguration* g_collisionConfiguration;
btCollisionDispatcher *g_dispatcher;
//btBroadphaseInterface *g_broadphase;
btAxisSweep3 *g_broadphase;
btSequentialImpulseConstraintSolver* g_solver;
btDynamicsWorld *g_dynamicsWorld;
// Player variables
btCollisionObject* g_playerObject;
btConvexShape *g_playerShape;
// Player position. This is updated automatically by the physics
// system based on g_walkDirection and collisions. It is read by D
// code through cpp_getPlayerPos().
btVector3 g_playerPosition;
// Walking vector - defines direction and speed that the player
// intends to move right now. This is updated from D code each frame
// through cpp_setPlayerDir(), based on player input (and later, AI
// decisions.) The units of the vector are points per second.
btVector3 g_walkDirection;
// These variables and the class below are used in player collision
// detection. The callback is injected into the broadphase and keeps a
// continuously updated list of what objects are colliding with the
// player (in g_pairCache). This list is used in the function called
// recoverFromPenetration() below.
btHashedOverlappingPairCache* g_pairCache;
CustomOverlappingPairCallback *g_customPairCallback;
// Include the player physics
#include "cpp_player.cpp"
class CustomOverlappingPairCallback : public btOverlappingPairCallback
{
// Set up basic objects
m_collisionConfiguration = new btDefaultCollisionConfiguration();
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
m_broadphase = new btDbvtBroadphase();
m_collisionWorld =
new btCollisionWorld(m_dispatcher, m_broadphase,
m_collisionConfiguration);
/*m_solver = new btSequentialImpulseConstraintSolver;
m_dynamicsWorld =
new btDiscreteDynamicsWorld(m_dispatcher, m_broadphase,
m_solver, m_collisionConfiguration);
m_dynamicsWorld->setGravity(btVector3(0,-10,0));
public:
virtual btBroadphasePair* addOverlappingPair(btBroadphaseProxy* proxy0,
btBroadphaseProxy* proxy1)
{
if (proxy0->m_clientObject==g_playerObject ||
proxy1->m_clientObject==g_playerObject)
return g_pairCache->addOverlappingPair(proxy0,proxy1);
return 0;
}
virtual void* removeOverlappingPair(btBroadphaseProxy* proxy0,
btBroadphaseProxy* proxy1,
btDispatcher* dispatcher)
{
if (proxy0->m_clientObject==g_playerObject ||
proxy1->m_clientObject==g_playerObject)
return g_pairCache->removeOverlappingPair(proxy0,proxy1,dispatcher);
return 0;
}
void removeOverlappingPairsContainingProxy(btBroadphaseProxy* proxy0,
btDispatcher* dispatcher)
{ if (proxy0->m_clientObject==g_playerObject)
g_pairCache->removeOverlappingPairsContainingProxy(proxy0,dispatcher);
}
/* KILLME
btBroadphasePairArray& getOverlappingPairArray()
{ return g_pairCache->getOverlappingPairArray(); }
btOverlappingPairCache* getOverlappingPairCache()
{ return g_pairCache; }
*/
};
// Create player collision object
//playerShape = new btCylinderShape(btVector3(50, 50, 50));
playerShape = new btSphereShape(50);
/*
m_playerObject = new btCollisionObject ();
m_playerObject->setCollisionShape (m_shape);
m_playerObject->setCollisionFlags (btCollisionObject::CF_NO_CONTACT_RESPONSE);
*/
extern "C" int32_t cpp_initBullet()
{
// ------- SET UP THE WORLD -------
/*
// Dynamic shapes:
// Set up basic objects
g_collisionConfiguration = new btDefaultCollisionConfiguration();
g_dispatcher = new btCollisionDispatcher(g_collisionConfiguration);
//g_broadphase = new btDbvtBroadphase();
g_solver = new btSequentialImpulseConstraintSolver;
// Re-using the same collision is better for memory usage and
// performance.
// TODO: Figure out what to do with this. We need the user callback
// function used below (I think), but this is only offered by this
// broadphase implementation (as far as I can see.)
btVector3 worldMin(-100000,-100000,-100000);
btVector3 worldMax(100000,100000,100000);
g_broadphase = new btAxisSweep3(worldMin,worldMax);
btCollisionShape* colShape = new btBoxShape(btVector3(1,1,1));
//btCollisionShape* colShape = new btSphereShape(btScalar(1.));
//m_collisionShapes.push_back(colShape);
g_dynamicsWorld =
new btDiscreteDynamicsWorld(g_dispatcher,
g_broadphase,
g_solver,
g_collisionConfiguration);
// Create Dynamic Objects
btTransform startTransform;
startTransform.setIdentity();
//g_dynamicsWorld->setGravity(btVector3(0,-10,0));
mass = 1.f;
colShape->calculateLocalInertia(mass,localInertia);
// ------- SET UP THE PLAYER -------
///create 125 (5x5x5) dynamic objects
#define ARRAY_SIZE_X 5
#define ARRAY_SIZE_Y 5
#define ARRAY_SIZE_Z 5
// Create the player collision shape.
float width = 50;
//float height = 50;
/*
// One possible shape is the convex hull around two spheres
btVector3 spherePositions[2];
btScalar sphereRadii[2];
sphereRadii[0] = width;
sphereRadii[1] = width;
spherePositions[0] = btVector3 (0.0, height/2.0, 0.0);
spherePositions[1] = btVector3 (0.0, -height/2.0, 0.0);
m_shape = new btMultiSphereShape(btVector3(width/2.0, height/2.0, width/2.0),
&spherePositions[0], &sphereRadii[0], 2);
*/
//g_playerShape = new btCylinderShape(btVector3(50, 50, 50));
g_playerShape = new btSphereShape(width);
#define START_POS_X -5
#define START_POS_Y -5
#define START_POS_Z -3
// Create the collision object
g_playerObject = new btCollisionObject ();
g_playerObject->setCollisionShape (g_playerShape);
g_playerObject->setCollisionFlags (btCollisionObject::CF_NO_CONTACT_RESPONSE);
float start_x = START_POS_X - ARRAY_SIZE_X/2;
float start_y = START_POS_Y;
float start_z = START_POS_Z - ARRAY_SIZE_Z/2;
for (int k=0;k<ARRAY_SIZE_Y;k++)
for (int i=0;i<ARRAY_SIZE_X;i++)
for(int j = 0;j<ARRAY_SIZE_Z;j++)
{
startTransform.setOrigin(btVector3(2.0*i + start_x,
10+2.0*k + start_y,
2.0*j + start_z));
// ------- OTHER STUFF -------
btDefaultMotionState* myMotionState =
new btDefaultMotionState(startTransform);
// Create a custom callback to pick out all the objects colliding
// with the player. We use this in the collision recovery phase.
g_pairCache = new btHashedOverlappingPairCache();
g_customPairCallback = new CustomOverlappingPairCallback();
g_broadphase->setOverlappingPairUserCallback(g_customPairCallback);
btRigidBody::btRigidBodyConstructionInfo
rbInfo(mass,myMotionState,colShape,localInertia);
// Set up the callback that moves the player at the end of each
// simulation step.
g_dynamicsWorld->setInternalTickCallback(playerStepCallback);
btRigidBody* body = new btRigidBody(rbInfo);
body->setActivationState(ISLAND_SLEEPING);
// Add the character collision object to the world.
g_dynamicsWorld->addCollisionObject(g_playerObject
,btBroadphaseProxy::DebrisFilter
//,btBroadphaseProxy::StaticFilter
);
m_dynamicsWorld->addRigidBody(body);
body->setActivationState(ISLAND_SLEEPING);
}
*/
// Success!
return 0;
}
extern "C" int32_t cpp_movePlayerCollision(float x, float y, float z,
float dx, float dy, float dz)
// Warp the player to a specific location. We do not bother setting
// rotation, since it's completely irrelevant for collision detection.
extern "C" void cpp_movePlayer(float x, float y, float z)
{
btTransform start, end;
start.setIdentity();
end.setIdentity();
// The sweep test moves the shape from the old position to the
// new. The 0.1 offset in one of the coordinates is to make sure a
// sweep is performed even when the player does not move.
start.setOrigin(btVector3(x, y, z));
end.setOrigin(btVector3(x+dx,y+dy,z+dz));
btCollisionWorld::ClosestConvexResultCallback cb(btVector3(0,0,0),
btVector3(0,0,0));
btTransform tr;
tr.setIdentity();
tr.setOrigin(btVector3(x,y,z));
g_playerObject->setWorldTransform(tr);
}
m_collisionWorld->convexSweepTest(playerShape, start, end, cb);
// Request that the player moves in this direction
extern "C" void cpp_setPlayerDir(float x, float y, float z)
{ g_walkDirection.setValue(x,y,z); }
if(cb.hasHit()) return 1;
else return 0;
// Get the current player position, after physics and collision have
// been applied.
extern "C" void cpp_getPlayerPos(float *x, float *y, float *z)
{
*x = g_playerPosition.getX();
*y = g_playerPosition.getY();
*z = g_playerPosition.getZ();
}
// Insert a debug collision shape
extern "C" void cpp_insertBox(float x, float y, float z)
{
btCollisionShape* groundShape =
new btSphereShape(50);
//new btBoxShape(btVector3(100,100,100));
// Create a motion state to hold the object (not sure why yet.)
btTransform groundTransform;
groundTransform.setIdentity();
groundTransform.setOrigin(btVector3(x,y,z));
btCollisionObject *obj = new btCollisionObject;
obj->setCollisionShape(groundShape);
obj->setWorldTransform(groundTransform);
m_collisionWorld->addCollisionObject(obj);
/*
m_collisionWorld->addCollisionObject(obj,
btBroadphaseProxy::DebrisFilter, // ??
btBroadphaseProxy::StaticFilter); // Only static objects
/*
btDefaultMotionState* myMotionState =
new btDefaultMotionState(groundTransform);
// Create a rigid body from the motion state. Give it zero mass and
// inertia.
btRigidBody::btRigidBodyConstructionInfo
rbInfo(0, myMotionState, groundShape, btVector3(0,0,0));
btRigidBody* body = new btRigidBody(rbInfo);
// Add the body to the dynamics world
m_dynamicsWorld->addRigidBody(body);
*/
// Add the body to the world
g_dynamicsWorld->addRigidBody(body);
}
/*
// Move the physics simulation 'delta' seconds forward in time
extern "C" void cpp_timeStep(float delta)
{
// TODO: Find what unit Bullet uses here
m_dynamicsWorld->stepSimulation(delta / 1000.f);
// TODO: We might experiment with the number of time steps. Remember
// that the function also returns the number of steps performed.
g_dynamicsWorld->stepSimulation(delta,2);
}
*/
// Cleanup in the reverse order of creation/initialization
extern "C" void cpp_cleanupBullet()
{
// Remove the rigidbodies from the dynamics world and delete them
for (int i=m_collisionWorld->getNumCollisionObjects()-1; i>=0 ;i--)
for (int i=g_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--)
{
btCollisionObject* obj = m_collisionWorld->getCollisionObjectArray()[i];
/*
btCollisionObject* obj = g_dynamicsWorld->getCollisionObjectArray()[i];
btRigidBody* body = btRigidBody::upcast(obj);
if (body && body->getMotionState())
delete body->getMotionState();
*/
m_collisionWorld->removeCollisionObject( obj );
g_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 m_collisionWorld;
//delete m_solver;
delete m_broadphase;
delete m_dispatcher;
delete m_collisionConfiguration;
delete g_dynamicsWorld;
delete g_solver;
delete g_broadphase;
delete g_dispatcher;
delete g_collisionConfiguration;
}

@ -0,0 +1,303 @@
// This file handles player-specific physics and collision detection
// TODO: Later we might handle various physics modes, eg. dynamic
// (full physics), player_walk, player_fall, player_swim, player_float,
// player_levitate, player_ghost. These would be applicable to any
// object (through Monster script), allowing player physics to be used
// on NPCs and creatures.
// Variables used internally in this file. Once we make per-object
// player collision, these will be member variables.
bool g_touchingContact;
btVector3 g_touchingNormal;
// Returns the reflection direction of a ray going 'direction' hitting
// a surface with normal 'normal'
btVector3 reflect (const btVector3& direction, const btVector3& normal)
{ return direction - (btScalar(2.0) * direction.dot(normal)) * normal; }
// Returns the portion of 'direction' that is perpendicular to
// 'normal'
btVector3 perpComponent (const btVector3& direction, const btVector3& normal)
{ return direction - normal * direction.dot(normal); }
btManifoldArray manifoldArray;
// Callback used for collision detection sweep tests. It prevents self
// collision and is used in calls to convexSweepTest().
class ClosestNotMeConvexResultCallback : public btCollisionWorld::ClosestConvexResultCallback
{
public:
ClosestNotMeConvexResultCallback()
: btCollisionWorld::ClosestConvexResultCallback
(btVector3(0.0, 0.0, 0.0), btVector3(0.0, 0.0, 0.0))
{
m_collisionFilterGroup = g_playerObject->
getBroadphaseHandle()->m_collisionFilterGroup;
m_collisionFilterMask = g_playerObject->
getBroadphaseHandle()->m_collisionFilterMask;
}
btScalar addSingleResult(btCollisionWorld::LocalConvexResult&
convexResult, bool normalInWorldSpace)
{
if (convexResult.m_hitCollisionObject == g_playerObject) return 1.0;
return ClosestConvexResultCallback::addSingleResult
(convexResult, normalInWorldSpace);
}
};
/* Used to step up small steps and slopes. Not done.
void KinematicCharacterController::stepUp (const btCollisionWorld* world)
{
// phase 1: up
btVector3 targetPosition = g_playerPosition + btVector3 (btScalar(0.0), m_stepHeight, btScalar(0.0));
btTransform start, end;
start.setIdentity ();
end.setIdentity ();
// FIXME: Handle penetration properly
start.setOrigin (g_playerPosition + btVector3(0.0, 0.1, 0.0));
end.setOrigin (targetPosition);
ClosestNotMeConvexResultCallback callback (g_playerObject);
world->convexSweepTest (g_playerShape, start, end, callback);
if (callback.hasHit())
{
// we moved up only a fraction of the step height
m_currentStepOffset = m_stepHeight * callback.m_closestHitFraction;
g_playerPosition.setInterpolate3(g_playerPosition, targetPosition,
callback.m_closestHitFraction);
}
else
{
m_currentStepOffset = m_stepHeight;
g_playerPosition = targetPosition;
}
}
*/
void updateTargetPositionBasedOnCollision (const btVector3& hitNormal,
btVector3 &targetPosition)
{
btVector3 movementDirection = targetPosition - g_playerPosition;
btScalar movementLength = movementDirection.length();
if (movementLength <= SIMD_EPSILON)
return;
// Is this needed?
movementDirection.normalize();
btVector3 reflectDir = reflect(movementDirection, hitNormal);
reflectDir.normalize();
btVector3 perpendicularDir = perpComponent (reflectDir, hitNormal);
targetPosition = g_playerPosition;
targetPosition += perpendicularDir * movementLength;
}
// This covers all normal forward movement and collision, including
// walking sideways when hitting a wall at an angle. It does NOT
// handle walking up slopes and steps, or falling/gravity.
void stepForward(btVector3& walkMove)
{
btVector3 originalDir = walkMove.normalized();
// If no walking direction is given, we still run the function. This
// allows moving forces to push the player around even if she is
// standing still.
if (walkMove.length() < SIMD_EPSILON)
originalDir.setValue(0.f,0.f,0.f);
btTransform start, end;
btVector3 targetPosition = g_playerPosition + walkMove;
start.setIdentity ();
end.setIdentity ();
btScalar fraction = 1.0;
btScalar distance2 = (g_playerPosition-targetPosition).length2();
if (g_touchingContact)
if (originalDir.dot(g_touchingNormal) > btScalar(0.0))
updateTargetPositionBasedOnCollision (g_touchingNormal, targetPosition);
int maxIter = 10;
while (fraction > btScalar(0.01) && maxIter-- > 0)
{
start.setOrigin (g_playerPosition);
end.setOrigin (targetPosition);
ClosestNotMeConvexResultCallback callback;
g_dynamicsWorld->convexSweepTest (g_playerShape, start, end, callback);
fraction -= callback.m_closestHitFraction;
if (callback.hasHit())
{
// We moved only a fraction
btScalar hitDistance = (callback.m_hitPointWorld - g_playerPosition).length();
// If the distance is further than the collision margin,
// move
if (hitDistance > 0.05)
g_playerPosition.setInterpolate3(g_playerPosition, targetPosition,
callback.m_closestHitFraction);
updateTargetPositionBasedOnCollision(callback.m_hitNormalWorld,
targetPosition);
btVector3 currentDir = targetPosition - g_playerPosition;
distance2 = currentDir.length2();
if (distance2 <= SIMD_EPSILON)
break;
currentDir.normalize();
if (currentDir.dot(originalDir) <= btScalar(0.0))
break;
}
else
// we moved the whole way
g_playerPosition = targetPosition;
}
}
/* Not done. Will handle gravity, falling, sliding, etc.
void KinematicCharacterController::stepDown (const btCollisionWorld* g_dynamicsWorld, btScalar dt)
{
btTransform start, end;
// phase 3: down
btVector3 step_drop = btVector3(btScalar(0.0), m_currentStepOffset, btScalar(0.0));
btVector3 gravity_drop = btVector3(btScalar(0.0), m_stepHeight, btScalar(0.0));
targetPosition -= (step_drop + gravity_drop);
start.setIdentity ();
end.setIdentity ();
start.setOrigin (g_playerPosition);
end.setOrigin (targetPosition);
ClosestNotMeConvexResultCallback callback (g_playerObject);
g_dynamicsWorld->convexSweepTest (g_playerShape, start, end, callback);
if (callback.hasHit())
{
// we dropped a fraction of the height -> hit floor
g_playerPosition.setInterpolate3 (g_playerPosition, targetPosition, callback.m_closestHitFraction);
} else {
// we dropped the full height
g_playerPosition = targetPosition;
}
}
*/
// Check if the player currently collides with anything, and adjust
// its position accordingly. Returns true if collisions were found.
bool recoverFromPenetration()
{
bool penetration = false;
// Update the collision pair cache
g_dispatcher->dispatchAllCollisionPairs(g_pairCache,
g_dynamicsWorld->getDispatchInfo(),
g_dispatcher);
g_playerPosition = g_playerObject->getWorldTransform().getOrigin();
btScalar maxPen = 0.0;
for (int i = 0; i < g_pairCache->getNumOverlappingPairs(); i++)
{
manifoldArray.resize(0);
btBroadphasePair* collisionPair = &g_pairCache->getOverlappingPairArray()[i];
// Get the contact points
if (collisionPair->m_algorithm)
collisionPair->m_algorithm->getAllContactManifolds(manifoldArray);
// And handle them
for (int j=0;j<manifoldArray.size();j++)
{
btPersistentManifold* manifold = manifoldArray[j];
btScalar directionSign = manifold->getBody0() ==
g_playerObject ? btScalar(-1.0) : btScalar(1.0);
for (int p=0;p<manifold->getNumContacts();p++)
{
const btManifoldPoint &pt = manifold->getContactPoint(p);
if (pt.getDistance() < 0.0)
{
// Pick out the maximum penetration normal and store
// it
if (pt.getDistance() < maxPen)
{
maxPen = pt.getDistance();
g_touchingNormal = pt.m_normalWorldOnB * directionSign;//??
}
g_playerPosition += pt.m_normalWorldOnB * directionSign *
pt.getDistance() * btScalar(0.2);
penetration = true;
}
}
}
}
btTransform newTrans = g_playerObject->getWorldTransform();
newTrans.setOrigin(g_playerPosition);
g_playerObject->setWorldTransform(newTrans);
return penetration;
}
// Callback called at the end of each simulation cycle. This is the
// main function is responsible for player movement.
void playerStepCallback(btDynamicsWorld* dynamicsWorld, btScalar timeStep)
{
// Before moving, recover from current penetrations
int numPenetrationLoops = 0;
g_touchingContact = false;
while (recoverFromPenetration())
{
numPenetrationLoops++;
g_touchingContact = true;
// Make sure we don't stay here indefinitely
if (numPenetrationLoops > 4)
break;
}
// Get the player position
btTransform xform;
xform = g_playerObject->getWorldTransform ();
g_playerPosition = xform.getOrigin();
// Next, do the walk.
// TODO: Walking direction should be set from D code, and the final
// position should be retrieved back from C++. The walking direction
// always reflects the intentional action of an agent (ie. the
// player or the AI), but the end result comes from collision and
// physics.
btVector3 walkStep = g_walkDirection * timeStep;
//stepUp();
stepForward(walkStep);
//stepDown(dt);
// Move the player (but keep rotation)
xform = g_playerObject->getWorldTransform ();
xform.setOrigin (g_playerPosition);
g_playerObject->setWorldTransform (xform);
}

@ -243,13 +243,18 @@ float musCumTime = 0;
void initializeInput()
{
// Move the camera in place
// Move the player into place. TODO: This isn't really input-related
// at all, and should be moved.
with(playerData.position)
{
cpp_moveCamera(position[0], position[1], position[2],
rotation[0], rotation[1], rotation[2]);
// TODO: Think about renaming these functions to ogre_moveCamera
// and bullet_movePlayer etc.
cpp_moveCamera(position[0], position[1], position[2]);
cpp_setCameraRotation(rotation[0], rotation[1], rotation[2]);
// Insert a collision box close to the player
cpp_movePlayer(position[0], position[1], position[2]);
// Insert a collision shape close to the player
cpp_insertBox(position[0], position[1]+500, position[2]);
cpp_drawBox(position[0], position[1]+500, position[2]);
}
@ -299,12 +304,12 @@ extern(C) int d_frameStarted(float time)
// The rest is ignored in pause mode
if(pause) return 1;
const float moveSpeed = 900;
float speed = moveSpeed * time;
// Walking / floating speed, in points per second.
const float speed = 300;
// Check if the movement keys are pressed
float moveX = 0, moveY = 0, moveZ = 0;
float x, y, z;
float x, y, z, ox, oy, oz;
if(isPressed(Keys.MoveLeft)) moveX -= speed;
if(isPressed(Keys.MoveRight)) moveX += speed;
@ -313,21 +318,34 @@ extern(C) int d_frameStarted(float time)
if(isPressed(Keys.MoveUp)) moveY += speed;
if(isPressed(Keys.MoveDown)) moveY -= speed;
// Move the player. This is a temporary hack, we should do this more
// efficiently in C++.
if(moveX != 0 || moveY !=0 || moveZ != 0)
{
cpp_moveCameraRel(moveX, moveY, moveZ);
cpp_getCameraPos(&x, &y, &z);
bool nw = cpp_movePlayerCollision(x, y, z, moveX, moveY, moveZ) != 0;
if(nw != collides)
{
if(nw) writefln("Entered shape");
else writefln("Left shape");
collides = nw;
}
}
// This isn't very elegant, but it's simple and it works.
// Get the current coordinates
cpp_getCameraPos(&ox, &oy, &oz);
// Move camera using relative coordinates. TODO: We won't really
// need to move the camera here (since it's moved below anyway), we
// only want the transformation from camera space to world
// space. This can likely be done more efficiently.
cpp_moveCameraRel(moveX, moveY, moveZ);
// Get the result
cpp_getCameraPos(&x, &y, &z);
// The result is the real movement direction, in world coordinates
moveX = x-ox;
moveY = y-oy;
moveZ = z-oz;
// Tell Bullet that this is where we want to go
cpp_setPlayerDir(moveX, moveY, moveZ);
// Perform a Bullet time step
cpp_timeStep(time);
// Get the final (actual) player position and update the camera
cpp_getPlayerPos(&x, &y, &z);
cpp_moveCamera(x,y,z);
sndCumTime += time;
if(sndCumTime > sndRefresh)

@ -142,7 +142,8 @@ void cpp_screenshot(char *filename);
// Camera control and information
void cpp_rotateCamera(float x, float y);
void cpp_moveCamera(float x, float y, float z, float r1, float r2, float r3);
void cpp_moveCamera(float x, float y, float z);
void cpp_setCameraRotation(float r1, float r2, float r3);
void cpp_getCameraPos(float *x, float *y, float *z);
void cpp_getCameraOrientation(float *fx, float *fy, float *fz, float *ux, float *uy, float *uz);
void cpp_moveCameraRel(float x, float y, float z);

@ -132,7 +132,8 @@ extern "C" void cpp_getCameraPos(float *x, float *y, float *z)
*z = pos[1];
}
// Get current camera orientation
// Get current camera orientation, in the form of 'front' and 'up'
// vectors.
extern "C" void cpp_getCameraOrientation(float *fx, float *fy, float *fz,
float *ux, float *uy, float *uz)
{
@ -146,18 +147,21 @@ extern "C" void cpp_getCameraOrientation(float *fx, float *fy, float *fz,
*uz = up[1];
}
// Move and rotate camera in place.
extern "C" void cpp_moveCamera(float x, float y, float z,
float r1, float r2, float r3)
// Move camera
extern "C" void cpp_moveCamera(float x, float y, float z)
{
// Transforms Morrowind coordinates to OGRE coordinates. The camera
// is not affected by the rotation of the root node, so we must
// transform this manually.
mCamera->setPosition(Vector3(x,z,-y));
}
// Rotation is probably not correct, but for now I have no reference
// point. Fix it later when we teleport from one cell to another, so
// we have something to compare against.
// Rotate camera using Morrowind rotation specifiers
extern "C" void cpp_setCameraRotation(float r1, float r2, float r3)
{
// TODO: This translation is probably not correct, but for now I
// have no reference point. Fix it later when we teleport from one
// cell to another, so we have something to compare against.
// Rotate around X axis
Quaternion xr(Radian(-r1), Vector3::UNIT_X);
@ -170,7 +174,7 @@ extern "C" void cpp_moveCamera(float x, float y, float z,
mCamera->setOrientation(xr*yr*zr);
}
// Move camera relative to its own axis set
// Move camera relative to its own axis set.
extern "C" void cpp_moveCameraRel(float x, float y, float z)
{
mCamera->moveRelative(Vector3(x,y,z));

Loading…
Cancel
Save