Ver Fonte

Reimplemented the collision listener mechanism (old mechanism had a huge inefficiency).

Adds ray intersection test API on the physics controller.
Adds implicit conversion between GamePlay and Bullet vector3 and quaternion objects.

Updates collision listener interface to notify when a collision starts and stops and also to pass both contact points of a collision.
Fixed a minor bug in Texture creation code (missing NULL check).
Minor fix for mesh rigid bodies (scale stuff).

Adding support for "!=" operations on vectors.

Added MATH_CLAMP macro.
Fixed a minor bug in Matrix::decompose (related to precision).
Fixed a bug with mesh rigid bodies when loading from a .scene file (where the node is being renamed).
Fixed some bugs for attaching rigid bodies to nodes with world scale.
Fixed a bug with mesh rigid bodies (incorrect triangle index stride values).
Minor bug fix with kinematic rigid body transform update (rotation decomposition from Matrix wasn't accurate).
Minor optimization in PhysicsMotionState.
Chris Culy há 14 anos atrás
pai
commit
3f71dec55c

+ 2 - 0
gameplay/src/Base.h

@@ -17,6 +17,7 @@
 #include <string>
 #include <vector>
 #include <list>
+#include <set>
 #include <stack>
 #include <map>
 #include <algorithm>
@@ -145,6 +146,7 @@ extern void printError(const char* format, ...);
 #define MATH_PIOVER4                M_PI_4
 #define MATH_PIX2                   6.28318530717958647693f
 #define MATH_EPSILON                0.000001f
+#define MATH_CLAMP(x, lo, hi)       ((x < lo) ? lo : ((x > hi) ? hi : x))
 #ifndef M_1_PI
 #define M_1_PI                      0.31830988618379067154
 #endif

+ 1 - 1
gameplay/src/Matrix.cpp

@@ -460,7 +460,7 @@ bool Matrix::decompose(Vector3* scale, Quaternion* rotation, Vector3* translatio
     // Now calculate the rotation from the resulting matrix (axes).
     float trace = xaxis.x + yaxis.y + zaxis.z + 1.0f;
 
-    if (trace > MATH_TOLERANCE)
+    if (trace > MATH_EPSILON)
     {
         float s = 0.5f / sqrt(trace);
         rotation->w = 0.25f / s;

+ 2 - 2
gameplay/src/Package.cpp

@@ -1089,7 +1089,7 @@ Mesh* Package::loadMesh(const char* id, bool loadWithMeshRBSupport, const char*
     }
     mesh->setVertexData(vertexData, 0, vertexCount);
     if (loadWithMeshRBSupport)
-        SceneLoader::addMeshRigidBodyData(nodeId, mesh, vertexData, vertexByteCount);
+        SceneLoader::addMeshRigidBodyData(_path, nodeId, mesh, vertexData, vertexByteCount);
     SAFE_DELETE_ARRAY(vertexData);
 
     // Set mesh bounding volumes
@@ -1150,7 +1150,7 @@ Mesh* Package::loadMesh(const char* id, bool loadWithMeshRBSupport, const char*
         }
         part->setIndexData(indexData, 0, indexCount);
         if (loadWithMeshRBSupport)
-            SceneLoader::addMeshRigidBodyData(nodeId, indexData, iByteCount);
+            SceneLoader::addMeshRigidBodyData(_path, nodeId, indexData, iByteCount);
         SAFE_DELETE_ARRAY(indexData);
     }
 

+ 1 - 1
gameplay/src/PhysicsConstraint.cpp

@@ -118,7 +118,7 @@ btTransform PhysicsConstraint::getTransformOffset(const Node* node, const Vector
     
     t = offsetByCenterOfMass(node, t);
 
-    return btTransform(btQuaternion(r.x, r.y, r.z, r.w), btVector3(t.x, t.y, t.z));
+    return btTransform(r, t);
 }
 
 Vector3 PhysicsConstraint::getWorldCenterOfMass(const Model* model)

+ 146 - 51
gameplay/src/PhysicsController.cpp

@@ -11,6 +11,10 @@
 namespace gameplay
 {
 
+const int PhysicsController::DIRTY         = 0x01;
+const int PhysicsController::COLLISION     = 0x02;
+const int PhysicsController::REGISTERED    = 0x04;
+
 PhysicsController::PhysicsController()
   : _collisionConfiguration(NULL), _dispatcher(NULL),
     _overlappingPairCache(NULL), _solver(NULL), _world(NULL), _debugDrawer(NULL), 
@@ -114,7 +118,7 @@ void PhysicsController::setGravity(const Vector3& gravity)
     _gravity = gravity;
 
     if (_world)
-        _world->setGravity(btVector3(_gravity.x, _gravity.y, _gravity.z));
+        _world->setGravity(_gravity);
 }
 
 void PhysicsController::drawDebug(const Matrix& viewProjection)
@@ -124,6 +128,83 @@ void PhysicsController::drawDebug(const Matrix& viewProjection)
     _debugDrawer->end();
 }
 
+PhysicsRigidBody* PhysicsController::rayTest(const Ray& ray)
+{
+    btCollisionWorld::ClosestRayResultCallback callback(ray.getOrigin(), ray.getDirection());
+    _world->rayTest(ray.getOrigin(), ray.getDirection(), callback);
+    if (callback.hasHit())
+        return getRigidBody(callback.m_collisionObject);
+
+    return NULL;
+}
+
+btScalar PhysicsController::addSingleResult(btManifoldPoint& cp, const btCollisionObject* a, int partIdA, int indexA, 
+    const btCollisionObject* b, int partIdB, int indexB)
+{
+    // Get pointers to the PhysicsRigidBody objects.
+    PhysicsRigidBody* rbA = Game::getInstance()->getPhysicsController()->getRigidBody(a);
+    PhysicsRigidBody* rbB = Game::getInstance()->getPhysicsController()->getRigidBody(b);
+    
+    // If the given rigid body pair has collided in the past, then
+    // we notify the listeners only if the pair was not colliding
+    // during the previous frame. Otherwise, it's a new pair, so add a
+    // new entry to the cache with the appropriate listeners and notify them.
+    PhysicsRigidBody::CollisionPair pair(rbA, rbB);
+    if (_collisionStatus.count(pair) > 0)
+    {
+        const CollisionInfo& collisionInfo = _collisionStatus[pair];
+        if ((collisionInfo._status & COLLISION) == 0)
+        {
+            std::vector<PhysicsRigidBody::Listener*>::const_iterator iter = collisionInfo._listeners.begin();
+            for (; iter != collisionInfo._listeners.end(); iter++)
+            {
+                (*iter)->collisionEvent(PhysicsRigidBody::Listener::COLLIDING, pair, Vector3(cp.getPositionWorldOnA().x(), cp.getPositionWorldOnA().y(), cp.getPositionWorldOnA().z()),
+                    Vector3(cp.getPositionWorldOnB().x(), cp.getPositionWorldOnB().y(), cp.getPositionWorldOnB().z()));
+            }
+        }
+    }
+    else
+    {
+        CollisionInfo& collisionInfo = _collisionStatus[pair];
+
+        // Add the appropriate listeners.
+        PhysicsRigidBody::CollisionPair p1(pair._rbA, NULL);
+        if (_collisionStatus.count(p1) > 0)
+        {
+            const CollisionInfo& ci = _collisionStatus[p1];
+            std::vector<PhysicsRigidBody::Listener*>::const_iterator iter = ci._listeners.begin();
+            for (; iter != ci._listeners.end(); iter++)
+            {
+                collisionInfo._listeners.push_back(*iter);
+            }
+        }
+        PhysicsRigidBody::CollisionPair p2(pair._rbB, NULL);
+        if (_collisionStatus.count(p2) > 0)
+        {
+            const CollisionInfo& ci = _collisionStatus[p2];
+            std::vector<PhysicsRigidBody::Listener*>::const_iterator iter = ci._listeners.begin();
+            for (; iter != ci._listeners.end(); iter++)
+            {
+                collisionInfo._listeners.push_back(*iter);
+            }
+        }
+
+        std::vector<PhysicsRigidBody::Listener*>::iterator iter = collisionInfo._listeners.begin();
+        for (; iter != collisionInfo._listeners.end(); iter++)
+        {
+            (*iter)->collisionEvent(PhysicsRigidBody::Listener::COLLIDING, pair, Vector3(cp.getPositionWorldOnA().x(), cp.getPositionWorldOnA().y(), cp.getPositionWorldOnA().z()),
+                Vector3(cp.getPositionWorldOnB().x(), cp.getPositionWorldOnB().y(), cp.getPositionWorldOnB().z()));
+        }
+    }
+
+    // Update the collision status cache (we remove the dirty bit
+    // set in the controller's update so that this particular collision pair's
+    // status is not reset to 'no collision' when the controller's update completes).
+    _collisionStatus[pair]._status &= ~DIRTY;
+    _collisionStatus[pair]._status |= COLLISION;
+    return 0.0f;
+}
+
 void PhysicsController::initialize()
 {
     _collisionConfiguration = new btDefaultCollisionConfiguration();
@@ -133,7 +214,7 @@ void PhysicsController::initialize()
 
     // Create the world.
     _world = new btDiscreteDynamicsWorld(_dispatcher, _overlappingPairCache, _solver, _collisionConfiguration);
-    _world->setGravity(btVector3(_gravity.x, _gravity.y, _gravity.z));
+    _world->setGravity(_gravity);
 
     // Set up debug drawing.
     _debugDrawer = new DebugDrawer();
@@ -217,67 +298,57 @@ void PhysicsController::update(long elapsedTime)
     // set to COLLISION and the DIRTY bit is cleared. Then, after collision processing 
     // is finished, if a given status is still dirty, the COLLISION bit is cleared.
 
-    // Dirty all the collision listeners' collision status caches.
-    for (unsigned int i = 0; i < _bodies.size(); i++)
+    // Dirty the collision status cache entries.
+    std::map<PhysicsRigidBody::CollisionPair, CollisionInfo>::iterator iter = _collisionStatus.begin();
+    for (; iter != _collisionStatus.end(); iter++)
     {
-        if (_bodies[i]->_listeners)
-        {
-            for (unsigned int k = 0; k < _bodies[i]->_listeners->size(); k++)
-            {
-                std::map<PhysicsRigidBody::CollisionPair, int>::iterator iter = (*_bodies[i]->_listeners)[k]->_collisionStatus.begin();
-                for (; iter != (*_bodies[i]->_listeners)[k]->_collisionStatus.end(); iter++)
-                {
-                    iter->second |= PhysicsRigidBody::Listener::DIRTY;
-                }
-            }
-        }
+        iter->second._status |= DIRTY;
     }
 
-    // Go through the physics rigid bodies and update the collision listeners.
-    for (unsigned int i = 0; i < _bodies.size(); i++)
+    // Go through the collision status cache and perform all registered collision tests.
+    iter = _collisionStatus.begin();
+    for (; iter != _collisionStatus.end(); iter++)
     {
-        if (_bodies[i]->_listeners)
+        // If this collision pair was one that was registered for listening, then perform the collision test.
+        // (In the case where we register for all collisions with a rigid body, there will be a lot
+        // of collision pairs in the status cache that we did not explicitly register for.)
+        if ((iter->second._status & REGISTERED) != 0)
         {
-            for (unsigned int k = 0; k < _bodies[i]->_listeners->size(); k++)
-            {
-                std::map<PhysicsRigidBody::CollisionPair, int>::iterator iter = (*_bodies[i]->_listeners)[k]->_collisionStatus.begin();
-                for (; iter != (*_bodies[i]->_listeners)[k]->_collisionStatus.end(); iter++)
-                {
-                    // If this collision pair was one that was registered for listening, then perform the collision test.
-                    // (In the case where we register for all collisions with a rigid body, there will be a lot
-                    // of collision pairs in the status cache that we did not explicitly register for.)
-                    if ((iter->second & PhysicsRigidBody::Listener::REGISTERED) != 0)
-                    {
-                        if (iter->first._rbB)
-                            Game::getInstance()->getPhysicsController()->_world->contactPairTest(iter->first._rbA->_body, iter->first._rbB->_body, *(*_bodies[i]->_listeners)[k]);
-                        else
-                            Game::getInstance()->getPhysicsController()->_world->contactTest(iter->first._rbA->_body, *(*_bodies[i]->_listeners)[k]);
-                    }
-                }   
-            }
+            if (iter->first._rbB)
+                _world->contactPairTest(iter->first._rbA->_body, iter->first._rbB->_body, *this);
+            else
+                _world->contactTest(iter->first._rbA->_body, *this);
         }
     }
 
-    // Go through all the collision listeners and update their collision status caches.
-    for (unsigned int i = 0; i < _bodies.size(); i++)
+    // Update all the collision status cache entries.
+    iter = _collisionStatus.begin();
+    for (; iter != _collisionStatus.end(); iter++)
     {
-        if (_bodies[i]->_listeners)
+        if ((iter->second._status & DIRTY) != 0)
         {
-            for (unsigned int k = 0; k < _bodies[i]->_listeners->size(); k++)
+            if ((iter->second._status & COLLISION) != 0 && iter->first._rbB)
             {
-                std::map<PhysicsRigidBody::CollisionPair, int>::iterator iter = (*_bodies[i]->_listeners)[k]->_collisionStatus.begin();
-                for (; iter != (*_bodies[i]->_listeners)[k]->_collisionStatus.end(); iter++)
+                unsigned int size = iter->second._listeners.size();
+                for (unsigned int i = 0; i < size; i++)
                 {
-                    if ((iter->second & PhysicsRigidBody::Listener::DIRTY) != 0)
-                    {
-                        iter->second &= ~PhysicsRigidBody::Listener::COLLISION;
-                    }
+                    iter->second._listeners[i]->collisionEvent(PhysicsRigidBody::Listener::NOT_COLLIDING, iter->first);
                 }
             }
+
+            iter->second._status &= ~COLLISION;
         }
     }
 }
-    
+
+void PhysicsController::addCollisionListener(PhysicsRigidBody::Listener* listener, PhysicsRigidBody* rbA, PhysicsRigidBody* rbB)
+{
+    // Add the listener and ensure the status includes that this collision pair is registered.
+    PhysicsRigidBody::CollisionPair pair(rbA, rbB);
+    _collisionStatus[pair]._listeners.push_back(listener);
+    if ((_collisionStatus[pair]._status & PhysicsController::REGISTERED) == 0)
+        _collisionStatus[pair]._status |= PhysicsController::REGISTERED;
+}
 
 void PhysicsController::addRigidBody(PhysicsRigidBody* body)
 {
@@ -311,8 +382,32 @@ void PhysicsController::removeRigidBody(PhysicsRigidBody* rigidBody)
             else
                 _shapes[i]->release();
 
-            return;
+            break;
+        }
+    }
+
+    // Remove the rigid body from the controller's list.
+    for (unsigned int i = 0; i < _bodies.size(); i++)
+    {
+        if (_bodies[i] == rigidBody)
+        {
+            _bodies.erase(_bodies.begin() + i);
+            break;
+        }
+    }
+
+    // Find all references to the rigid body in the collision status cache and remove them.
+    std::map<PhysicsRigidBody::CollisionPair, CollisionInfo>::iterator iter = _collisionStatus.begin();
+    for (; iter != _collisionStatus.end();)
+    {
+        if (iter->first._rbA == rigidBody || iter->first._rbB == rigidBody)
+        {
+            std::map<PhysicsRigidBody::CollisionPair, CollisionInfo>::iterator eraseIter = iter;
+            iter++;
+            _collisionStatus.erase(eraseIter);
         }
+        else
+            iter++;
     }
 }
 
