Remove the PhysicsEngine and PhysicsWorld classes and add the CollisionWorld and DynamicsWorld classes

This commit is contained in:
Daniel Chappuis 2012-10-03 21:00:17 +02:00
parent 4c0c285174
commit fc37d40bbb
12 changed files with 478 additions and 397 deletions

View File

@ -25,7 +25,7 @@
// Libraries
#include "CollisionDetection.h"
#include "../engine/PhysicsWorld.h"
#include "../engine/CollisionWorld.h"
#include "broadphase/SweepAndPruneAlgorithm.h"
#include "broadphase/NoBroadPhaseAlgorithm.h"
#include "../body/Body.h"
@ -45,7 +45,7 @@ using namespace reactphysics3d;
using namespace std;
// Constructor
CollisionDetection::CollisionDetection(PhysicsWorld* world)
CollisionDetection::CollisionDetection(CollisionWorld* world)
: world(world), narrowPhaseGJKAlgorithm(memoryPoolContactInfos),
narrowPhaseSphereVsSphereAlgorithm(memoryPoolContactInfos) {
@ -63,9 +63,7 @@ CollisionDetection::~CollisionDetection() {
// Compute the collision detection
bool CollisionDetection::computeCollisionDetection() {
world->removeAllContactConstraints();
// TODO : Remove this code
timeval timeValueStart;
timeval timeValueStop;

View File

@ -46,7 +46,7 @@ namespace reactphysics3d {
// Declarations
class BroadPhaseAlgorithm;
class PhysicsWorld;
class CollisionWorld;
/* -------------------------------------------------------------------
Class CollisionDetection :
@ -59,7 +59,7 @@ class PhysicsWorld;
class CollisionDetection {
private :
PhysicsWorld* world; // Pointer to the physics world
CollisionWorld* world; // Pointer to the physics world
std::map<bodyindexpair, BroadPhasePair*> overlappingPairs; // Broad-phase overlapping pairs of bodies
BroadPhaseAlgorithm* broadPhaseAlgorithm; // Broad-phase algorithm
GJKAlgorithm narrowPhaseGJKAlgorithm; // Narrow-phase GJK algorithm
@ -73,7 +73,7 @@ class CollisionDetection {
CollisionShape* collisionShape2); // Select the narrow phase algorithm to use given two collision shapes
public :
CollisionDetection(PhysicsWorld* physicsWorld); // Constructor
CollisionDetection(CollisionWorld* world); // Constructor
~CollisionDetection(); // Destructor
void addBody(CollisionBody* body); // Add a body to the collision detection

View File

@ -0,0 +1,124 @@
/********************************************************************************
* ReactPhysics3D physics library, http://code.google.com/p/reactphysics3d/ *
* Copyright (c) 2010-2012 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "CollisionWorld.h"
#include <algorithm>
// Namespaces
using namespace reactphysics3d;
using namespace std;
// Constructor
CollisionWorld::CollisionWorld() : collisionDetection(this), currentBodyID(0) {
}
// Destructor
CollisionWorld::~CollisionWorld() {
}
// Notify the world about a new broad-phase overlapping pair
void CollisionWorld::notifyAddedOverlappingPair(const BroadPhasePair* addedPair) {
// TODO : Implement this method
}
// Notify the world about a removed broad-phase overlapping pair
void CollisionWorld::notifyRemovedOverlappingPair(const BroadPhasePair* removedPair) {
// TODO : Implement this method
}
// Notify the world about a new narrow-phase contact
void CollisionWorld::notifyNewContact(const BroadPhasePair* broadPhasePair, const ContactInfo* contactInfo) {
// TODO : Implement this method
}
// Update the overlapping pair
inline void CollisionWorld::updateOverlappingPair(const BroadPhasePair* pair) {
}
// Create a collision body and add it to the world
CollisionBody* CollisionWorld::createCollisionBody(const Transform& transform, CollisionShape* collisionShape) {
// Get the next available body ID
bodyindex bodyID = computeNextAvailableBodyID();
// Largest index cannot be used (it is used for invalid index)
assert(bodyID < std::numeric_limits<reactphysics3d::bodyindex>::max());
// Create the collision body
CollisionBody* collisionBody = new (memoryPoolCollisionBodies.allocateObject()) CollisionBody(transform, collisionShape, bodyID);
// Add the collision body to the world
bodies.insert(collisionBody);
// Add the collision body to the collision detection
collisionDetection.addBody(collisionBody);
// Return the pointer to the rigid body
return collisionBody;
}
// Destroy a collision body
void CollisionWorld::destroyCollisionBody(CollisionBody* collisionBody) {
// Remove the body from the collision detection
collisionDetection.removeBody(collisionBody);
// Add the body ID to the list of free IDs
freeBodiesIDs.push_back(collisionBody->getID());
// Call the constructor of the collision body
collisionBody->CollisionBody::~CollisionBody();
// Remove the collision body from the list of bodies
bodies.erase(collisionBody); // TOOD : Maybe use a set to make this faster
// Free the object from the memory pool
memoryPoolCollisionBodies.freeObject(collisionBody);
}
// Return the next available body ID
bodyindex CollisionWorld::computeNextAvailableBodyID() {
// Compute the body ID
bodyindex bodyID;
if (!freeBodiesIDs.empty()) {
bodyID = freeBodiesIDs.back();
freeBodiesIDs.pop_back();
}
else {
bodyID = currentBodyID;
currentBodyID++;
}
return bodyID;
}

View File

@ -0,0 +1,93 @@
/********************************************************************************
* ReactPhysics3D physics library, http://code.google.com/p/reactphysics3d/ *
* Copyright (c) 2010-2012 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef COLLISION_WORLD_H
#define COLLISION_WORLD_H
// Libraries
#include <vector>
#include <set>
#include <algorithm>
#include "../mathematics/mathematics.h"
#include "../body/CollisionBody.h"
#include "OverlappingPair.h"
#include "../collision/CollisionDetection.h"
#include "../constraint/Constraint.h"
#include "../constraint/Contact.h"
#include "../memory/MemoryPool.h"
// Namespace reactphysics3d
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class CollisionWorld :
This class represent a world where it is possible to move bodies
by hand and to test collision between each other. In this kind of
world, the bodies movement is not computed using the laws of physics.
-------------------------------------------------------------------
*/
class CollisionWorld {
protected :
CollisionDetection collisionDetection; // Reference to the collision detection
std::set<CollisionBody*> bodies; // All the bodies (rigid and soft) of the physics world
std::map<std::pair<bodyindex, bodyindex>, OverlappingPair*> overlappingPairs; // Broad-phase overlapping pairs of bodies
bodyindex currentBodyID; // Current body ID
MemoryPool<CollisionBody> memoryPoolCollisionBodies; // Memory pool for rigid bodies memory allocation
std::vector<luint> freeBodiesIDs; // List of free ID for rigid bodies
virtual void notifyAddedOverlappingPair(const BroadPhasePair* addedPair); // Notify the world about a new broad-phase overlapping pair
virtual void notifyRemovedOverlappingPair(const BroadPhasePair* removedPair); // Notify the world about a removed broad-phase overlapping pair
virtual void notifyNewContact(const BroadPhasePair* pair, const ContactInfo* contactInfo); // Notify the world about a new narrow-phase contact
virtual void updateOverlappingPair(const BroadPhasePair* pair); // Update the overlapping pair
bodyindex computeNextAvailableBodyID(); // Return the next available body ID
public :
CollisionWorld(); // Constructor
virtual ~CollisionWorld(); // Destructor
std::set<CollisionBody*>::iterator getBodiesBeginIterator(); // Return an iterator to the beginning of the bodies of the physics world
std::set<CollisionBody*>::iterator getBodiesEndIterator(); // Return an iterator to the end of the bodies of the physics world
CollisionBody* createCollisionBody(const Transform& transform,
CollisionShape* collisionShape); // Create a collision body
void destroyCollisionBody(CollisionBody* collisionBody); // Destroy a collision body
// Friends
friend class CollisionDetection;
};
// Return an iterator to the beginning of the bodies of the physics world
inline std::set<CollisionBody*>::iterator CollisionWorld::getBodiesBeginIterator() {
return bodies.begin();
}
// Return an iterator to the end of the bodies of the physics world
inline std::set<CollisionBody*>::iterator CollisionWorld::getBodiesEndIterator() {
return bodies.end();
}
} // End of the ReactPhysics3D namespace
#endif

View File

@ -25,6 +25,7 @@
// Libraries
#include "ConstraintSolver.h"
#include "DynamicsWorld.h"
#include "../body/RigidBody.h"
using namespace reactphysics3d;
@ -32,8 +33,8 @@ using namespace std;
// Constructor
ConstraintSolver::ConstraintSolver(PhysicsWorld* world)
:physicsWorld(world), nbConstraints(0), nbIterationsLCP(DEFAULT_LCP_ITERATIONS),
ConstraintSolver::ConstraintSolver(DynamicsWorld* world)
:world(world), nbConstraints(0), nbIterationsLCP(DEFAULT_LCP_ITERATIONS),
nbIterationsLCPErrorCorrection(DEFAULT_LCP_ITERATIONS_ERROR_CORRECTION),
isErrorCorrectionActive(false) {
@ -53,7 +54,7 @@ void ConstraintSolver::initialize() {
// For each constraint
vector<Constraint*>::iterator it;
for (it = physicsWorld->getConstraintsBeginIterator(); it != physicsWorld->getConstraintsEndIterator(); ++it) {
for (it = world->getConstraintsBeginIterator(); it != world->getConstraintsEndIterator(); ++it) {
constraint = *it;
// If the constraint is active

View File

@ -29,12 +29,14 @@
// Libraries
#include "../configuration.h"
#include "../constraint/Constraint.h"
#include "PhysicsWorld.h"
#include <map>
#include <set>
// ReactPhysics3D namespace
namespace reactphysics3d {
// Declarations
class DynamicsWorld;
/* -------------------------------------------------------------------
@ -64,7 +66,7 @@ namespace reactphysics3d {
*/
class ConstraintSolver {
private:
PhysicsWorld* physicsWorld; // Reference to the physics world
DynamicsWorld* world; // Reference to the world
std::vector<Constraint*> activeConstraints; // Current active constraints in the physics world
bool isErrorCorrectionActive; // True if error correction (with world order) is active
uint nbIterationsLCP; // Number of iterations of the LCP solver
@ -125,7 +127,7 @@ class ConstraintSolver {
void solveLCPErrorCorrection(); // Solve the LCP problem for error correction projection
public:
ConstraintSolver(PhysicsWorld* world); // Constructor
ConstraintSolver(DynamicsWorld* world); // Constructor
virtual ~ConstraintSolver(); // Destructor
void solve(decimal dt); // Solve the current LCP problem
bool isConstrainedBody(Body* body) const; // Return true if the body is in at least one constraint
@ -232,4 +234,4 @@ inline void ConstraintSolver::solve(decimal dt) {
} // End of ReactPhysics3D namespace
#endif
#endif

View File

@ -24,28 +24,32 @@
********************************************************************************/
// Libraries
#include "PhysicsEngine.h"
#include "DynamicsWorld.h"
// We want to use the ReactPhysics3D namespace
using namespace reactphysics3d;
using namespace std;
// Constructor
PhysicsEngine::PhysicsEngine(PhysicsWorld* world, decimal timeStep = DEFAULT_TIMESTEP)
: world(world), collisionDetection(world), timer(timeStep), constraintSolver(world),
DynamicsWorld::DynamicsWorld(const Vector3 &gravity, decimal timeStep = DEFAULT_TIMESTEP)
: CollisionWorld(), timer(timeStep), gravity(gravity), isGravityOn(true), constraintSolver(this),
isDeactivationActive(DEACTIVATION_ENABLED) {
assert(world);
assert(timeStep > 0.0);
world->setCollisionDetection(&collisionDetection);
}
// Destructor
PhysicsEngine::~PhysicsEngine() {
DynamicsWorld::~DynamicsWorld() {
// Delete the remaining overlapping pairs
for (map<std::pair<bodyindex, bodyindex>, OverlappingPair*>::iterator it=overlappingPairs.begin(); it != overlappingPairs.end(); it++) {
// Delete the overlapping pair
(*it).second->OverlappingPair::~OverlappingPair();
memoryPoolOverlappingPairs.freeObject((*it).second);
}
}
// Update the physics simulation
void PhysicsEngine::update() {
void DynamicsWorld::update() {
bool existCollision = false;
assert(timer.getIsRunning());
@ -59,8 +63,9 @@ void PhysicsEngine::update() {
// While the time accumulator is not empty
while(timer.isPossibleToTakeStep()) {
std::cout << "Update ..." << std::endl;
existCollision = false;
removeAllContactConstraints();
// Compute the collision detection
if (collisionDetection.computeCollisionDetection()) {
@ -98,7 +103,7 @@ void PhysicsEngine::update() {
// and orientation of each body.
// This method uses the semi-implicit Euler method to update the position and
// orientation of the body
void PhysicsEngine::updateAllBodiesMotion() {
void DynamicsWorld::updateAllBodiesMotion() {
decimal dt = timer.getTimeStep();
Vector3 newLinearVelocity;
Vector3 newAngularVelocity;
@ -106,7 +111,7 @@ void PhysicsEngine::updateAllBodiesMotion() {
Vector3 angularVelocityErrorCorrection;
// For each body of thephysics world
for (set<RigidBody*>::iterator it=world->getRigidBodiesBeginIterator(); it != world->getRigidBodiesEndIterator(); ++it) {
for (set<RigidBody*>::iterator it=getRigidBodiesBeginIterator(); it != getRigidBodiesEndIterator(); ++it) {
RigidBody* rigidBody = *it;
assert(rigidBody);
@ -150,7 +155,7 @@ void PhysicsEngine::updateAllBodiesMotion() {
// Update the position and orientation of a body
// Use the Semi-Implicit Euler (Sympletic Euler) method to compute the new position and the new
// orientation of the body
void PhysicsEngine::updatePositionAndOrientationOfBody(RigidBody* rigidBody, const Vector3& newLinVelocity, const Vector3& newAngVelocity,
void DynamicsWorld::updatePositionAndOrientationOfBody(RigidBody* rigidBody, const Vector3& newLinVelocity, const Vector3& newAngVelocity,
const Vector3& linearVelocityErrorCorrection, const Vector3& angularVelocityErrorCorrection) {
decimal dt = timer.getTimeStep();
@ -179,14 +184,14 @@ void PhysicsEngine::updatePositionAndOrientationOfBody(RigidBody* rigidBody, con
}
// Compute and set the interpolation factor to all bodies
void PhysicsEngine::setInterpolationFactorToAllBodies() {
void DynamicsWorld::setInterpolationFactorToAllBodies() {
// Compute the interpolation factor
decimal factor = timer.computeInterpolationFactor();
assert(factor >= 0.0 && factor <= 1.0);
// Set the factor to all bodies
for (set<RigidBody*>::iterator it=world->getRigidBodiesBeginIterator(); it != world->getRigidBodiesEndIterator(); ++it) {
for (set<RigidBody*>::iterator it=getRigidBodiesBeginIterator(); it != getRigidBodiesEndIterator(); ++it) {
RigidBody* rigidBody = dynamic_cast<RigidBody*>(*it);
assert(rigidBody);
@ -196,18 +201,140 @@ void PhysicsEngine::setInterpolationFactorToAllBodies() {
}
// Apply the gravity force to all bodies of the physics world
void PhysicsEngine::applyGravity() {
void DynamicsWorld::applyGravity() {
// For each body of the physics world
for (set<RigidBody*>::iterator it=world->getRigidBodiesBeginIterator(); it != world->getRigidBodiesEndIterator(); ++it) {
for (set<RigidBody*>::iterator it=getRigidBodiesBeginIterator(); it != getRigidBodiesEndIterator(); ++it) {
RigidBody* rigidBody = dynamic_cast<RigidBody*>(*it);
assert(rigidBody);
// If the gravity force is on
if(world->getIsGravityOn()) {
if(isGravityOn) {
// Apply the current gravity force to the body
rigidBody->setExternalForce(rigidBody->getMass() * world->getGravity());
rigidBody->setExternalForce(rigidBody->getMass() * gravity);
}
}
}
// Create a rigid body into the physics world
RigidBody* DynamicsWorld::createRigidBody(const Transform& transform, decimal mass,
const Matrix3x3& inertiaTensorLocal,
CollisionShape* collisionShape) {
// Compute the body ID
bodyindex bodyID = computeNextAvailableBodyID();
// Largest index cannot be used (it is used for invalid index)
assert(bodyID < std::numeric_limits<reactphysics3d::bodyindex>::max());
// Create the rigid body
RigidBody* rigidBody = new (memoryPoolRigidBodies.allocateObject()) RigidBody(transform, mass, inertiaTensorLocal, collisionShape, bodyID);
// Add the rigid body to the physics world
bodies.insert(rigidBody);
rigidBodies.insert(rigidBody);
// Add the rigid body to the collision detection
collisionDetection.addBody(rigidBody);
// Return the pointer to the rigid body
return rigidBody;
}
// Destroy a rigid body
void DynamicsWorld::destroyRigidBody(RigidBody* rigidBody) {
// Remove the body from the collision detection
collisionDetection.removeBody(rigidBody);
// Add the body ID to the list of free IDs
freeBodiesIDs.push_back(rigidBody->getID());
// Call the constructor of the rigid body
rigidBody->RigidBody::~RigidBody();
// Remove the rigid body from the list of rigid bodies
bodies.erase(rigidBody); // TOOD : Maybe use a set to make this faster
rigidBodies.erase(rigidBody); // TOOD : Maybe use a set to make this faster
// Free the object from the memory pool
memoryPoolRigidBodies.freeObject(rigidBody);
}
// Remove all collision contacts constraints
// TODO : This method should be in the collision detection class
void DynamicsWorld::removeAllContactConstraints() {
// For all constraints
for (vector<Constraint*>::iterator it = constraints.begin(); it != constraints.end(); ) {
// Try a downcasting
Contact* contact = dynamic_cast<Contact*>(*it);
// If the constraint is a contact
if (contact) {
// Remove it from the constraints of the physics world
it = constraints.erase(it);
}
else {
++it;
}
}
}
// Remove all constraints in the physics world
void DynamicsWorld::removeAllConstraints() {
constraints.clear();
}
// Notify the world about a new broad-phase overlapping pair
void DynamicsWorld::notifyAddedOverlappingPair(const BroadPhasePair* addedPair) {
// Get the pair of body index
std::pair<bodyindex, bodyindex> indexPair = addedPair->getBodiesIndexPair();
// Add the pair into the set of overlapping pairs (if not there yet)
OverlappingPair* newPair = new (memoryPoolOverlappingPairs.allocateObject()) OverlappingPair(addedPair->body1, addedPair->body2, memoryPoolContacts);
std::pair<map<std::pair<bodyindex, bodyindex>, OverlappingPair*>::iterator, bool> check = overlappingPairs.insert(make_pair(indexPair, newPair));
assert(check.second);
}
// Notify the world about a removed broad-phase overlapping pair
void DynamicsWorld::notifyRemovedOverlappingPair(const BroadPhasePair* removedPair) {
// Get the pair of body index
std::pair<bodyindex, bodyindex> indexPair = removedPair->getBodiesIndexPair();
// Remove the overlapping pair from the memory pool
overlappingPairs[indexPair]->OverlappingPair::~OverlappingPair();
memoryPoolOverlappingPairs.freeObject(overlappingPairs[indexPair]);
overlappingPairs.erase(indexPair);
}
// Notify the world about a new narrow-phase contact
void DynamicsWorld::notifyNewContact(const BroadPhasePair* broadPhasePair, const ContactInfo* contactInfo) {
RigidBody* const rigidBody1 = dynamic_cast<RigidBody* const>(broadPhasePair->body1);
RigidBody* const rigidBody2 = dynamic_cast<RigidBody* const>(broadPhasePair->body2);
assert(rigidBody1);
assert(rigidBody2);
// Create a new contact
Contact* contact = new (memoryPoolContacts.allocateObject()) Contact(rigidBody1, rigidBody2, contactInfo);
assert(contact);
// Get the corresponding overlapping pair
pair<bodyindex, bodyindex> indexPair = broadPhasePair->getBodiesIndexPair();
OverlappingPair* overlappingPair = overlappingPairs[indexPair];
assert(overlappingPair);
// Add the contact to the contact cache of the corresponding overlapping pair
overlappingPair->addContact(contact);
// Add all the contacts in the contact cache of the two bodies
// to the set of constraints in the physics world
for (uint i=0; i<overlappingPair->getNbContacts(); i++) {
addConstraint(overlappingPair->getContact(i));
}
}

View File

@ -23,79 +23,114 @@
* *
********************************************************************************/
#ifndef PHYSICS_WORLD_H
#define PHYSICS_WORLD_H
#ifndef DYNAMICS_WORLD_H
#define DYNAMICS_WORLD_H
// Libraries
#include <vector>
#include <set>
#include <algorithm>
#include "../mathematics/mathematics.h"
#include "../body/CollisionBody.h"
#include "OverlappingPair.h"
#include "CollisionWorld.h"
#include "../collision/CollisionDetection.h"
#include "../constraint/Constraint.h"
#include "../constraint/Contact.h"
#include "../memory/MemoryPool.h"
#include "ConstraintSolver.h"
#include "../body/RigidBody.h"
#include "Timer.h"
#include "../configuration.h"
// Namespace reactphysics3d
// Namespace ReactPhysics3D
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class PhysicsWorld :
This class represents the world of the
physics engine. The physics world contains all the bodies of the physics
engine.
Class DynamicsWorld :
This class represents a dynamics world. This class inherits from
the CollisionWorld class. In a dynamics world, bodies can collide
and their movements are simulated using the laws of physics.
-------------------------------------------------------------------
*/
class PhysicsWorld {
class DynamicsWorld : public CollisionWorld {
protected :
CollisionDetection* collisionDetection; // Reference to the collision detection
std::set<CollisionBody*> bodies; // All the bodies (rigid and soft) of the physics world
std::set<RigidBody*> rigidBodies; // All the rigid bodies of the physics world
std::vector<luint> freeRigidBodyIDs; // List of free ID for rigid bodies
std::vector<Constraint*> constraints; // List that contains all the current constraints
std::map<std::pair<bodyindex, bodyindex>, OverlappingPair*> overlappingPairs; // Broad-phase overlapping pairs of bodies
Vector3 gravity; // Gravity vector of the world
bool isGravityOn; // True if the gravity force is on
bodyindex currentBodyID; // Current body ID
MemoryPool<RigidBody> memoryPoolRigidBodies; // Memory pool for rigid bodies memory allocation
Timer timer; // Timer of the physics engine
ConstraintSolver constraintSolver; // Constraint solver
bool isDeactivationActive; // True if the deactivation (sleeping) of inactive bodies is enabled
std::set<RigidBody*> rigidBodies; // All the rigid bodies of the physics world
std::vector<Constraint*> constraints; // List that contains all the current constraints
Vector3 gravity; // Gravity vector of the world
bool isGravityOn; // True if the gravity force is on
MemoryPool<OverlappingPair> memoryPoolOverlappingPairs; // Memory pool for the overlapping pairs
MemoryPool<RigidBody> memoryPoolRigidBodies; // Memory pool for rigid bodies memory allocation
MemoryPool<Contact> memoryPoolContacts; // Memory pool for the contacts
void notifyAddedOverlappingPair(const BroadPhasePair* addedPair); // Notify the world about a new broad-phase overlapping pair
void notifyRemovedOverlappingPair(const BroadPhasePair* removedPair); // Notify the world about a removed broad-phase overlapping pair
void notifyNewContact(const BroadPhasePair* pair, const ContactInfo* contactInfo); // Notify the world about a new narrow-phase contact
void updateOverlappingPair(const BroadPhasePair* pair); // Update the overlapping pair
void updateAllBodiesMotion(); // Compute the motion of all bodies and update their positions and orientations
void updatePositionAndOrientationOfBody(RigidBody* body, const Vector3& newLinVelocity, const Vector3& newAngVelocity,
const Vector3& linearVelocityErrorCorrection, const Vector3& angularVelocityErrorCorrection); // Update the position and orientation of a body
void setInterpolationFactorToAllBodies(); // Compute and set the interpolation factor to all bodies
void applyGravity(); // Apply the gravity force to all bodies
void resetBodiesMovementVariable(); // Reset the boolean movement variable of each body
virtual void updateOverlappingPair(const BroadPhasePair* pair); // Update the overlapping pair
virtual void notifyAddedOverlappingPair(const BroadPhasePair* addedPair); // Notify the world about a new broad-phase overlapping pair
virtual void notifyRemovedOverlappingPair(const BroadPhasePair* removedPair); // Notify the world about a removed broad-phase overlapping pair
virtual void notifyNewContact(const BroadPhasePair* pair,
const ContactInfo* contactInfo); // Notify the world about a new narrow-phase contact
public :
PhysicsWorld(const Vector3& gravity); // Constructor
virtual ~PhysicsWorld(); // Destructor
public :
DynamicsWorld(const Vector3& gravity, decimal timeStep); // Constructor
virtual ~DynamicsWorld(); // Destructor
Timer& getTimer() {return timer;}
void start(); // Start the physics simulation
void stop(); // Stop the physics simulation
void update(); // Update the physics simulation
void setNbLCPIterations(uint nbIterations); // Set the number of iterations of the LCP solver
void setIsErrorCorrectionActive(bool isErrorCorrectionActive); // Set the isErrorCorrectionActive value
RigidBody* createRigidBody(const Transform& transform, decimal mass,
const Matrix3x3& inertiaTensorLocal, CollisionShape* collisionShape); // Create a rigid body into the physics world
void destroyRigidBody(RigidBody* rigidBody); // Destroy a rigid body
Vector3 getGravity() const; // Return the gravity vector of the world
bool getIsGravityOn() const; // Return if the gravity is on
void setIsGratityOn(bool isGravityOn); // Set the isGravityOn attribute
void setCollisionDetection(CollisionDetection* collisionDetection); // Set the collision detection reference
void addConstraint(Constraint* constraint); // Add a constraint
void removeConstraint(Constraint* constraint); // Remove a constraint
void removeAllContactConstraints(); // Remove all collision contacts constraints
void removeAllConstraints(); // Remove all constraints and delete them (free their memory)
std::vector<Constraint*>::iterator getConstraintsBeginIterator(); // Return a start iterator on the constraint list
std::vector<Constraint*>::iterator getConstraintsEndIterator(); // Return a end iterator on the constraint list
std::set<CollisionBody*>::iterator getBodiesBeginIterator(); // Return an iterator to the beginning of the bodies of the physics world
std::set<CollisionBody*>::iterator getBodiesEndIterator(); // Return an iterator to the end of the bodies of the physics world
std::set<RigidBody*>::iterator getRigidBodiesBeginIterator(); // Return an iterator to the beginning of the rigid bodies of the physics world
std::set<RigidBody*>::iterator getRigidBodiesEndIterator(); // Return an iterator to the end of the rigid bodies of the physics world
// Friends
friend class CollisionDetection;
};
// --- Inline functions --- //
// Start the physics simulation
inline void DynamicsWorld::start() {
timer.start();
}
inline void DynamicsWorld::stop() {
std::cout << "Stop Simulation" << std::endl;
timer.stop();
}
// Set the number of iterations of the LCP solver
inline void DynamicsWorld::setNbLCPIterations(uint nbIterations) {
constraintSolver.setNbLCPIterations(nbIterations);
}
// Set the isErrorCorrectionActive value
inline void DynamicsWorld::setIsErrorCorrectionActive(bool isErrorCorrectionActive) {
constraintSolver.setIsErrorCorrectionActive(isErrorCorrectionActive);
}
// Reset the boolean movement variable of each body
inline void DynamicsWorld::resetBodiesMovementVariable() {
// For each rigid body
for (std::set<RigidBody*>::iterator it = getRigidBodiesBeginIterator(); it != getRigidBodiesEndIterator(); it++) {
// Set the hasMoved variable to false
(*it)->setHasMoved(false);
}
}
// Update the overlapping pair
inline void PhysicsWorld::updateOverlappingPair(const BroadPhasePair* pair) {
inline void DynamicsWorld::updateOverlappingPair(const BroadPhasePair* pair) {
// Get the pair of body index
std::pair<bodyindex, bodyindex> indexPair = pair->getBodiesIndexPair();
@ -109,13 +144,13 @@ inline void PhysicsWorld::updateOverlappingPair(const BroadPhasePair* pair) {
// Add a constraint into the physics world
inline void PhysicsWorld::addConstraint(Constraint* constraint) {
inline void DynamicsWorld::addConstraint(Constraint* constraint) {
assert(constraint != 0);
constraints.push_back(constraint);
}
// Remove a constraint and free its memory
inline void PhysicsWorld::removeConstraint(Constraint* constraint) {
inline void DynamicsWorld::removeConstraint(Constraint* constraint) {
std::vector<Constraint*>::iterator it;
assert(constraint);
@ -126,55 +161,40 @@ inline void PhysicsWorld::removeConstraint(Constraint* constraint) {
}
// Return the gravity vector of the world
inline Vector3 PhysicsWorld::getGravity() const {
inline Vector3 DynamicsWorld::getGravity() const {
return gravity;
}
// Return if the gravity is on
inline bool PhysicsWorld::getIsGravityOn() const {
inline bool DynamicsWorld::getIsGravityOn() const {
return isGravityOn;
}
// Set the isGravityOn attribute
inline void PhysicsWorld::setIsGratityOn(bool isGravityOn) {
inline void DynamicsWorld::setIsGratityOn(bool isGravityOn) {
this->isGravityOn = isGravityOn;
}
// Set the collision detection reference
inline void PhysicsWorld::setCollisionDetection(CollisionDetection* collisionDetection) {
this->collisionDetection = collisionDetection;
}
// Return a start iterator on the constraint list
inline std::vector<Constraint*>::iterator PhysicsWorld::getConstraintsBeginIterator() {
return constraints.begin();
}
// Return a end iterator on the constraint list
inline std::vector<Constraint*>::iterator PhysicsWorld::getConstraintsEndIterator() {
return constraints.end();
}
// Return an iterator to the beginning of the bodies of the physics world
inline std::set<CollisionBody*>::iterator PhysicsWorld::getBodiesBeginIterator() {
return bodies.begin();
}
// Return an iterator to the end of the bodies of the physics world
inline std::set<CollisionBody*>::iterator PhysicsWorld::getBodiesEndIterator() {
return bodies.end();
}
// Return an iterator to the beginning of the bodies of the physics world
inline std::set<RigidBody*>::iterator PhysicsWorld::getRigidBodiesBeginIterator() {
inline std::set<RigidBody*>::iterator DynamicsWorld::getRigidBodiesBeginIterator() {
return rigidBodies.begin();
}
// Return an iterator to the end of the bodies of the physics world
inline std::set<RigidBody*>::iterator PhysicsWorld::getRigidBodiesEndIterator() {
inline std::set<RigidBody*>::iterator DynamicsWorld::getRigidBodiesEndIterator() {
return rigidBodies.end();
}
} // End of the ReactPhysics3D namespace
// Return a start iterator on the constraint list
inline std::vector<Constraint*>::iterator DynamicsWorld::getConstraintsBeginIterator() {
return constraints.begin();
}
#endif
// Return a end iterator on the constraint list
inline std::vector<Constraint*>::iterator DynamicsWorld::getConstraintsEndIterator() {
return constraints.end();
}
}
#endif

View File

@ -1,107 +0,0 @@
/********************************************************************************
* ReactPhysics3D physics library, http://code.google.com/p/reactphysics3d/ *
* Copyright (c) 2010-2012 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
#ifndef PHYSICS_ENGINE_H
#define PHYSICS_ENGINE_H
// Libraries
#include "PhysicsWorld.h"
#include "../collision/CollisionDetection.h"
#include "ConstraintSolver.h"
#include "../body/RigidBody.h"
#include "Timer.h"
#include "../configuration.h"
// Namespace ReactPhysics3D
namespace reactphysics3d {
/* -------------------------------------------------------------------
Class PhysicsEngine :
This class represents the physics engine
of the library.
-------------------------------------------------------------------
*/
class PhysicsEngine {
private :
PhysicsWorld* world; // Pointer to the physics world of the physics engine
Timer timer; // Timer of the physics engine
CollisionDetection collisionDetection; // Collision detection
ConstraintSolver constraintSolver; // Constraint solver
bool isDeactivationActive; // True if the deactivation (sleeping) of inactive bodies is enabled
void updateAllBodiesMotion(); // Compute the motion of all bodies and update their positions and orientations
void updatePositionAndOrientationOfBody(RigidBody* body, const Vector3& newLinVelocity, const Vector3& newAngVelocity,
const Vector3& linearVelocityErrorCorrection, const Vector3& angularVelocityErrorCorrection); // Update the position and orientation of a body
void setInterpolationFactorToAllBodies(); // Compute and set the interpolation factor to all bodies
void applyGravity(); // Apply the gravity force to all bodies
void resetBodiesMovementVariable(); // Reset the boolean movement variable of each body
public :
PhysicsEngine(PhysicsWorld* world, decimal timeStep); // Constructor
~PhysicsEngine(); // Destructor
void start(); // Start the physics simulation
void stop(); // Stop the physics simulation
void update(); // Update the physics simulation
void setNbLCPIterations(uint nbIterations); // Set the number of iterations of the LCP solver
void setIsErrorCorrectionActive(bool isErrorCorrectionActive); // Set the isErrorCorrectionActive value
};
// --- Inline functions --- //
// Start the physics simulation
inline void PhysicsEngine::start() {
timer.start();
}
inline void PhysicsEngine::stop() {
timer.stop();
}
// Set the number of iterations of the LCP solver
inline void PhysicsEngine::setNbLCPIterations(uint nbIterations) {
constraintSolver.setNbLCPIterations(nbIterations);
}
// Set the isErrorCorrectionActive value
inline void PhysicsEngine::setIsErrorCorrectionActive(bool isErrorCorrectionActive) {
constraintSolver.setIsErrorCorrectionActive(isErrorCorrectionActive);
}
// Reset the boolean movement variable of each body
inline void PhysicsEngine::resetBodiesMovementVariable() {
// For each rigid body
for (std::set<RigidBody*>::iterator it = world->getRigidBodiesBeginIterator(); it != world->getRigidBodiesEndIterator(); it++) {
// Set the hasMoved variable to false
(*it)->setHasMoved(false);
}
}
}
#endif

View File

@ -1,179 +0,0 @@
/********************************************************************************
* ReactPhysics3D physics library, http://code.google.com/p/reactphysics3d/ *
* Copyright (c) 2010-2012 Daniel Chappuis *
*********************************************************************************
* *
* This software is provided 'as-is', without any express or implied warranty. *
* In no event will the authors be held liable for any damages arising from the *
* use of this software. *
* *
* Permission is granted to anyone to use this software for any purpose, *
* including commercial applications, and to alter it and redistribute it *
* freely, subject to the following restrictions: *
* *
* 1. The origin of this software must not be misrepresented; you must not claim *
* that you wrote the original software. If you use this software in a *
* product, an acknowledgment in the product documentation would be *
* appreciated but is not required. *
* *
* 2. Altered source versions must be plainly marked as such, and must not be *
* misrepresented as being the original software. *
* *
* 3. This notice may not be removed or altered from any source distribution. *
* *
********************************************************************************/
// Libraries
#include "PhysicsWorld.h"
#include "PhysicsEngine.h"
#include <algorithm>
// Namespaces
using namespace reactphysics3d;
using namespace std;
// Constructor
PhysicsWorld::PhysicsWorld(const Vector3& gravity)
: gravity(gravity), isGravityOn(true), currentBodyID(0) {
}
// Destructor
PhysicsWorld::~PhysicsWorld() {
// Delete the remaining overlapping pairs
for (map<std::pair<bodyindex, bodyindex>, OverlappingPair*>::iterator it=overlappingPairs.begin(); it != overlappingPairs.end(); it++) {
// Delete the overlapping pair
(*it).second->OverlappingPair::~OverlappingPair();
memoryPoolOverlappingPairs.freeObject((*it).second);
}
}
// Create a rigid body into the physics world
RigidBody* PhysicsWorld::createRigidBody(const Transform& transform, decimal mass, const Matrix3x3& inertiaTensorLocal, CollisionShape* collisionShape) {
// Compute the body ID
bodyindex bodyID;
if (!freeRigidBodyIDs.empty()) {
bodyID = freeRigidBodyIDs.back();
freeRigidBodyIDs.pop_back();
}
else {
bodyID = currentBodyID;
currentBodyID++;
}
// Largest index cannot be used (it is used for invalid index)
assert(bodyID < std::numeric_limits<reactphysics3d::bodyindex>::max());
// Create the rigid body
RigidBody* rigidBody = new (memoryPoolRigidBodies.allocateObject()) RigidBody(transform, mass, inertiaTensorLocal, collisionShape, bodyID);
// Add the rigid body to the physics world
bodies.insert(rigidBody);
rigidBodies.insert(rigidBody);
// Add the rigid body to the collision detection
collisionDetection->addBody(rigidBody);
// Return the pointer to the rigid body
return rigidBody;
}
// Destroy a rigid body
void PhysicsWorld::destroyRigidBody(RigidBody* rigidBody) {
// Remove the body from the collision detection
collisionDetection->removeBody(rigidBody);
// Add the body ID to the list of free IDs
freeRigidBodyIDs.push_back(rigidBody->getID());
// Call the constructor of the rigid body
rigidBody->RigidBody::~RigidBody();
// Remove the rigid body from the list of rigid bodies
bodies.erase(rigidBody); // TOOD : Maybe use a set to make this faster
rigidBodies.erase(rigidBody); // TOOD : Maybe use a set to make this faster
// Free the object from the memory pool
memoryPoolRigidBodies.freeObject(rigidBody);
}
// Remove all collision contacts constraints
// TODO : This method should be in the collision detection class
void PhysicsWorld::removeAllContactConstraints() {
// For all constraints
for (vector<Constraint*>::iterator it = constraints.begin(); it != constraints.end(); ) {
// Try a downcasting
Contact* contact = dynamic_cast<Contact*>(*it);
// If the constraint is a contact
if (contact) {
// Remove it from the constraints of the physics world
it = constraints.erase(it);
}
else {
++it;
}
}
}
// Remove all constraints in the physics world
void PhysicsWorld::removeAllConstraints() {
constraints.clear();
}
// Notify the world about a new broad-phase overlapping pair
void PhysicsWorld::notifyAddedOverlappingPair(const BroadPhasePair* addedPair) {
// Get the pair of body index
std::pair<bodyindex, bodyindex> indexPair = addedPair->getBodiesIndexPair();
// Add the pair into the set of overlapping pairs (if not there yet)
OverlappingPair* newPair = new (memoryPoolOverlappingPairs.allocateObject()) OverlappingPair(addedPair->body1, addedPair->body2, memoryPoolContacts);
std::pair<map<std::pair<bodyindex, bodyindex>, OverlappingPair*>::iterator, bool> check = overlappingPairs.insert(make_pair(indexPair, newPair));
assert(check.second);
}
// Notify the world about a removed broad-phase overlapping pair
void PhysicsWorld::notifyRemovedOverlappingPair(const BroadPhasePair* removedPair) {
// Get the pair of body index
std::pair<bodyindex, bodyindex> indexPair = removedPair->getBodiesIndexPair();
// Remove the overlapping pair from the memory pool
overlappingPairs[indexPair]->OverlappingPair::~OverlappingPair();
memoryPoolOverlappingPairs.freeObject(overlappingPairs[indexPair]);
overlappingPairs.erase(indexPair);
}
// Notify the world about a new narrow-phase contact
void PhysicsWorld::notifyNewContact(const BroadPhasePair* broadPhasePair, const ContactInfo* contactInfo) {
RigidBody* const rigidBody1 = dynamic_cast<RigidBody* const>(broadPhasePair->body1);
RigidBody* const rigidBody2 = dynamic_cast<RigidBody* const>(broadPhasePair->body2);
assert(rigidBody1);
assert(rigidBody2);
// Create a new contact
Contact* contact = new (memoryPoolContacts.allocateObject()) Contact(rigidBody1, rigidBody2, contactInfo);
assert(contact);
// Get the corresponding overlapping pair
pair<bodyindex, bodyindex> indexPair = broadPhasePair->getBodiesIndexPair();
OverlappingPair* overlappingPair = overlappingPairs[indexPair];
assert(overlappingPair);
// Add the contact to the contact cache of the corresponding overlapping pair
overlappingPair->addContact(contact);
// Add all the contacts in the contact cache of the two bodies
// to the set of constraints in the physics world
for (uint i=0; i<overlappingPair->getNbContacts(); i++) {
addConstraint(overlappingPair->getContact(i));
}
}

View File

@ -126,6 +126,7 @@ inline void Timer::start() {
// Stop the timer
inline void Timer::stop() {
std::cout << "Timer stop" << std::endl;
isRunning = false;
}

View File

@ -37,9 +37,10 @@
// Libraries
#include "configuration.h"
#include "mathematics/mathematics.h"
#include "body/CollisionBody.h"
#include "body/RigidBody.h"
#include "engine/PhysicsWorld.h"
#include "engine/PhysicsEngine.h"
#include "engine/DynamicsWorld.h"
#include "engine/CollisionWorld.h"
#include "collision/shapes/CollisionShape.h"
#include "collision/shapes/BoxShape.h"
#include "collision/shapes/SphereShape.h"