@@ -407,14 +502,14 @@ btCollisionShape* PhysicsController::createSphere(float radius, const btVector3&
     return sphere;
 }
 
-btCollisionShape* PhysicsController::createMesh(PhysicsRigidBody* body)
+btCollisionShape* PhysicsController::createMesh(PhysicsRigidBody* body, const Vector3& scale)
 {
     // Retrieve the mesh rigid body data from the loaded scene.
     const SceneLoader::MeshRigidBodyData* data = SceneLoader::getMeshRigidBodyData(body->_node->getId());
 
     // Copy the scaled vertex position data to the rigid body's local buffer.
     Matrix m;
-    Matrix::createScale(body->_node->getScaleX(), body->_node->getScaleY(), body->_node->getScaleZ(), &m);
+    Matrix::createScale(scale, &m);
     unsigned int vertexCount = data->mesh->getVertexCount();
     body->_vertexData = new float[vertexCount * 3];
     Vector3 v;
@@ -467,7 +562,7 @@ btCollisionShape* PhysicsController::createMesh(PhysicsRigidBody* body)
             indexedMesh.m_numTriangles = meshPart->getIndexCount() / 3;
             indexedMesh.m_numVertices = meshPart->getIndexCount();
             indexedMesh.m_triangleIndexBase = (const unsigned char*)body->_indexData[i];
-            indexedMesh.m_triangleIndexStride = indexStride;
+            indexedMesh.m_triangleIndexStride = indexStride*3;
             indexedMesh.m_vertexBase = (const unsigned char*)body->_vertexData;
             indexedMesh.m_vertexStride = sizeof(float)*3;
             indexedMesh.m_vertexType = PHY_FLOAT;
@@ -664,4 +759,4 @@ int	PhysicsController::DebugDrawer::getDebugMode() const
     return _mode;
 }
 
-}
+}

+ 35 - 3
gameplay/src/PhysicsController.h

@@ -15,7 +15,7 @@ namespace gameplay
 /**
  * Defines a class for controlling game physics.
  */
-class PhysicsController
+class PhysicsController : public btCollisionWorld::ContactResultCallback
 {
     friend class Game;
     friend class PhysicsConstraint;
@@ -189,8 +189,36 @@ public:
      */
     void drawDebug(const Matrix& viewProjection);
 
+    /**
+     * Gets the first rigid body that the given ray intersects.
+     * 
+     * @param ray The ray to test intersection with.
+     * @return The first rigid body that the ray intersects.
+     */
+    PhysicsRigidBody* rayTest(const Ray& ray);
+
+protected:
+
+    /**
+     * Internal function used for Bullet integration (do not use or override).
+     */
+    btScalar addSingleResult(btManifoldPoint& cp, const btCollisionObject* a, int partIdA, int indexA, const btCollisionObject* b, int partIdB, int indexB);    
+
 private:
 
+    // Internal constants for the collision status cache.
+    static const int DIRTY;
+    static const int COLLISION;
+    static const int REGISTERED;
+
+    // Represents the collision listeners and status for a given collision pair (used by the collision status cache).
+    struct CollisionInfo
+    {
+        std::vector<PhysicsRigidBody::Listener*> _listeners;
+        int _status;
+    };
+
+    // Wraps Bullet collision shapes (used for implementing shape caching).
     struct PhysicsCollisionShape : public Ref
     {
         PhysicsCollisionShape(btCollisionShape* shape) : _shape(shape) {}
@@ -234,6 +262,9 @@ private:
      */
     void update(long elapsedTime);
 
+    // Adds the given collision listener for the two given rigid bodies.
+    void addCollisionListener(PhysicsRigidBody::Listener* listener, PhysicsRigidBody* rbA, PhysicsRigidBody* rbB);
+
     // Adds the given rigid body to the world.
     void addRigidBody(PhysicsRigidBody* body);
     
@@ -253,7 +284,7 @@ private:
     btCollisionShape* createSphere(float radius, const btVector3& scale);
 
     // Creates a triangle mesh collision shape to be used in the creation of a rigid body.
-    btCollisionShape* createMesh(PhysicsRigidBody* body);
+    btCollisionShape* createMesh(PhysicsRigidBody* body, const Vector3& scale);
 
     // Sets up the given constraint for the given two rigid bodies.
     void addConstraint(PhysicsRigidBody* a, PhysicsRigidBody* b, PhysicsConstraint* constraint);
@@ -308,8 +339,9 @@ private:
     std::vector<Listener*>* _listeners;
     std::vector<PhysicsRigidBody*> _bodies;
     Vector3 _gravity;
+    std::map<PhysicsRigidBody::CollisionPair, CollisionInfo> _collisionStatus;  
 };
 
 }
 
-#endif
+#endif

+ 3 - 3
gameplay/src/PhysicsGenericConstraint.cpp

@@ -45,13 +45,13 @@ PhysicsGenericConstraint::PhysicsGenericConstraint(PhysicsRigidBody* a, const Qu
         b->getNode()->getWorldMatrix().getScale(&sB);
         Vector3 tB(translationOffsetB.x * sB.x, translationOffsetB.y * sB.y, translationOffsetB.z * sB.z);
 
-        btTransform frameInA(btQuaternion(rotationOffsetA.x, rotationOffsetA.y, rotationOffsetA.z, rotationOffsetA.w), btVector3(tA.x, tA.y, tA.z));
-        btTransform frameInB(btQuaternion(rotationOffsetB.x, rotationOffsetB.y, rotationOffsetB.z, rotationOffsetB.w), btVector3(tB.x, tB.y, tB.z));
+        btTransform frameInA(rotationOffsetA, tA);
+        btTransform frameInB(rotationOffsetB, tB);
         _constraint = new btGeneric6DofConstraint(*a->_body, *b->_body, frameInA, frameInB, true);
     }
     else
     {
-        btTransform frameInA(btQuaternion(rotationOffsetA.x, rotationOffsetA.y, rotationOffsetA.z, rotationOffsetA.w), btVector3(tA.x, tA.y, tA.z));
+        btTransform frameInA(rotationOffsetA, tA);
         _constraint = new btGeneric6DofConstraint(*a->_body, frameInA, true);
     }
 }

+ 8 - 8
gameplay/src/PhysicsGenericConstraint.inl

@@ -45,42 +45,42 @@ inline const Vector3& PhysicsGenericConstraint::getTranslationOffsetB() const
 
 inline void PhysicsGenericConstraint::setAngularLowerLimit(const Vector3& limits)
 {
-    ((btGeneric6DofConstraint*)_constraint)->setAngularLowerLimit(btVector3(limits.x, limits.y, limits.z));
+    ((btGeneric6DofConstraint*)_constraint)->setAngularLowerLimit(limits);
 }
 
 inline void PhysicsGenericConstraint::setAngularUpperLimit(const Vector3& limits)
 {
-    ((btGeneric6DofConstraint*)_constraint)->setAngularUpperLimit(btVector3(limits.x, limits.y, limits.z));
+    ((btGeneric6DofConstraint*)_constraint)->setAngularUpperLimit(limits);
 }
 
 inline void PhysicsGenericConstraint::setLinearLowerLimit(const Vector3& limits)
 {
-    ((btGeneric6DofConstraint*)_constraint)->setLinearLowerLimit(btVector3(limits.x, limits.y, limits.z));
+    ((btGeneric6DofConstraint*)_constraint)->setLinearLowerLimit(limits);
 }
     
 inline void PhysicsGenericConstraint::setLinearUpperLimit(const Vector3& limits)
 {
-    ((btGeneric6DofConstraint*)_constraint)->setLinearUpperLimit(btVector3(limits.x, limits.y, limits.z));
+    ((btGeneric6DofConstraint*)_constraint)->setLinearUpperLimit(limits);
 }
 
 inline void PhysicsGenericConstraint::setRotationOffsetA(const Quaternion& rotationOffset)
 {
-    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetA().setRotation(btQuaternion(rotationOffset.x, rotationOffset.y, rotationOffset.z, rotationOffset.w));
+    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetA().setRotation(rotationOffset);
 }
 
 inline void PhysicsGenericConstraint::setRotationOffsetB(const Quaternion& rotationOffset)
 {
-    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetB().setRotation(btQuaternion(rotationOffset.x, rotationOffset.y, rotationOffset.z, rotationOffset.w));
+    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetB().setRotation(rotationOffset);
 }
 
 inline void PhysicsGenericConstraint::setTranslationOffsetA(const Vector3& translationOffset)
 {
-    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetA().setOrigin(btVector3(translationOffset.x, translationOffset.y, translationOffset.z));
+    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetA().setOrigin(translationOffset);
 }
 
 inline void PhysicsGenericConstraint::setTranslationOffsetB(const Vector3& translationOffset)
 {
-    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetB().setOrigin(btVector3(translationOffset.x, translationOffset.y, translationOffset.z));
+    static_cast<btGeneric6DofConstraint*>(_constraint)->getFrameOffsetB().setOrigin(translationOffset);
 }
 
 }

+ 3 - 3
gameplay/src/PhysicsHingeConstraint.cpp

@@ -27,13 +27,13 @@ PhysicsHingeConstraint::PhysicsHingeConstraint(PhysicsRigidBody* a, const Quater
         b->getNode()->getWorldMatrix().getScale(&sB);
         Vector3 tB(translationOffsetB.x * sB.x, translationOffsetB.y * sB.y, translationOffsetB.z * sB.z);
 
-        btTransform frameInA(btQuaternion(rotationOffsetA.x, rotationOffsetA.y, rotationOffsetA.z, rotationOffsetA.w), btVector3(tA.x, tA.y, tA.z));
-        btTransform frameInB(btQuaternion(rotationOffsetB.x, rotationOffsetB.y, rotationOffsetB.z, rotationOffsetB.w), btVector3(tB.x, tB.y, tB.z));
+        btTransform frameInA(rotationOffsetA, tA);
+        btTransform frameInB(rotationOffsetB, tB);
         _constraint = new btHingeConstraint(*a->_body, *b->_body, frameInA, frameInB);
     }
     else
     {
-        btTransform frameInA(btQuaternion(rotationOffsetA.x, rotationOffsetA.y, rotationOffsetA.z, rotationOffsetA.w), btVector3(tA.x, tA.y, tA.z));
+        btTransform frameInA(rotationOffsetA, tA);
         _constraint = new btHingeConstraint(*a->_body, frameInA);
     }
 }

+ 4 - 5
gameplay/src/PhysicsMotionState.cpp

@@ -9,7 +9,7 @@ PhysicsMotionState::PhysicsMotionState(Node* node, const Vector3* centerOfMassOf
     if (centerOfMassOffset)
     {
         // Store the center of mass offset.
-        _centerOfMassOffset.setOrigin(btVector3(centerOfMassOffset->x, centerOfMassOffset->y, centerOfMassOffset->z));
+        _centerOfMassOffset.setOrigin(*centerOfMassOffset);
     }
 
     updateTransformFromNode();
@@ -49,17 +49,16 @@ void PhysicsMotionState::updateTransformFromNode() const
     {
         // When there is a center of mass offset, we modify the initial world transformation
         // so that when physics is initially applied, the object is in the correct location.
-        btQuaternion orientation(rotation.x, rotation.y, rotation.z, rotation.w);
-        btTransform offset = btTransform(orientation, btVector3(0.0f, 0.0f, 0.0f)) * _centerOfMassOffset.inverse();
+        btTransform offset = btTransform(rotation, btVector3(0.0f, 0.0f, 0.0f)) * _centerOfMassOffset.inverse();
 
         btVector3 origin(m.m[12] + _centerOfMassOffset.getOrigin().getX() + offset.getOrigin().getX(), 
                          m.m[13] + _centerOfMassOffset.getOrigin().getY() + offset.getOrigin().getY(), 
                          m.m[14] + _centerOfMassOffset.getOrigin().getZ() + offset.getOrigin().getZ());
-        _worldTransform = btTransform(orientation, origin);
+        _worldTransform = btTransform(rotation, origin);
     }
     else
     {
-        _worldTransform = btTransform(btQuaternion(rotation.x, rotation.y, rotation.z, rotation.w), btVector3(m.m[12], m.m[13], m.m[14]));
+        _worldTransform = btTransform(rotation, btVector3(m.m[12], m.m[13], m.m[14]));
     }
 }
 

+ 26 - 52
gameplay/src/PhysicsRigidBody.cpp

@@ -10,10 +10,6 @@
 namespace gameplay
 {
 
-const int PhysicsRigidBody::Listener::DIRTY         = 0x01;
-const int PhysicsRigidBody::Listener::COLLISION     = 0x02;
-const int PhysicsRigidBody::Listener::REGISTERED    = 0x04;
-
 // Internal values used for creating mesh, heightfield, and capsule rigid bodies.
 #define SHAPE_MESH ((PhysicsRigidBody::Type)(PhysicsRigidBody::SHAPE_NONE + 1))
 #define SHAPE_HEIGHTFIELD ((PhysicsRigidBody::Type)(PhysicsRigidBody::SHAPE_NONE + 2))
@@ -28,33 +24,40 @@ PhysicsRigidBody::PhysicsRigidBody(Node* node, PhysicsRigidBody::Type type, floa
         _anisotropicFriction(NULL), _gravity(NULL), _linearVelocity(NULL), _vertexData(NULL),
         _indexData(NULL), _heightfieldData(NULL), _inverse(NULL), _inverseIsDirty(true)
 {
+    // Get the node's world scale (we need to apply this during creation since rigid bodies don't scale dynamically).
+    Vector3 scale;
+    node->getWorldMatrix().getScale(&scale);
+
     switch (type)
     {
         case SHAPE_BOX:
         {
             const BoundingBox& box = node->getModel()->getMesh()->getBoundingBox();
-            _shape = Game::getInstance()->getPhysicsController()->createBox(box.min, box.max, btVector3(node->getScaleX(), node->getScaleY(), node->getScaleZ()));
+            _shape = Game::getInstance()->getPhysicsController()->createBox(box.min, box.max, scale);
             break;
         }
         case SHAPE_SPHERE:
         {
             const BoundingSphere& sphere = node->getModel()->getMesh()->getBoundingSphere();
-            _shape = Game::getInstance()->getPhysicsController()->createSphere(sphere.radius, btVector3(node->getScaleX(), node->getScaleY(), node->getScaleZ()));
+            _shape = Game::getInstance()->getPhysicsController()->createSphere(sphere.radius, scale);
             break;
         }
         case SHAPE_MESH:
         {
-            _shape = Game::getInstance()->getPhysicsController()->createMesh(this);
+            _shape = Game::getInstance()->getPhysicsController()->createMesh(this, scale);
             break;
         }
     }
 
     // Use the center of the bounding sphere as the center of mass offset.
     Vector3 c(node->getModel()->getMesh()->getBoundingSphere().center);
+    c.x *= scale.x;
+    c.y *= scale.y;
+    c.z *= scale.z;
     c.negate();
 
-    // Create the Bullet rigid body.
-    if (c.lengthSquared() > MATH_EPSILON)
+    // Create the Bullet rigid body (we don't apply center of mass offsets on mesh rigid bodies).
+    if (c.lengthSquared() > MATH_EPSILON && type != SHAPE_MESH)
         _body = createRigidBodyInternal(_shape, mass, node, friction, restitution, linearDamping, angularDamping, &c);
     else
         _body = createRigidBodyInternal(_shape, mass, node, friction, restitution, linearDamping, angularDamping);
@@ -151,11 +154,18 @@ PhysicsRigidBody::PhysicsRigidBody(Node* node, float radius, float height, float
         _anisotropicFriction(NULL), _gravity(NULL), _linearVelocity(NULL), _vertexData(NULL),
         _indexData(NULL), _heightfieldData(NULL), _inverse(NULL), _inverseIsDirty(true)
 {
+    // Get the node's world scale (we need to apply this during creation since rigid bodies don't scale dynamically).
+    Vector3 scale;
+    node->getWorldMatrix().getScale(&scale);
+
     // Create the capsule collision shape.
     _shape = Game::getInstance()->getPhysicsController()->createCapsule(radius, height);
 
     // Use the center of the bounding sphere as the center of mass offset.
     Vector3 c(node->getModel()->getMesh()->getBoundingSphere().center);
+    c.x *= scale.x;
+    c.y *= scale.y;
+    c.z *= scale.z;
     c.negate();
 
     // Create the Bullet rigid body.
@@ -205,13 +215,7 @@ PhysicsRigidBody::~PhysicsRigidBody()
 
 void PhysicsRigidBody::addCollisionListener(Listener* listener, PhysicsRigidBody* body)
 {
-    if (!_listeners)
-        _listeners = new std::vector<Listener*>();
-
-    CollisionPair pair(this, body);
-    listener->_collisionStatus[pair] = PhysicsRigidBody::Listener::REGISTERED;
-
-    _listeners->push_back(listener);
+    Game::getInstance()->getPhysicsController()->addCollisionListener(listener, this, body);
 }
 
 void PhysicsRigidBody::applyForce(const Vector3& force, const Vector3* relativePosition)
@@ -222,9 +226,9 @@ void PhysicsRigidBody::applyForce(const Vector3& force, const Vector3* relativeP
     {
         _body->activate();
         if (relativePosition)
-            _body->applyForce(btVector3(force.x, force.y, force.z), btVector3(relativePosition->x, relativePosition->y, relativePosition->z));
+            _body->applyForce(force, *relativePosition);
         else
-            _body->applyCentralForce(btVector3(force.x, force.y, force.z));
+            _body->applyCentralForce(force);
     }
 }
 
@@ -238,10 +242,10 @@ void PhysicsRigidBody::applyImpulse(const Vector3& impulse, const Vector3* relat
 
         if (relativePosition)
         {
-            _body->applyImpulse(btVector3(impulse.x, impulse.y, impulse.z), btVector3(relativePosition->x, relativePosition->y, relativePosition->z));
+            _body->applyImpulse(impulse, *relativePosition);
         }
         else
-            _body->applyCentralImpulse(btVector3(impulse.x, impulse.y, impulse.z));
+            _body->applyCentralImpulse(impulse);
     }
 }
 
@@ -252,7 +256,7 @@ void PhysicsRigidBody::applyTorque(const Vector3& torque)
     if (torque.lengthSquared() > MATH_EPSILON)
     {
         _body->activate();
-        _body->applyTorque(btVector3(torque.x, torque.y, torque.z));
+        _body->applyTorque(torque);
     }
 }
 
@@ -263,7 +267,7 @@ void PhysicsRigidBody::applyTorqueImpulse(const Vector3& torque)
     if (torque.lengthSquared() > MATH_EPSILON)
     {
         _body->activate();
-        _body->applyTorqueImpulse(btVector3(torque.x, torque.y, torque.z));
+        _body->applyTorqueImpulse(torque);
     }
 }
 
@@ -568,36 +572,6 @@ PhysicsRigidBody::Listener::~Listener()
     // Unused
 }
 
-btScalar PhysicsRigidBody::Listener::addSingleResult(btManifoldPoint& cp, 
-                                                     const btCollisionObject* a, int partIdA, int indexA, 
-                                                     const btCollisionObject* b, int partIdB, int indexB)
-{
-    // Get pointers to the PhysicsRigidBody objects.
-    PhysicsRigidBody* rbA = Game::getInstance()->getPhysicsController()->getRigidBody(a);
-    PhysicsRigidBody* rbB = Game::getInstance()->getPhysicsController()->getRigidBody(b);
-    
-    // If the given rigid body pair has collided in the past, then
-    // we notify the listener only if the pair was not colliding
-    // during the previous frame. Otherwise, it's a new pair, so notify the listener.
-    CollisionPair pair(rbA, rbB);
-    if (_collisionStatus.count(pair) > 0)
-    {
-        if ((_collisionStatus[pair] & COLLISION) == 0)
-            collisionEvent(pair, Vector3(cp.getPositionWorldOnA().x(), cp.getPositionWorldOnA().y(), cp.getPositionWorldOnA().z()));
-    }
-    else
-    {
-        collisionEvent(pair, Vector3(cp.getPositionWorldOnA().x(), cp.getPositionWorldOnA().y(), cp.getPositionWorldOnA().z()));
-    }
-
-    // Update the collision status cache (we remove the dirty bit
-    // set in the controller's update so that this particular collision pair's
-    // status is not reset to 'no collision' when the controller's update completes).
-    _collisionStatus[pair] &= ~DIRTY;
-    _collisionStatus[pair] |= COLLISION;
-    return 0.0f;
-}
-
 btScalar PhysicsRigidBody::CollidesWithCallback::addSingleResult(btManifoldPoint& cp, 
                                                                  const btCollisionObject* a, int partIdA, int indexA, 
                                                                  const btCollisionObject* b, int partIdB, int indexB)

+ 22 - 24
gameplay/src/PhysicsRigidBody.h

@@ -69,44 +69,42 @@ public:
     /**
      * Collision listener interface.
      */
-    class Listener : public btCollisionWorld::ContactResultCallback
+    class Listener
     {
         friend class PhysicsRigidBody;
         friend class PhysicsController;
 
     public:
+        /**
+         * The type of collision event.
+         */
+        enum EventType
+        {
+            /**
+             * Event fired when the two rigid bodies start colliding.
+             */
+            COLLIDING,
+
+            /**
+             * Event fired when the two rigid bodies no longer collide.
+             */
+            NOT_COLLIDING
+        };
+
         /**
          * Destructor.
          */
         virtual ~Listener();
 
         /**
-         * Handles when a collision occurs for the rigid body where this listener is registered.
+         * Handles when a collision starts or stops occurring for the rigid body where this listener is registered.
          * 
+         * @param type The type of collision event.
          * @param collisionPair The two rigid bodies involved in the collision.
-         * @param contactPoint The point (in world space) where the collision occurred.
-         */
-        virtual void collisionEvent(const CollisionPair& collisionPair, const Vector3& contactPoint) = 0;
-        
-    protected:
-        
-        /**
-         * Internal function used for Bullet integration (do not use or override).
+         * @param contactPointA The contact point with the first rigid body (in world space).
+         * @param contactPointB The contact point with the second rigid body (in world space).
          */
-        btScalar addSingleResult(btManifoldPoint& cp, 
-                                 const btCollisionObject* a, int partIdA, int indexA, 
-                                 const btCollisionObject* b, int partIdB, int indexB);
-
-        std::map<CollisionPair, int> _collisionStatus;  // Holds the collision status for each pair of rigid bodies. 
-        
-    private:
-
-        // Internal constant.
-        static const int DIRTY;
-        // Internal constant.
-        static const int COLLISION;
-        // Internal constant.
-        static const int REGISTERED;
+        virtual void collisionEvent(EventType type, const CollisionPair& collisionPair, const Vector3& contactPointA = Vector3(), const Vector3& contactPointB = Vector3()) = 0;
     };
 
     /**

+ 4 - 4
gameplay/src/PhysicsRigidBody.inl

@@ -75,12 +75,12 @@ inline bool PhysicsRigidBody::isKinematic() const
 
 inline void PhysicsRigidBody::setAngularVelocity(const Vector3& velocity)
 {
-    _body->setAngularVelocity(btVector3(velocity.x, velocity.y, velocity.z));
+    _body->setAngularVelocity(velocity);
 }
 
 inline void PhysicsRigidBody::setAnisotropicFriction(const Vector3& friction)
 {
-    _body->setAnisotropicFriction(btVector3(friction.x, friction.y, friction.z));
+    _body->setAnisotropicFriction(friction);
 }
 
 inline void PhysicsRigidBody::setDamping(float linearDamping, float angularDamping)
@@ -95,7 +95,7 @@ inline void PhysicsRigidBody::setFriction(float friction)
 
 inline void PhysicsRigidBody::setGravity(const Vector3& gravity)
 {
-    _body->setGravity(btVector3(gravity.x, gravity.y, gravity.z));
+    _body->setGravity(gravity);
 }
 
 inline void PhysicsRigidBody::setKinematic(bool kinematic)
@@ -114,7 +114,7 @@ inline void PhysicsRigidBody::setKinematic(bool kinematic)
 
 inline void PhysicsRigidBody::setLinearVelocity(const Vector3& velocity)
 {
-    _body->setLinearVelocity(btVector3(velocity.x, velocity.y, velocity.z));
+    _body->setLinearVelocity(velocity);
 }
 
 inline void PhysicsRigidBody::setRestitution(float restitution)

+ 2 - 2
gameplay/src/PhysicsSocketConstraint.cpp

@@ -38,11 +38,11 @@ PhysicsSocketConstraint::PhysicsSocketConstraint(PhysicsRigidBody* a, const Vect
         b->getNode()->getWorldMatrix().getScale(&sB);
         Vector3 tB(translationOffsetB.x * sB.x, translationOffsetB.y * sB.y, translationOffsetB.z * sB.z);
 
-        _constraint = new btPoint2PointConstraint(*a->_body, *b->_body, btVector3(tA.x, tA.y, tA.z), btVector3(tB.x, tB.y, tB.z));
+        _constraint = new btPoint2PointConstraint(*a->_body, *b->_body, tA, tB);
     }
     else
     {
-        _constraint = new btPoint2PointConstraint(*a->_body, btVector3(tA.x, tA.y, tA.z));
+        _constraint = new btPoint2PointConstraint(*a->_body, tA);
     }
 }
 

+ 2 - 2
gameplay/src/PhysicsSpringConstraint.cpp

@@ -32,8 +32,8 @@ PhysicsSpringConstraint::PhysicsSpringConstraint(PhysicsRigidBody* a, const Quat
     b->getNode()->getWorldMatrix().getScale(&sB);
     Vector3 tB(translationOffsetB.x * sB.x, translationOffsetB.y * sB.y, translationOffsetB.z * sB.z);
 
-    btTransform frameInA(btQuaternion(rotationOffsetA.x, rotationOffsetA.y, rotationOffsetA.z, rotationOffsetA.w), btVector3(tA.x, tA.y, tA.z));
-    btTransform frameInB(btQuaternion(rotationOffsetB.x, rotationOffsetB.y, rotationOffsetB.z, rotationOffsetB.w), btVector3(tB.x, tB.y, tB.z));
+    btTransform frameInA(rotationOffsetA, tA);
+    btTransform frameInB(rotationOffsetB, tB);
     _constraint = new btGeneric6DofSpringConstraint(*a->_body, *b->_body, frameInA, frameInB, true);
 }
 

+ 5 - 0
gameplay/src/Quaternion.h

@@ -350,6 +350,11 @@ public:
      */
     inline Quaternion& operator*=(const Quaternion& q);
 
+    /**
+     * Defines implicit conversion operator to the Bullet btQuaternion type.
+     */
+    inline operator btQuaternion() const;
+
 private:
 
     /**

+ 6 - 0
gameplay/src/Quaternion.inl

@@ -1,4 +1,5 @@
 #include "Quaternion.h"
+#include "Base.h"
 
 namespace gameplay
 {
@@ -16,4 +17,9 @@ inline Quaternion& Quaternion::operator*=(const Quaternion& q)
     return *this;
 }
 
+inline Quaternion::operator btQuaternion() const
+{
+    return btQuaternion(x, y, z, w);
+}
+
 }

+ 52 - 8
gameplay/src/SceneLoader.cpp

@@ -12,6 +12,7 @@ std::vector<SceneLoader::SceneAnimation> SceneLoader::_animations;
 std::vector<SceneLoader::SceneNodeProperty> SceneLoader::_nodeProperties;
 std::vector<std::string> SceneLoader::_nodesWithMeshRB;
 std::map<std::string, SceneLoader::MeshRigidBodyData>* SceneLoader::_meshRigidBodyData = NULL;
+std::string SceneLoader::_path;
 
 Scene* SceneLoader::load(const char* filePath)
 {
@@ -35,8 +36,10 @@ Scene* SceneLoader::load(const char* filePath)
         SAFE_DELETE(properties);
         return NULL;
     }
-    
 
+    // Get the path to the main GPB.
+    _path = sceneProperties->getString("path");
+    
     // Build the node URL/property and animation reference tables and load the referenced files.
     buildReferenceTables(sceneProperties);
     loadReferencedFiles();
@@ -124,7 +127,7 @@ Scene* SceneLoader::load(const char* filePath)
     return scene;
 }
 
-void SceneLoader::addMeshRigidBodyData(std::string id, Mesh* mesh, unsigned char* vertexData, unsigned int vertexByteCount)
+void SceneLoader::addMeshRigidBodyData(std::string package, std::string id, Mesh* mesh, unsigned char* vertexData, unsigned int vertexByteCount)
 {
     if (!_meshRigidBodyData)
     {
@@ -132,12 +135,27 @@ void SceneLoader::addMeshRigidBodyData(std::string id, Mesh* mesh, unsigned char
         return;
     }
 
+    // If the node with the mesh rigid body is renamed, we need to find the new id.
+    for (unsigned int i = 0; i < _nodeProperties.size(); i++)
+    {
+        if (_nodeProperties[i]._type == SceneNodeProperty::URL &&
+            _nodeProperties[i]._id == id)
+        {
+            if ((package == _path && _nodeProperties[i]._file.size() == 0) ||
+                (package == _nodeProperties[i]._file))
+            {
+                id = _nodeProperties[i]._nodeID;
+                break;
+            }
+        }
+    }
+
     (*_meshRigidBodyData)[id].mesh = mesh;
     (*_meshRigidBodyData)[id].vertexData = new unsigned char[vertexByteCount];
     memcpy((*_meshRigidBodyData)[id].vertexData, vertexData, vertexByteCount);
 }
 
-void SceneLoader::addMeshRigidBodyData(std::string id, unsigned char* indexData, unsigned int indexByteCount)
+void SceneLoader::addMeshRigidBodyData(std::string package, std::string id, unsigned char* indexData, unsigned int indexByteCount)
 {
     if (!_meshRigidBodyData)
     {
@@ -145,6 +163,21 @@ void SceneLoader::addMeshRigidBodyData(std::string id, unsigned char* indexData,
         return;
     }
 
+    // If the node with the mesh rigid body is renamed, we need to find the new id.
+    for (unsigned int i = 0; i < _nodeProperties.size(); i++)
+    {
+        if (_nodeProperties[i]._type == SceneNodeProperty::URL &&
+            _nodeProperties[i]._id == id)
+        {
+            if ((package == _path && _nodeProperties[i]._file.size() == 0) ||
+                (package == _nodeProperties[i]._file))
+            {
+                id = _nodeProperties[i]._nodeID;
+                break;
+            }
+        }
+    }
+
     unsigned char* indexDataCopy = new unsigned char[indexByteCount];
     memcpy(indexDataCopy, indexData, indexByteCount);
     (*_meshRigidBodyData)[id].indexData.push_back(indexDataCopy);
@@ -568,7 +601,19 @@ void SceneLoader::calculateNodesWithMeshRigidBodies(const Properties* scenePrope
                     if (p && (name = p->getString("rigidbodymodel")))
                         _nodesWithMeshRB.push_back(name);
                     else
-                        _nodesWithMeshRB.push_back(_nodeProperties[i]._nodeID);
+                    {
+                        const char* id = _nodeProperties[i]._nodeID;
+                        for (unsigned int j = 0; j < _nodeProperties.size(); j++)
+                        {
+                            if (_nodeProperties[j]._type == SceneNodeProperty::URL &&
+                                _nodeProperties[j]._nodeID == _nodeProperties[i]._nodeID)
+                            {
+                                id = _nodeProperties[j]._id.c_str();
+                                break;
+                            }
+                        }
+                        _nodesWithMeshRB.push_back(id);
+                    }
                 }
             }
         }
@@ -704,18 +749,17 @@ PhysicsConstraint* SceneLoader::loadHingeConstraint(const Properties* constraint
 Scene* SceneLoader::loadMainSceneData(const Properties* sceneProperties)
 {
     // Load the main scene from the specified path.
-    const char* path = sceneProperties->getString("path");
-    Package* package = Package::create(path);
+    Package* package = Package::create(_path.c_str());
     if (!package)
     {
-        WARN_VARG("Failed to load scene GPB file '%s'.", path);
+        WARN_VARG("Failed to load scene GPB file '%s'.", _path.c_str());
         return NULL;
     }
     
     Scene* scene = package->loadScene(NULL, &_nodesWithMeshRB);
     if (!scene)
     {
-        WARN_VARG("Failed to load scene from '%s'.", path);
+        WARN_VARG("Failed to load scene from '%s'.", _path.c_str());
         SAFE_RELEASE(package);
         return NULL;
     }

+ 5 - 2
gameplay/src/SceneLoader.h

@@ -58,8 +58,8 @@ private:
         std::string _id;
     };
 
-    static void addMeshRigidBodyData(std::string id, Mesh* mesh, unsigned char* vertexData, unsigned int vertexByteCount);
-    static void addMeshRigidBodyData(std::string id, unsigned char* indexData, unsigned int indexByteCount);
+    static void addMeshRigidBodyData(std::string package, std::string id, Mesh* mesh, unsigned char* vertexData, unsigned int vertexByteCount);
+    static void addMeshRigidBodyData(std::string package, std::string id, unsigned char* indexData, unsigned int indexByteCount);
     static void addSceneAnimation(const char* animationID, const char* targetID, const char* url);
     static void addSceneNodeProperty(SceneNodeProperty::Type type, const char* nodeID, const char* url = NULL);
     static void applyNodeProperties(const Scene* scene, const Properties* sceneProperties);
@@ -93,6 +93,9 @@ private:
 
     // Stores the mesh data needed for triangle mesh rigid body support.
     static std::map<std::string, MeshRigidBodyData>* _meshRigidBodyData;
+
+    // The path of the main GPB for the scene being loaded.
+    static std::string _path;
 };
 
 }

+ 2 - 1
gameplay/src/Texture.cpp

@@ -68,7 +68,8 @@ Texture* Texture::create(const char* path, bool generateMipmaps)
             if (tolower(ext[1]) == 'p' && tolower(ext[2]) == 'n' && tolower(ext[3]) == 'g')
             {
                 Image* image = Image::create(path);
-                texture = create(image, generateMipmaps);
+                if (image)
+                    texture = create(image, generateMipmaps);
                 SAFE_RELEASE(image);
             }
             break;

+ 9 - 0
gameplay/src/Vector2.h

@@ -395,6 +395,15 @@ public:
      * @return True if this vector is equal to the given vector, false otherwise.
      */
     inline bool operator==(const Vector2& v) const;
+
+    /**
+     * Determines if this vector is not equal to the given vector.
+     * 
+     * @param v The vector to compare against.
+     * 
+     * @return True if this vector is not equal to the given vector, false otherwise.
+     */
+    inline bool operator!=(const Vector2& v) const;
 };
 
 /**

+ 5 - 0
gameplay/src/Vector2.inl

@@ -63,6 +63,11 @@ inline bool Vector2::operator==(const Vector2& v) const
     return x==v.x && y==v.y;
 }
 
+inline bool Vector2::operator!=(const Vector2& v) const
+{
+    return x!=v.x || y!=v.y;
+}
+
 inline Vector2 operator*(float x, const Vector2& v)
 {
     Vector2 result(v);

+ 7 - 0
gameplay/src/Vector3.h

@@ -1,6 +1,8 @@
 #ifndef VECTOR3_H_
 #define VECTOR3_H_
 
+class btVector3;
+
 namespace gameplay
 {
 
@@ -425,6 +427,11 @@ public:
      * @return True if this vector is equal to the given vector, false otherwise.
      */
     inline bool operator==(const Vector3& v) const;
+
+    /**
+     * Defines implicit conversion operator to the Bullet btVector3 type.
+     */
+    inline operator btVector3() const;
 };
 
 /**

+ 6 - 0
gameplay/src/Vector3.inl

@@ -1,5 +1,6 @@
 #include "Vector3.h"
 #include "Matrix.h"
+#include "Base.h"
 
 namespace gameplay
 {
@@ -68,6 +69,11 @@ inline bool Vector3::operator==(const Vector3& v) const
     return x==v.x && y==v.y && z==v.z;
 }
 
+inline Vector3::operator btVector3() const
+{
+    return btVector3(x, y, z);
+}
+
 inline Vector3 operator*(float x, const Vector3& v)
 {
     Vector3 result(v);

+ 9 - 0
gameplay/src/Vector4.h

@@ -420,6 +420,15 @@ public:
      * @return True if this vector is equal to the given vector, false otherwise.
      */
     inline bool operator==(const Vector4& v) const;
+
+    /**
+     * Determines if this vector is not equal to the given vector.
+     * 
+     * @param v The vector to compare against.
+     * 
+     * @return True if this vector is not equal to the given vector, false otherwise.
+     */
+    inline bool operator!=(const Vector4& v) const;
 };
 
 /**

+ 5 - 0
gameplay/src/Vector4.inl

@@ -75,6 +75,11 @@ inline bool Vector4::operator==(const Vector4& v) const
     return x==v.x && y==v.y && z==v.z && w==v.w;
 }
 
+inline bool Vector4::operator!=(const Vector4& v) const
+{
+    return x!=v.x || y!=v.y || z!=v.z || w!=v.w;
+}
+
 inline Vector4 operator*(float x, const Vector4& v)
 {
     Vector4 result(v);